diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 000000000..ce4fc13d3 --- /dev/null +++ b/.gitattributes @@ -0,0 +1 @@ +jenkins-pipeline merge-ours \ No newline at end of file diff --git a/jenkins-pipeline b/jenkins-pipeline index 02191156e..dbe1a5c14 100644 --- a/jenkins-pipeline +++ b/jenkins-pipeline @@ -3,6 +3,8 @@ ciPipeline("--ros-distro noetic --publish-doxygen --recipes onnxruntime raisimli --dependencies 'git@github.com:leggedrobotics/hpp-fcl.git;master;git'\ 'git@github.com:leggedrobotics/pinocchio.git;master;git'\ 'git@github.com:leggedrobotics/ocs2_robotic_assets.git;main;git'\ + 'git@github.com:leggedrobotics/elevation_mapping_cupy.git;main;git'\ + 'git@github.com:ANYbotics/grid_map.git;master;git'\ --ignore ocs2_doc") node { diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/CMakeLists.txt new file mode 100644 index 000000000..a6ffc9f67 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_anymal) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/package.xml new file mode 100644 index 000000000..49817d0fd --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal/package.xml @@ -0,0 +1,22 @@ + + + ocs2_anymal + 0.0.0 + The ocs2_anymal metapackage + + Farbod Farshidian + Jan Carius + Ruben Grandia + + TODO + + catkin + + ocs2_anymal_mpc + ocs2_anymal_loopshaping_mpc + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/CMakeLists.txt new file mode 100644 index 000000000..2a627d59c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/CMakeLists.txt @@ -0,0 +1,141 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_anymal_commands) + +find_package(catkin REQUIRED COMPONENTS + roslib + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_interface + grid_map_filters_rsl +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +find_package(Boost REQUIRED COMPONENTS + filesystem +) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_interface + DEPENDS + Boost +) + +########### +## Build ## +########### + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +# Declare a C++ library +add_library(${PROJECT_NAME} + src/LoadMotions.cpp + src/ModeSequenceKeyboard.cpp + src/MotionCommandController.cpp + src/MotionCommandDummy.cpp + src/MotionCommandInterface.cpp + src/PoseCommandToCostDesiredRos.cpp + src/ReferenceExtrapolation.cpp + src/TerrainAdaptation.cpp + ) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + ) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +# Declare a C++ Executable +add_executable(target_command_node + src/AnymalPoseCommandNode.cpp + ) +add_dependencies(target_command_node + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) +target_link_libraries(target_command_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ) +target_compile_options(target_command_node PRIVATE ${OCS2_CXX_FLAGS}) + +add_executable(gait_command_node + src/AnymalGaitNode.cpp +) +add_dependencies(gait_command_node + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(gait_command_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) +target_compile_options(gait_command_node PRIVATE ${OCS2_CXX_FLAGS}) + +add_executable(motion_command_node + src/AnymalMotionCommandNode.cpp + ) +add_dependencies(motion_command_node + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) +target_link_libraries(motion_command_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ) +target_compile_options(motion_command_node PRIVATE ${OCS2_CXX_FLAGS}) + +############# +## Install ## +############# + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) +install(TARGETS target_command_node gait_command_node motion_command_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +catkin_add_gtest(test_${PROJECT_NAME} + test/testLoadMotions.cpp + test/testReferenceExtrapolation.cpp + test/testTerrainAdaptation.cpp +) +target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + -lstdc++fs + gtest_main +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/gait.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/gait.info new file mode 100644 index 000000000..4c6ea322d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/gait.info @@ -0,0 +1,255 @@ +list +{ + [0] stance + [1] trot + [2] standing_trot + [3] flying_trot + [4] pace + [5] standing_pace + [6] dynamic_walk + [7] static_walk + [8] amble + [9] lindyhop + [10] skipping + [11] pawup +} + +stance + { + modeSequence + { + [0] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 0.5 + } +} + +trot + { + modeSequence + { + [0] LF_RH + [1] RF_LH + } + switchingTimes + { + [0] 0.0 + [1] 0.35 + [2] 0.70 + } +} + +standing_trot +{ + modeSequence + { + [0] LF_RH + [1] STANCE + [2] RF_LH + [3] STANCE + } + switchingTimes + { + [0] 0.00 + [1] 0.30 + [2] 0.35 + [3] 0.65 + [4] 0.70 + } +} + +flying_trot +{ + modeSequence + { + [0] LF_RH + [1] FLY + [2] RF_LH + [3] FLY + } + switchingTimes + { + [0] 0.00 + [1] 0.27 + [2] 0.30 + [3] 0.57 + [4] 0.60 + } +} + +pace +{ + modeSequence + { + [0] LF_LH + [1] FLY + [2] RF_RH + [3] FLY + } + switchingTimes + { + [0] 0.0 + [1] 0.28 + [2] 0.30 + [3] 0.58 + [4] 0.60 + } +} + +standing_pace +{ + modeSequence + { + [0] LF_LH + [1] STANCE + [2] RF_RH + [3] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 0.30 + [2] 0.35 + [3] 0.65 + [4] 0.70 + } +} + +dynamic_walk +{ + modeSequence + { + [0] LF_RF_RH + [1] RF_RH + [2] RF_LH_RH + [3] LF_RF_LH + [4] LF_LH + [5] LF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.2 + [2] 0.3 + [3] 0.5 + [4] 0.7 + [5] 0.8 + [6] 1.0 + } +} + +static_walk +{ + modeSequence + { + [0] LF_RF_RH + [1] RF_LH_RH + [2] LF_RF_LH + [3] LF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.3 + [2] 0.6 + [3] 0.9 + [4] 1.2 + } +} + +amble +{ + modeSequence + { + [0] RF_LH + [1] LF_LH + [2] LF_RH + [3] RF_RH + } + switchingTimes + { + [0] 0.0 + [1] 0.15 + [2] 0.40 + [3] 0.55 + [4] 0.80 + } +} + +lindyhop +{ + modeSequence + { + [0] LF_RH + [1] STANCE + [2] RF_LH + [3] STANCE + [4] LF_LH + [5] RF_RH + [6] LF_LH + [7] STANCE + [8] RF_RH + [9] LF_LH + [10] RF_RH + [11] STANCE + } + switchingTimes + { + [0] 0.00 ; Step 1 + [1] 0.35 ; Stance + [2] 0.45 ; Step 2 + [3] 0.80 ; Stance + [4] 0.90 ; Tripple step + [5] 1.125 ; + [6] 1.35 ; + [7] 1.70 ; Stance + [8] 1.80 ; Tripple step + [9] 2.025 ; + [10] 2.25 ; + [11] 2.60 ; Stance + [12] 2.70 ; + } +} + +skipping +{ + modeSequence + { + [0] LF_RH + [1] FLY + [2] LF_RH + [3] FLY + [4] RF_LH + [5] FLY + [6] RF_LH + [7] FLY + } + switchingTimes + { + [0] 0.00 + [1] 0.27 + [2] 0.30 + [3] 0.57 + [4] 0.60 + [5] 0.87 + [6] 0.90 + [7] 1.17 + [8] 1.20 + } +} + +pawup +{ + modeSequence + { + [0] RF_LH_RH + } + switchingTimes + { + [0] 0.0 + [1] 2.0 + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions.info new file mode 100644 index 000000000..6ff130d35 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions.info @@ -0,0 +1,7 @@ +dt 0.05; + +motionList +{ + [0] walking + [1] demo_motion +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/demo_motion.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/demo_motion.txt new file mode 100644 index 000000000..3e787a176 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/demo_motion.txt @@ -0,0 +1,773 @@ +time,contactflag_LF,contactflag_RF,contactflag_LH,contactflag_RH,base_positionInWorld_x,base_positionInWorld_y,base_positionInWorld_z,base_quaternion_w,base_quaternion_x,base_quaternion_y,base_quaternion_z,base_linearvelocityInBase_x,base_linearvelocityInBase_y,base_linearvelocityInBase_z,base_angularvelocityInBase_x,base_angularvelocityInBase_y,base_angularvelocityInBase_z,jointAngle_LF_HAA,jointAngle_LF_HFE,jointAngle_LF_KFE,jointAngle_RF_HAA,jointAngle_RF_HFE,jointAngle_RF_KFE,jointAngle_LH_HAA,jointAngle_LH_HFE,jointAngle_LH_KFE,jointAngle_RH_HAA,jointAngle_RH_HFE,jointAngle_RH_KFE,jointVelocity_LF_HAA,jointVelocity_LF_HFE,jointVelocity_LF_KFE,jointVelocity_RF_HAA,jointVelocity_RF_HFE,jointVelocity_RF_KFE,jointVelocity_LH_HAA,jointVelocity_LH_HFE,jointVelocity_LH_KFE,jointVelocity_RH_HAA,jointVelocity_RH_HFE,jointVelocity_RH_KFE,contactForcesInWorld_LF_x,contactForcesInWorld_LF_y,contactForcesInWorld_LF_z,contactForcesInWorld_RF_x,contactForcesInWorld_RF_y,contactForcesInWorld_RF_z,contactForcesInWorld_LH_x,contactForcesInWorld_LH_y,contactForcesInWorld_LH_z,contactForcesInWorld_RH_x,contactForcesInWorld_RH_y,contactForcesInWorld_RH_z +0.0,1.0,1.0,1.0,1.0,0.0,0.0,0.5224948219166418,0.9686392881053237,-0.0002719887608139517,-0.06962544641993205,-0.23851656708025726,0.9590421056614473,-0.02401518531046548,-0.32334144936611176,-0.9600964677526755,0.3304505021822653,0.0618498292008306,-0.47825639152012367,0.9567133767893488,-1.1430208213995279,0.22296692884477007,0.6241501537404359,-0.9509366340285713,-0.33515691409521586,-1.0411140881780632,1.0521918361014952,0.363062829148687,-0.05805651874182022,1.0807684916440115,-1.5846992880879016,-1.2077918774039014,-5.907374074067523,1.496877979093471,3.08532601274583,-2.5586327312027324,-0.7367935701773651,-2.017136197227842,3.7032648753235256,2.442180031869849,2.3862900613472884,-0.08658559973872894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0166667,1.0,1.0,1.0,1.0,0.014551656083842922,-0.00792174288768983,0.5193030206395822,0.9689169713446908,-0.007400870876187361,-0.06504713141742798,-0.2385665534916191,0.9484465533242659,-0.01002001649388956,-0.31221032534398874,-0.9930597250989672,0.4146453224610035,0.05163480796037938,-0.5046680991448983,0.9365834719062212,-1.241477252879789,0.24791494505892722,0.6755723567970668,-0.9935805981697079,-0.34743683149129095,-1.0747330920364004,1.1139130407990498,0.4037659110858522,-0.01828493817636337,1.079325395428846,-1.1187348316131682,-3.6081694734640344,-4.747794146718025,1.3343334972872993,2.8590730364200274,-2.464591886072122,-0.36639434274951677,-1.2128850485739562,2.9452140968944134,1.718887010587332,1.6582682685822168,-0.006845703773797245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0333334,1.0,1.0,1.0,1.0,0.02886907960685585,-0.015353420296676988,0.5162681413254046,0.969160153984871,-0.014716561880737965,-0.05897558576436827,-0.2388177108553326,0.9489410940196215,0.02706860173539405,-0.2752929863276504,-0.9505780189958584,0.5955859798537304,0.09128509540419523,-0.515547627156218,0.8364408204625827,-1.3012809428097385,0.2674448010432465,0.7194527788926393,-1.0330898612037678,-0.3473700832798226,-1.0815436706561983,1.1503658356789155,0.42035917742739876,-0.0027807992378617555,1.080540301061838,-0.45522726843159544,-7.581338577203887,-2.077188207070302,1.004840481951709,2.6633440625041427,-2.382530959168483,0.18693988006474796,-0.12051651930412957,2.032060574516616,0.8704957766777747,0.4471912276024153,0.4665382044809246,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0500001,1.0,1.0,1.0,1.0,0.0437586559882315,-0.02223046765232581,0.5140323004218591,0.9696297588434394,-0.020468475126482782,-0.05161477104306462,-0.23819128384846955,0.9785870443476767,0.04051651791070421,-0.24658909810338547,-0.9078103856277018,0.6518382814622404,0.14106888184112126,-0.519842371774436,0.6838716805768531,-1.3107169982613462,0.2814096947800163,0.7643506697701424,-1.0729984556440546,-0.3412054896931407,-1.0787503173809727,1.181648528753642,0.4327824950081631,-0.0033785341102010188,1.0948767000140904,-0.09097604007355702,-9.723884884141903,0.5352771269914604,0.8722103289130385,2.5883993565180297,-2.1991367490686202,0.47575652118044587,0.26417822363621135,1.8547692449965767,0.9157749959157478,-0.4466588960069045,1.3575622335977402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0666668,1.0,1.0,1.0,1.0,0.058982841777320494,-0.029684187354918068,0.5116618829818796,0.9699727539058809,-0.026920320917240923,-0.04479021392423085,-0.23753313398045303,1.0236782129164634,0.04166077785762612,-0.22093503013934074,-0.8184108451481921,0.6164954654552741,0.15932266271412723,-0.518580167890406,0.512310676065527,-1.2834383362248813,0.2965185368210364,0.8057329300031973,-1.1063945661151717,-0.33151150085670633,-1.072737712256443,1.2121916008300844,0.45088507167625674,-0.017669458882018305,1.1257924660192449,0.4320400827005198,-9.766747156506334,2.487447145732958,0.8087096203310535,2.3972325508797354,-1.5985696649183514,0.5540237827859127,0.5842277908195732,1.6831548961377893,0.8506210115781784,-1.3411208374165304,2.0248440159228887,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0833335,0.0,1.0,1.0,0.0,0.07508286578665764,-0.037183286046848195,0.5100663652334587,0.9703637003343292,-0.03137489320529502,-0.038333865469046595,-0.23651727190212915,1.0749190799080868,0.04703416744317457,-0.14794033971185044,-0.6590493901515377,0.5895852796576959,0.1127636427572055,-0.5054410068817465,0.3583127909101649,-1.2278019275737713,0.30836673603835946,0.844258581281637,-1.126284217712644,-0.32273799333202474,-1.0592760187384676,1.2377538041685614,0.4611365854355032,-0.048082651432141195,1.1623716355344544,1.1226161301726776,-8.44113146455621,3.83764246936674,0.6859781493600036,2.24502084369941,-0.9688576093365094,0.5891222351127668,1.1022420868432918,1.3016706813010925,0.3764496939309414,-2.118830901188518,1.868934011669759,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1000002,0.0,1.0,1.0,0.0,0.09171657698213014,-0.04504522854571948,0.5098851202130733,0.9704558953284548,-0.035332595785846084,-0.03260229826923886,-0.23644037947196073,1.1392579472332245,0.021466489041614967,-0.06486252928755065,-0.5613583743462305,0.4792422550358558,0.056813211387863286,-0.481159555376908,0.23093906450488905,-1.155516664736492,0.31938452086491315,0.8805671077945673,-1.1386898843502293,-0.31187405374479843,-1.0359962358788608,1.2555807103181662,0.4634334199039344,-0.08829729684369565,1.1880903910038376,1.903557408023819,-6.798081766841855,5.038892664298049,0.5990219753200128,2.153608917439068,-0.4517937550551357,0.5949294181360312,1.6552369663086421,0.8689572844557125,0.07668361127894899,-2.621268953364944,1.5865500417828051,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.11666689999999999,0.0,1.0,1.0,0.0,0.10916223762233253,-0.05407090066280651,0.5109137386818587,0.9705274296445636,-0.038595999745188514,-0.028336527411379323,-0.23618615184944766,1.2031835331340073,-0.021141765246417088,-0.019414811765191525,-0.45441952222498794,0.3511543547192705,0.14448366915834226,-0.44198896637712537,0.1317096121433186,-1.0598385028376587,0.32833417515049157,0.9160456887702004,-1.1413440396673988,-0.30290697306552916,-1.004101342845715,1.2667191049142374,0.4636927109237089,-0.1354584579622362,1.2152567426972174,2.0564749070096813,-5.095584454414801,5.439157886617039,0.4806658350282076,2.115396118092661,0.031083015242585228,0.4783217622363622,1.9944497659073401,0.5203973414409333,0.12148141868506239,-3.092694948803776,1.6685651673844921,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1333336,0.0,1.0,1.0,0.0,0.12698298066812233,-0.06402534811680342,0.512221443624363,0.9709024413840485,-0.04136280516600192,-0.025035841578537874,-0.23454375775054886,1.2195566741502353,-0.02545824392576035,-0.024509257130423893,-0.3431266273920146,0.28353032697214076,0.23322011026572845,-0.4126102547115915,0.06108590965209874,-0.9742110392387316,0.3354067474102424,0.9510804527573972,-1.1376537817699421,-0.2959299631154689,-0.9695144440519651,1.2729273230593534,0.46748280862553104,-0.19138733465015142,1.2437093411543318,1.2696032743382277,-3.4243426428622215,5.281864597604189,0.4052863804633702,2.0560601804358547,0.32865589994294075,0.39057489241700666,2.1884752866379773,0.3835741022327182,0.18731664411354826,-3.9196911712386333,1.9855202767748399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1500003,0.0,1.0,1.0,0.0,0.14492627312997236,-0.07332872061714159,0.5129238196480713,0.971323962278747,-0.043136125896305076,-0.02224443618791532,-0.23275356066976782,1.2108817524127211,-0.005316588926459309,-0.03436650603913605,-0.256281415834253,0.24725386802531085,0.29536406992586506,-0.3996687725922995,0.017564629091735038,-0.8837759974598792,0.3418437481850293,0.984581165188741,-1.1303888210922408,-0.2898877839466361,-0.9311520207260967,1.2795049338936015,0.46993661154860344,-0.26611509164960206,1.2814408842910638,2.061017694727483,-1.6706629965806514,5.427346940220018,0.33190168049730034,1.8910096017953346,0.555178835954005,0.35306468501726856,2.4071425773342794,0.2774985035351553,0.20100515424123322,-5.042718416915729,2.414030253091185,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.166667,0.0,1.0,1.0,0.0,0.16287862360968386,-0.08246347970089467,0.5136489979870493,0.9719550207021176,-0.044658653526674454,-0.019824431059017128,-0.23003485459885623,1.2395381140672852,-0.010445419462631333,-0.0219678716757098,-0.2634036766779283,0.21983921633601805,0.3877224132327361,-0.34390952748616244,0.005397031721877248,-0.7932991127416017,0.3464701588869311,1.0141142322178818,-1.119147783559553,-0.28416111674391425,-0.8892761976646506,1.2821772916770922,0.47418299383391577,-0.3594782847285702,1.3241771771927215,3.4129614545619735,0.9433375558820237,3.833350524010411,0.24112054048912476,1.793536370174253,0.7753738819805163,0.3639854435533267,2.528752397952109,-0.02419439617644743,0.30770033716038814,-5.783593998056604,2.5179414657406687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1833337,0.0,1.0,1.0,0.0,0.18169590704859384,-0.09211180989169783,0.5146632957844771,0.9726846389392699,-0.04668679812889468,-0.017385201911552472,-0.22672161521687473,1.28150350842821,-0.01884153740067096,0.007753181643737736,-0.2356301784421126,0.18865675039104074,0.3839437439080869,-0.2859031632428034,0.049009277176972885,-0.7559973911028306,0.34988111560936946,1.0443658304303074,-1.1045429733346315,-0.27775491156249565,-0.8468601055441999,1.2786984524080935,0.4801933099673055,-0.45890194382442206,1.3653724343451838,1.5365511187466265,3.8416465215933484,-1.202854770359145,0.17058826014282388,1.6898001380697916,1.0970913349022395,0.41385389082702295,2.718265885090929,-0.40117300185708843,0.3245323486697318,-5.981468629331495,2.0009919222711203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2000004,0.0,1.0,1.0,0.0,0.20089685056602696,-0.1017699598391103,0.5163072654961274,0.9732815287688861,-0.047876546344312106,-0.015575438641561832,-0.22402747103550458,1.3091493246495056,-0.002629057586284511,0.02925484054823918,0.0952542177984537,0.10986169556692396,0.3563210579190911,-0.29269105442453364,0.13345217188475697,-0.8333943519438912,0.3521564455975759,1.0704410161402174,-1.0825779992567226,-0.27036595945942077,-0.7986671536105606,1.268804831536989,0.4850007604250634,-0.5588609711375286,1.3908770413345537,-0.8982270028630411,4.65290218638491,-3.9419279333974115,-0.147081593547489,1.572045401392777,1.3919355897512196,0.25270454065904885,3.2126068702149344,-0.7034742886008432,0.021343446747631414,-5.744970997079309,1.2498366127460987,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2166671,0.0,1.0,1.0,0.0,0.22088586349600045,-0.11105746917590599,0.5179002264222918,0.9741154978330447,-0.04481789282917126,-0.01566220167555944,-0.22100915999683476,1.3302504134185682,-0.004790516454043714,0.010801605350308706,0.33905236849726955,0.12716043459711668,0.3365043039445664,-0.3158441232200383,0.20410632691661568,-0.8873952516779399,0.3449783860190136,1.0967674486130934,-1.0581450275472182,-0.2693314100268913,-0.7397729956965774,1.2552492625564462,0.480904759615123,-0.6504013600584655,1.4070337380924947,-0.5067961016708619,3.4770974876419363,-2.33297498232889,-0.35865215523222466,1.518971163981396,1.2987172949550072,0.0002460730142703381,3.1553288753802233,-0.9114262481581286,-0.31128200588922816,-5.491643403134573,0.5221364780829494,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.23333379999999998,0.0,0.0,1.0,0.0,0.24081227920556425,-0.12090976215070974,0.5189099855587509,0.9748098434316869,-0.04199529891263668,-0.014507443028060691,-0.2185673766020814,1.345939812719183,-0.0452730950437209,0.005244587367106111,0.1580942685138964,0.19040447390132348,0.27115438062096686,-0.30958429159996914,0.2493556532793207,-0.911160340219853,0.3402013498463581,1.1210734895376748,-1.0392873361770694,-0.2703577570092069,-0.6934893140759615,1.238423895836635,0.4746246728099554,-0.7419161173515746,1.4082816254130839,0.04429404572808201,2.9028171439212085,-1.5563198839024965,-0.26182407677400227,1.3132742331384586,0.8991972609992407,0.10677074733226193,3.0309936741394345,-1.1831897571970165,-0.19879917102125666,-5.299675634857614,-0.5433678899708819,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2500005,1.0,0.0,1.0,0.0,0.2607985586399047,-0.13146489169583797,0.5202809074696458,0.9752653089573665,-0.04162321788190808,-0.012959410277938831,-0.21669595880564013,1.3947293447148714,-0.079488197662969,0.021696495198012946,-0.04907219948105053,0.12739065751685408,0.17583268401485996,-0.31436765207616585,0.3008670919017989,-0.9392726848960153,0.33625089933827507,1.1405433439359909,-1.028171725567426,-0.2657723779977661,-0.638739671159018,1.2158095251038952,0.47427810732780307,-0.8270575678654283,1.3889214388689393,-0.20591553594172543,3.628366735384824,-2.2021714985279393,0.06203384639384579,0.9812863334350184,0.3837797594561391,0.3028927280517015,3.545696131619528,-1.509665183192354,0.06472768438463326,-4.651423355362479,-1.7259353425100785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2666672,1.0,0.0,1.0,0.0,0.28179354844685206,-0.14283890174206199,0.5218445368333359,0.9754406864506929,-0.042371098494989295,-0.01213937602611424,-0.21580730473880078,1.398165125010227,-0.07514632574479907,0.0023616370870612833,-0.11619681441137716,0.04801655528080116,0.08704299269639595,-0.31644815652572905,0.37030145301659717,-0.9845662036488843,0.3422691488617427,1.1537830994045977,-1.026494651943214,-0.2602613125479683,-0.5752992066422351,1.188101622419211,0.47678226660462214,-0.8969638726252143,1.3507503322670584,-0.010626913461490693,3.8446651851074742,-2.2818849104011587,0.5129403094437889,0.33940135484076256,-1.2385628929939847,0.3506475835919002,3.618455288763215,-1.4834772521057695,0.07993110114576714,-3.9920741805235287,-2.4714218896904456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.28333389999999997,1.0,0.0,1.0,0.0,0.30199172111983774,-0.15329422775001283,0.5225093133723786,0.9755064628672124,-0.04335720225266126,-0.011699926670630927,-0.21533788712863214,1.3451752844470541,-0.07115171252054275,-0.03279123185542454,-0.12617795350935262,-0.05331468968881357,-0.01580536219983212,-0.3147218832333431,0.42902285438306037,-1.0153356673683813,0.35334894384908866,1.15185674505744,-1.0694572379047518,-0.25408410183486385,-0.5181242536365582,1.1663601844685527,0.4769424826947354,-0.9601269733544913,1.3065405444511318,0.21586935897217902,3.507935246519371,-1.6338828253075652,0.7512600474559262,-0.8155038013810962,-3.4670125276461308,0.3475249285145641,3.4620063500041027,-1.1096218044064354,-0.06465585019195572,-3.4441173604093995,-2.8406236868627412,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3000006,1.0,0.0,1.0,0.0,0.3214678153172463,-0.16387242049242196,0.5228053889208556,0.9752819524950428,-0.044610706818121314,-0.012566080406710487,-0.21604881762661166,1.3082418993021152,-0.09703184564635725,-0.03958397674287714,-0.20057397412688388,-0.19869990582208608,-0.12488322441354188,-0.3092524968353658,0.48723286176292596,-1.0390290734179914,0.36731120052761007,1.126599584991641,-1.1420619673322536,-0.24867712509582093,-0.45989876417500836,1.1511141549642094,0.4746270672878336,-1.011768014246685,1.256062686663388,0.47559161180919485,3.441951919633745,-1.2079463178717678,1.1300346574373439,-1.4067241878150458,-4.595928650003325,0.2936360483997069,3.5038280756953966,-1.0045275324279477,-0.08101831043318233,-2.6824757902256717,-3.2042659323474902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3166673,1.0,0.0,1.0,0.0,0.34015534538926934,-0.17466411506449916,0.5233688715312224,0.9748615889542263,-0.04730678211135816,-0.014299895874890646,-0.21726127985878443,1.2620450293593444,-0.12988576982450184,-0.0461058117432688,-0.2004930412945124,-0.3649200209048311,-0.18327821557067692,-0.2988687978002625,0.5437548145009798,-1.055600625160528,0.3910168410993106,1.104965845015326,-1.2226551659667726,-0.24429621397913706,-0.4013297508581733,1.132875866419119,0.47424186694574194,-1.0495430118603997,1.19973146642182,0.6183141267458883,3.3136001922630998,-0.6857827292275603,1.4080514681047909,-1.6614036810244388,-5.144112211806562,0.16514243101042098,3.539695251226375,-1.0420527759183436,-0.17880039950734114,-2.0029962224112103,-3.207261142189888,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.333334,1.0,0.0,1.0,0.0,0.357718823862589,-0.18568831673453431,0.5236861132252608,0.9743711092378361,-0.04914764535778207,-0.017915586999549545,-0.2187795287061295,1.2021962921943739,-0.1371864694723458,-0.0776606521689612,0.1416046130515749,-0.5144860705362709,-0.2412482639459593,-0.28864198472289443,0.5976864224117088,-1.0618885434444254,0.4142463433345343,1.071219351530581,-1.3135327173332865,-0.24317236638597817,-0.3419086864877791,1.116378992963413,0.4686670420508956,-1.0785346885268068,1.1491537681063155,0.4086291792757887,3.186181721348602,-0.261726623087445,1.2698472852502782,-3.2666407714671326,-4.806365881820391,-0.22978693369760736,3.5719730954094047,-1.0361076505291216,-0.569516535366139,-1.4126961867696175,-2.877670465326294,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3500007,1.0,0.0,1.0,0.0,0.37444376316280137,-0.19605985801408468,0.5234573210333737,0.9739383396366402,-0.04681223431319421,-0.023375997477028475,-0.22069501137629982,1.1459436515145545,-0.13128689492713957,-0.1075206512338494,0.540353565747113,-0.5369924650689303,-0.2487103795992907,-0.2852477979157909,0.6499610842913813,-1.0643248633785511,0.43334516859747224,0.9960776015237034,-1.3828676824518444,-0.2519557937548529,-0.28226374287965345,1.0983388756609715,0.4552579444657683,-1.096632978932466,1.1038089257329124,0.08113865273485067,2.9836693798854785,-0.16752681775635647,0.8066366774147539,-6.1675533896906956,-2.6289698502222456,-0.6803463000487922,3.4927150062958026,-1.0448899744603726,-0.9249343225432881,-0.5295972549923599,-2.8252325992221823,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3666674,1.0,0.0,1.0,0.0,0.3903525657268116,-0.20632015887416336,0.5230041688754227,0.9736645373752125,-0.04225695787398853,-0.0288190373092739,-0.22217376365744895,1.1096865167964032,-0.15486185781619838,-0.1061926081323597,0.7340170548351574,-0.522739694090917,-0.24210819101925068,-0.28593735755582256,0.6971422673191834,-1.0674727818714251,0.44113428635747126,0.8656338273706652,-1.4011652209386847,-0.2658506217440246,-0.2254846200969186,1.0815492574887355,0.43783583630383116,-1.0961879656663691,1.0549791597834028,-0.2169831610368114,2.6798239155541683,0.03619182502440324,0.022622873117582404,-8.772081553965998,0.3261555877545803,-0.8986451955964706,3.335841898754188,-1.0371063014466764,-1.1163152334621527,0.48280732014603606,-2.566656746166156,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3833341,1.0,0.0,1.0,1.0,0.40560650893051936,-0.2169437922402449,0.52306516466639,0.9733005062594069,-0.036719215113322524,-0.034747347496124424,-0.2238982929783686,1.0876355963984765,-0.16995681908266402,-0.08970182367055612,0.9007505058098251,-0.5426282705392127,-0.30713069428447176,-0.29248058441589536,0.7392887267981146,-1.0631184667982827,0.43409926587624986,0.7036742982527332,-1.371995807782986,-0.2819106935177483,-0.1710687905317206,1.063768596472329,0.41804736226268097,-1.0805393694071102,1.0182535297502575,-0.32270978909768616,2.3370709600987793,0.5544684176007669,-0.8196673237466867,-9.757879674440195,2.8974080137457565,-1.0965243951539034,3.1658272787211996,-0.9774885073110541,-1.1326472813484783,0.5461909021324226,-0.9799645208470472,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4000008,1.0,0.0,1.0,1.0,0.4205541775121513,-0.227371077152074,0.5233945309781264,0.9727423125534699,-0.029488652789976807,-0.04116906450372909,-0.22629167207974682,1.063232321698838,-0.1560939586392826,-0.08580879179634669,1.1169541733395807,-0.4862692299493718,-0.30871406424540904,-0.29669437203973137,0.77504478846054,-1.0489904643201717,0.41381198758809346,0.5403705210306804,-1.3045847606532919,-0.3024015080174477,-0.11995683308439338,1.0489662420791332,0.4000808514157298,-1.0779815658492282,1.0223136104241999,-0.4316622825198731,2.124212256516901,0.7988572093607348,-1.7104531432450523,-9.224017243188445,4.953900819078326,-1.2132637371843726,2.8547733300616547,-0.8184191021266337,-0.9161783105217507,0.2456385076084627,0.8892490942655764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.41666749999999997,1.0,0.0,0.0,1.0,0.4351854016403992,-0.23733919571501408,0.5237327075835806,0.9723437643410017,-0.02023666306696513,-0.047005512595473704,-0.22787839564276705,1.0553310784432215,-0.12231110346894236,-0.12573515446483075,1.433050404367095,-0.3967479785104675,-0.2714971270686667,-0.3068693559440433,0.8100959436294951,-1.0364898398957776,0.37708404707120524,0.39620644187863546,-1.2068654502203204,-0.32235289897480984,-0.07590948921144346,1.036487905173501,0.38750802416673524,-1.0723514027775942,1.0478952255090497,-0.9259938455372057,2.180418830367611,0.5824438395125993,-2.3958272106958214,-7.546148740245297,6.05282116683721,-1.5197011817864672,2.2422996264821227,-0.24540707166138476,-0.5406715458063656,0.43949694829537367,2.40642014774141,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4333342,1.0,0.0,0.0,1.0,0.45045299289505863,-0.24679826572710142,0.5228384907146865,0.9718491571518036,-0.007559621916205487,-0.05313667838538029,-0.22940915690089989,1.0879741595872738,-0.0993176898780494,-0.16835886258963234,1.5673003803623375,-0.24534852587080747,-0.2240709880060516,-0.32756089529056126,0.8477255615007158,-1.0295756308401625,0.33395092084308536,0.2888317266125878,-1.1028236515706404,-0.3530583153904087,-0.045213362715014194,1.0407859899966156,0.3820584305107479,-1.0633316382729192,1.1025277757769234,-1.2265474634408629,2.266060975145587,0.31068292897331234,-2.4776399676655307,-5.825674738753202,5.832732686580238,-1.841401972047531,1.191287727523658,1.0088345856650531,-0.41674690041111834,0.5624999686770996,2.8409588703797994,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4500009,1.0,0.0,0.0,1.0,0.46651053072389753,-0.2566621292651654,0.5219923870887098,0.9714927260007162,0.004407409466759376,-0.057011132542787335,-0.2300699650881843,1.1179581477307314,-0.08259917621281859,-0.1955106183037711,1.3718025312562576,0.013576336101089881,-0.17606026841390005,-0.34775435316190295,0.885631460538413,-1.0261337215511386,0.29449588297302304,0.2020168955418795,-1.0124406384854667,-0.383733087469859,-0.036199818874806354,1.0701157919513085,0.37361643303657127,-1.053601366321693,1.1425940439189677,-1.1217136563797259,2.258599925483482,0.04286935399790673,-2.2679377511391903,-4.741211527762414,5.831923125940969,-1.5695108140315353,-0.2839519168357134,2.6171811426387253,-0.4984993984072195,0.6141040575885781,2.335221693557659,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.46666759999999996,1.0,0.0,0.0,1.0,0.4830367330457417,-0.266052324863327,0.5203206429813605,0.9711153908376926,0.014873752888473923,-0.05816179679422873,-0.23093478418556845,1.1477320663713253,-0.05834667949668293,-0.17488494067197133,1.088462715037609,0.36096758490030845,-0.20405539470702708,-0.3649514252841292,0.9230123762568269,-1.0281466495156086,0.2583528446092623,0.13079102627307218,-0.9084258252443997,-0.4053754471588475,-0.05467844553966576,1.1280255358966493,0.3654417506638807,-1.042861462079696,1.1803686545769583,-0.876753870728109,2.093763605806206,-0.04665527649462672,-3.081818011495981,-3.5450192849263518,6.784179014709393,-0.7340324077981616,-1.3209011183150179,2.4955866511265614,-0.6191390407931843,0.9383636889257475,1.8193522555930475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4833343,1.0,0.0,0.0,1.0,0.5002584554355961,-0.27561282802283926,0.5201553866347994,0.9708093041928173,0.023615704758578035,-0.05530290922702198,-0.2321921222015111,1.215376822723385,-0.0515049234813319,-0.11133662595359023,0.68008308812433,0.6710544588924149,-0.27124334919498855,-0.3769795406364313,0.9554237203161936,-1.0276889005446446,0.19176841046862292,0.08384934970971544,-0.7863008857165527,-0.40820088333195825,-0.08022994421204817,1.1533021800279706,0.35297842373419575,-1.0223225141332555,1.203239240395553,-0.5641473153293735,1.8314905845496081,0.11185160821089732,-3.6143069086911748,-1.187116196243296,6.1788343261675225,0.20964197070000418,-2.332561859398883,1.263842090261224,-0.5720687190329244,1.4120805140378947,1.0499603362047876,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.500001,1.0,0.0,0.0,1.0,0.5186029231766268,-0.2858773411110787,0.5204192821300909,0.9704371603629195,0.028725397549308793,-0.04981691109101833,-0.23440316698316435,1.2835621554980867,-0.03201645154430577,-0.08439973428030048,0.2332748225358402,0.7949619800389172,-0.2876581958620271,-0.38375637340492935,0.9840621845078528,-1.0244182551184715,0.13787570669909588,0.0912204072572159,-0.7024642691165273,-0.39838736749271597,-0.13243066302375248,1.1701536898281628,0.3463727552248686,-0.9957920174730653,1.215367402447807,-0.36097751670466205,1.595659429369594,0.2866070989654394,-1.4198906166971423,1.0899928459418933,1.4886187903530126,0.8802229094523664,-3.8295386566828067,1.0457388725229626,-0.2681233279276303,1.7485754290420872,0.5447849254901616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5166677,1.0,0.0,0.0,1.0,0.537957327746451,-0.2960574492077765,0.5208369208967076,0.9702442293585355,0.030737988424237972,-0.0432142691722995,-0.23624952572226904,1.3356324810310634,0.018627865064910543,-0.0805528469340905,-0.17179424418358813,0.8290877768139855,-0.24413594955603046,-0.3890121485917545,1.008612474339142,-1.01813531147199,0.1444386285860104,0.12018251724063495,-0.7366801601301995,-0.37886006100201874,-0.20788148807071882,1.1881602121613275,0.3440409615950529,-0.964036549926824,1.2213987742308867,-0.11544648265453483,1.4977864084964705,0.3407781539078361,1.0966335352307655,2.5087774271369847,-3.248723179624535,1.0493711844495939,-5.253871328173193,1.6844750164709648,-0.016478457199159434,2.0167921416091383,0.25302507499720917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5333344,1.0,0.0,0.0,1.0,0.5585351864470176,-0.3057501056484003,0.5208857912362126,0.9701612033043769,0.029390032428466276,-0.03560227729401356,-0.2380250899555283,1.393223046906449,0.06462594702679603,-0.08814446420182609,-0.6063639850445591,0.8163643568386932,-0.22780677235420305,-0.387604597189846,1.033988497976829,-1.013058960603,0.17443023098235708,0.17484648874694386,-0.8107552583522237,-0.3634082580529839,-0.3075600575542808,1.226302969342196,0.34582347221966614,-0.9285654782999513,1.223801588482719,0.27868604427815574,1.5582872993797545,0.08530495027921813,0.5869573834792148,3.6225845644309875,-3.9168326194349112,1.0864341119186358,-6.0627516664784435,2.478018876465891,0.2700234517023258,2.28268942136188,0.059134499425179864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5500011,0.0,1.0,0.0,1.0,0.5802526336016578,-0.3155789962947892,0.5206290163968353,0.9701131831628936,0.02430733330736395,-0.02749023115278285,-0.23986215331354216,1.438088435477234,0.07950676094379261,-0.07604893420254562,-1.0014250493239665,0.7613821922653787,-0.2322909219634082,-0.379722595203413,1.0605554882042871,-1.0152918074423527,0.16400391383247645,0.24093557756063883,-0.8672415085668712,-0.3426455181757901,-0.4099736144701114,1.2707610065781156,0.3530417613200272,-0.8879467503687999,1.223369928154026,0.5978325847877465,1.4177289633928076,-0.38854470211253406,0.3054282690269165,3.683123282798516,-3.3628644832179706,1.3759078803588694,-6.059048435193066,2.4379664423212684,0.5459391334614314,2.5679466742543364,-0.20333821510959868,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5666677999999999,0.0,1.0,0.0,1.0,0.6022777912310451,-0.32569486386757135,0.5205154068087149,0.9699725378834879,0.01634691743368683,-0.019189983641116386,-0.2419045236661266,1.4496215698342831,0.07546899393155682,-0.0373951276725961,-1.1485933577246124,0.6877169094987576,-0.17873085401211275,-0.36767680450808216,1.0812462246051868,-1.026010476576398,0.1846111936451389,0.2976175103817799,-0.9228509653171216,-0.31754457031382954,-0.5095287426639453,1.3075686799506678,0.3640214797309894,-0.8429670846283618,1.2170236344231846,0.5982157685914963,0.5657454158746194,-0.8450054868472009,1.245446349334421,3.535079225479052,-3.214497937459255,1.351721077805578,-6.176280571985514,1.949678993092973,0.628201907958117,2.788505483888578,-0.5883302854554054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5833345,0.0,1.0,0.0,1.0,0.6241178317465027,-0.3360375458989023,0.5209039308707338,0.9699357374038243,0.008576045856664152,-0.011685732297477347,-0.2429291263003178,1.4151213401424296,0.09018529515331875,0.028166825018501936,-1.073724110823598,0.5861753561647793,-0.086512331696009,-0.3597820297026452,1.0794137064498022,-1.0434587133376252,0.20551887517338044,0.35877178741522225,-0.9743916541153755,-0.29758805880086564,-0.6158500452883333,1.335750436326481,0.3739818667987583,-0.7949963816721484,1.2037588794168268,0.13118443844000435,-0.42915382403148206,-2.207076911171495,1.0236525674928145,3.5553699314027227,-2.781886719716146,1.062834025856757,-6.168680558951449,0.8842284190255529,0.5040583620687615,2.9974259911815886,-1.0575658084834356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6000012,0.0,1.0,0.0,1.0,0.6452590542641007,-0.34529298716285434,0.5223937462219793,0.9699035087013179,0.0013827054098954632,-0.005351396280360501,-0.2434268565554604,1.367972288526808,0.11321814605084174,0.05389089239940381,-1.013727362995597,0.4215283485972991,-0.05006102976609272,-0.3633039811477861,1.0669410685272158,-1.099579854087242,0.21873301413840388,0.41613007845319944,-1.0155807081001078,-0.2821166985963359,-0.7151518392076975,1.3370430195334142,0.38082345873717227,-0.7430526850939094,1.1817713703026829,-0.06515684099218108,-1.043377123168062,-3.505206122361206,0.7757013914213748,3.3774420265845,-2.1949043966665616,0.7322421114613613,-5.606596740122585,-0.23919327525019785,0.4815819846033242,3.1115682655368655,-1.2399334566658322,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6166678999999999,0.0,1.0,0.0,1.0,0.6660724299475073,-0.3542436682286914,0.5231627965893259,0.9698043211651955,-0.0060963178497265656,-0.0007570700753272016,-0.24380697365516535,1.307963212374404,0.1012509151528927,0.04844141405987747,-0.9835859601211454,0.17311569590052805,-0.02882098666434502,-0.361953928746174,1.044634399452392,-1.1602991510967402,0.2313756399341857,0.47135341346417403,-1.0475552803312207,-0.2731799396026795,-0.8027369770655355,1.327777311205256,0.3900346317243347,-0.6912772320497018,1.162427681532402,-0.35836850703100787,-1.4240696740450127,-4.321247527767911,0.6719403523726456,3.235185054468811,-1.5094872529324534,0.382667203171464,-4.861424091042163,-0.9756382959905835,0.5112586678545595,3.224178821399781,-1.153637063580826,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6333346,0.0,1.0,0.0,1.0,0.6852731539708806,-0.3629168162047422,0.5241633048341702,0.9696994959465267,-0.013811182257708112,0.0014426166243477474,-0.24390583769760746,1.2259874170859522,0.08676228687612969,0.059031627500457526,-0.7330227369027514,-0.06322622417296686,0.03564189086412883,-0.3752496219400535,1.0194719844544038,-1.2436217264293408,0.24113107068018222,0.5239697959478301,-1.0658970504970064,-0.26936109964614025,-0.8771996330040424,1.3045216779578417,0.39786544841623545,-0.635579842768662,1.1433167246075178,-0.8477369864677864,-2.8372285294566644,-4.476693491176247,0.3548081336572757,3.0135896771216277,-0.8512618928365531,-0.12414368436947569,-4.298151846723427,-1.7838255022301066,0.3471342643849107,3.274262208234081,-1.1193937122826434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6500013,0.0,1.0,0.0,1.0,0.7034629991075001,-0.3709781263637049,0.5252112525108302,0.9698064008761622,-0.018198040122832767,0.001215170069866306,-0.2431931321337298,1.1698071957394518,0.06256704843961747,0.058568783657127275,-0.4926618517937869,-0.31858735416699513,0.16606116527407283,-0.3902118848108993,0.9500599259886011,-1.3095225659155145,0.24320260137663713,0.5718066036075401,-1.0759307335098987,-0.277318070691241,-0.9460089918331062,1.268316342209219,0.4016057970127827,-0.5821349401577519,1.1251144831633997,-0.6642646536415013,-5.632941117784104,-3.063626267352277,0.15099238205216223,2.833000529637191,-0.3001909607376257,-0.5469634476493739,-3.7496534476385395,-2.3826707595830965,0.41492129562197283,3.1703708207969865,-0.9053968830897684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.666668,0.0,1.0,0.0,1.0,0.7206598499607645,-0.37940661191534214,0.5262926923992466,0.970224364810739,-0.023060496589310305,-0.0016537570323147766,-0.24110197119130028,1.127419434136867,0.04603164007487537,0.04361593041418749,-0.3983263520881749,-0.5432437362833205,0.30281043792075796,-0.39739182134574713,0.8317069049988591,-1.3457428062495012,0.24616416014807976,0.6184033358024384,-1.075903435867658,-0.2875932510320159,-1.0021883312355568,1.2250991604603545,0.4116961859317209,-0.5299006040507077,1.1131367681447333,-0.24423831274004526,-7.956763139766521,-1.0422832173249956,0.02431488661847256,2.681937372903471,0.19773095986175399,-0.7762486033662016,-2.9637010319370627,-2.8746850587673727,0.6456274714004875,3.013988509616145,-0.42478297604724985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6833347,0.0,1.0,0.0,1.0,0.7374038466747638,-0.3871366644523686,0.5271346187900158,0.9708551081803198,-0.026830246554068224,-0.005845337969932435,-0.238088909473005,1.0908015248672496,0.058253613090446965,0.035085970701126803,-0.2345577931080088,-0.6567121440850261,0.4358015091930986,-0.3983531781847883,0.6848339575455078,-1.3442654093118955,0.24401309921824532,0.6612046948334807,-1.0693396883324429,-0.3031930758866879,-1.044799223811077,1.1724933152713026,0.4231267557679637,-0.4816684555713131,1.1109550223096263,-0.009856703437736845,-8.908915973526392,0.8630005928334435,-0.23683124620229828,2.556367914606165,0.4995665219470449,-0.9784075965596563,-2.0030428409170344,-3.2903380605084074,0.6750681275546443,2.9305768675535684,-0.16536548588997863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7000014,0.0,1.0,0.0,1.0,0.7537952111403348,-0.39442144672243096,0.5282419290074438,0.9717803325731065,-0.02950623386639273,-0.011145819868467828,-0.2337694122133694,1.0639862132752482,0.059248020428257664,0.021432699452489906,-0.18601111848880558,-0.7801255383120774,0.5544246365671975,-0.3977203787841186,0.5347424452869145,-1.3169760622883468,0.23826976948592007,0.7036157700471716,-1.0592511851649884,-0.32020690281117753,-1.0689565594689807,1.1154210057542036,0.4341985018547509,-0.4322145130937976,1.1076245742573683,0.277933604702822,-8.559494735946867,2.4621870630372915,-0.3199877760635546,2.485248859534197,0.7682353892595516,-0.9758320256719462,-0.9791941054011785,-3.3062396754241097,0.785961210980539,2.9258469326713397,-0.03740218805772013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7166681,0.0,1.0,0.0,1.0,0.7698779623818678,-0.40142692515810185,0.5290022158568529,0.9727670252733857,-0.03298407080116875,-0.017484613273257444,-0.22875894280407155,1.0492337260020543,0.05709759504334033,3.5828863655332915e-05,-0.1868584251836013,-0.8219485372782338,0.648028634802497,-0.3890887061657873,0.3995168957142965,-1.2621923430648483,0.23334681868360843,0.7440464891678779,-1.0437317908080985,-0.3357208751312212,-1.0774390926040567,1.0622851056745206,0.4493255151980624,-0.3841400294258063,1.109708280214223,0.4928250227473713,-7.389649281483796,3.6063612378969148,-0.2964386824036701,2.366918932244195,0.9784358380171041,-0.9038491469766029,-0.0460145414384631,-3.0841032997710767,1.000483501442319,2.960023522872051,-0.04112410318818336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7333348,0.0,1.0,0.0,1.0,0.7859371075941397,-0.4082468058159621,0.5298537290685286,0.9739086723725289,-0.03586614306304732,-0.02339692944928728,-0.22286341411659374,1.0334376697917902,0.036124727279916835,-0.011165913729041844,-0.33612880803441303,-0.8085224960425675,0.6903912604390862,-0.38129284517087136,0.28842030992750256,-1.1967637806010338,0.22838846030988558,0.7825132255832402,-1.026636592002029,-0.3503352679670074,-1.0704903805845656,1.0126173568216144,0.4675480186017283,-0.3335468649964944,1.1062537680761553,0.5556099860075843,-6.099061277531881,4.1496403636386265,-0.09359232929463863,2.1486217510550434,1.189804272494864,-0.6474402618816174,0.7604185123762957,-2.6286038532107177,1.298567737365792,3.028700602045053,-0.23337153492863127,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7500015,0.0,1.0,1.0,1.0,0.8014020616578816,-0.41527132614552337,0.5306804166506046,0.974801570872189,-0.04171226516743235,-0.028965518718908498,-0.21721644294357462,1.0186388614086883,0.009696055418657368,-0.03470015630547353,-0.6586369796364937,-0.8009781541458885,0.627222918185538,-0.37056833625820207,0.1962144465258153,-1.1238707209675365,0.23022706813429852,0.815667357444496,-1.0040715690713182,-0.3573022603566259,-1.0520917581636127,0.9746648019939065,0.4926111930147713,-0.2831831407775977,1.101929213491833,1.0500565227093603,-4.817870319413234,4.947995668557007,0.33328882295577394,1.9124726525957267,1.3675627089539404,-0.2807833762262558,0.6880046546213098,-0.9839665011460851,1.5595899192066898,2.959682672314279,-0.22703528094037012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7666682,0.0,1.0,1.0,1.0,0.8168126716356318,-0.42236113047656615,0.5312135681328367,0.9753247881285042,-0.049768942557702506,-0.03360751325860945,-0.21245033554068324,1.007860280937162,0.02408375303798188,-0.04750834414990228,-0.8972829967479892,-0.6402765727839382,0.6130097895523344,-0.3462908910767912,0.1278243114223735,-1.0318302617827557,0.23949810996099957,0.8462624415012746,-0.9810510771993838,-0.3596947325601077,-1.0475568462302116,0.9798184078523114,0.5195344532146126,-0.2348905786071736,1.0986859102424575,1.9282209618834998,-4.081859134069371,6.469073541543846,0.660790737399373,1.7516651288715916,1.3181036572756823,0.03528245342577159,0.3612861980525431,0.7049779290013177,1.6384128567452079,2.7795992499758198,-0.3873282859576358,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7833349,0.0,1.0,1.0,1.0,0.832294618269757,-0.42853142860639165,0.5319545857197746,0.9758600414109584,-0.05892220096912291,-0.035689439876238245,-0.207247720594648,1.0075842574720486,0.06010559065123611,-0.06319531271092563,-1.0875541118373826,-0.43067995987422725,0.6677305423441621,-0.3062941756473546,0.06015220326622729,-0.9082345049778389,0.2522534701003268,0.8740563118512243,-0.960134692621885,-0.35612617622360326,-1.040048860809448,0.998164113292479,0.547225064133802,-0.19052964713845372,1.0890182448046928,3.21498699667042,-3.070592582034272,6.6690617724934596,0.7959161309755377,1.63786721469798,1.1972625984710439,0.30587166502731006,0.6319680017431586,1.9030553145627414,1.6142531382928917,2.427513001251046,-0.30385511765202117,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8000016,0.0,1.0,1.0,0.0,0.848342271141972,-0.43426105136237014,0.5320860301081131,0.9762915437801791,-0.0693495449148156,-0.03620440748743423,-0.20182839998847166,1.047169991101769,0.08974565423745318,-0.11333472017431172,-1.2105822168295386,-0.20546990018114403,0.7228481337160061,-0.2391244435219774,0.0254710206483923,-0.8095277580955222,0.26602870072125956,0.9008581245156883,-0.9411422440995091,-0.34949899000108636,-1.0264912040409062,1.0432537118747571,0.5733429987745848,-0.153973316731272,1.0885573860637157,3.294881058833919,-1.3114521257864786,5.30923620397265,0.8405701674398146,1.6989792379947297,0.9142574951854889,0.6140225521773458,0.7226965690059101,2.497827013657644,1.6096381716576469,1.9506827956239128,-0.0005633723069394529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8166683,0.0,1.0,1.0,0.0,0.8656203507095911,-0.4399597695887038,0.5313063203911141,0.9767579730432008,-0.07976101872619899,-0.03412070720056213,-0.19600464108900661,1.101844091366856,0.10735906949895868,-0.14258050075458265,-1.0784420321000954,0.08796596054259309,0.8231154431183824,-0.19646458736082006,0.016437044976536287,-0.731259610896337,0.2802725317196651,0.9306890663829979,-0.929659381831869,-0.3356587168828549,-1.0159589269961464,1.0814251802695347,0.600879777164935,-0.12550675723880358,1.0889994656902366,1.7601052927117915,0.15506491105466022,3.680456787179407,0.724660429494735,1.7314043381891833,0.6049270437339976,0.7968494785006399,0.7201332343550267,2.0766347240729592,1.5162254963877795,1.063628665045065,0.6424367058139295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8333349999999999,0.0,1.0,1.0,0.0,0.8837208499733425,-0.44567027091231853,0.5304916522891477,0.977606533501555,-0.08709633304804987,-0.03012698321664811,-0.1891878941870227,1.1424599393174153,0.12410005610230146,-0.13149773457066807,-0.6591886225319423,0.4017738865458954,0.9377221839998696,-0.18045414975789817,0.03063986135454171,-0.6868456198257562,0.29018409668177936,0.9585717178822836,-0.9209779689799062,-0.32293728759443313,-1.0024867148868564,1.1124750077861707,0.6238839497358772,-0.11851895698785882,1.1099719857532937,0.6283409036427636,1.2343131722428178,2.2932874043532183,0.35255277109468364,1.5367065624233625,0.45781622572346814,0.6510815371865039,0.9668418871188711,1.6058406405059755,0.915686495882641,-0.3959131303005823,1.6760633636896727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8500017,0.0,1.0,1.0,0.0,0.9025728441287488,-0.4508651828878851,0.5298384366180473,0.9789608795464579,-0.08971689194389394,-0.02409693655516062,-0.18167502102988708,1.1871975643412256,0.1244029337651884,-0.11865840761577187,-0.24927255357897568,0.7111959976813998,0.9972649957225307,-0.17551984868333437,0.05758089967217503,-0.6548165445320694,0.2920243142596726,0.9819127209108808,-0.9143988104533384,-0.3139559555712023,-0.9837307996360583,1.1349533086757766,0.6314027214067894,-0.13870388797636501,1.14486835621745,-0.7132534073523763,2.8358587728573106,-1.8307792867787882,-0.011353885587194235,1.4562143516306163,0.19673094464821395,0.38879939485500736,1.20512026143323,1.0188661254308293,-0.12978932303487817,-1.7412987753842404,1.8545442808221293,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8666684,0.0,1.0,1.0,0.0,0.9221865565891192,-0.456498744059033,0.5290696248396001,0.9805245641240006,-0.08942284781783673,-0.01625455525064437,-0.17410032415590262,1.24722461837134,0.11001016202526664,-0.11253017222393755,0.08068250028348695,0.915711112589153,1.0551971196995644,-0.20422931088653787,0.12516867617370359,-0.7478717181036683,0.2898056330719472,1.0071122933509276,-0.9144202577095695,-0.30997728184597323,-0.9623159591643979,1.1464372798916067,0.6195576303154264,-0.17656236558725186,1.17179025208365,-1.7790750456945084,3.565198791516436,-4.939615886605993,-0.31203016919142074,1.562257730879654,-0.18047580509367675,0.07854358112044817,1.4217423286529745,0.4962385908117783,-0.9521380380712359,-2.9929248906213948,1.546361881704446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8833350999999999,1.0,0.0,1.0,0.0,0.9428702262036305,-0.4622315227349999,0.5281468134076581,0.9823702998302968,-0.08602465332222846,-0.007770059263863672,-0.1657949915140966,1.2987168496057522,0.10452665159192409,-0.11865486452293748,0.4447280877527502,0.9917091435877455,1.0889237332071282,-0.2348224688114877,0.176421097069309,-0.8194707367266616,0.2816232878179473,1.0339880827573846,-0.9204146826548479,-0.31133783096428197,-0.9363392938981372,1.151494628118742,0.5996647233285457,-0.2384682505254042,1.196413855365057,-1.8810588939980728,3.422511936134826,-4.7104276027989505,-0.5908926238568366,1.6489428501615142,-0.8170802683614244,-0.14718768049487552,1.5706897620574936,0.2517881691110448,-1.2360281303970178,-4.305594906702566,1.788959865924635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9000018,1.0,0.0,1.0,0.0,0.9641792169914651,-0.46798011344837875,0.5264893005153464,0.9842846029859085,-0.07953956793183774,0.00034131125271633306,-0.157661539269151,1.329780640230252,0.05177861732272626,-0.12411895908670204,0.6651153448779189,0.9590286825041051,0.9887745464330706,-0.26693139942373323,0.2392526355456602,-0.9048862855588068,0.2701091728838777,1.0620771649525014,-0.9416563211269682,-0.3148835476749811,-0.9099595290498307,1.1548302356478528,0.5783566102336505,-0.32008248285033114,1.2314223668784623,-1.8862738127645986,3.7510367148821198,-4.8708344373982015,-0.6799937694006973,1.4842194984152446,-1.7979740142219167,-0.2036975024047645,1.7013913966221075,0.12288609003515504,-1.161294660058849,-5.233208196196006,2.3702857340511727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9166685,1.0,0.0,1.0,0.0,0.9854217247592327,-0.4750203769153914,0.5248733681532834,0.9858570980111901,-0.07259291339202888,0.007537919416788137,-0.15086162864386074,1.3439265301671248,-0.04598318255034983,-0.0985376211540547,0.6906168625283848,0.8596473027825112,0.8001888246275395,-0.29769838832189516,0.30145590430116065,-0.9818322093622308,0.2589567835050061,1.0834621649858593,-0.9803472696605128,-0.31812776129094095,-0.8796261339179738,1.1555908393123198,0.5609548239069401,-0.41290887261248416,1.2754235378524783,-1.464797129845644,3.7746351025763065,-4.349004129416348,-0.5383439500389513,0.47075260953273773,-2.822017455703766,-0.16282486950155034,2.0116882618354444,-0.09906348748625046,-1.271167463843084,-5.514551709308979,2.475677988733217,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9333351999999999,1.0,0.0,1.0,0.0,1.0063576311047886,-0.4832639808800445,0.5237779647437608,0.9870415633567236,-0.06593626513439683,0.013706938362062923,-0.14564848432846889,1.3330245354897077,-0.10559142871342997,-0.049858929578443505,0.7409615355580692,0.6871348999682945,0.5792893522876809,-0.31575806807173,0.36507405727387726,-1.0498533798062937,0.2521643386596493,1.0777689499871,-1.035723757784924,-0.3203110541800241,-0.8429031195427651,1.1515281127940786,0.5359842766943834,-0.503901240797411,1.313945131548102,-0.9374045609477599,3.7750588201337587,-3.520178622579375,0.15363641266337344,-0.8146929040632083,-3.713592564401619,-0.1425648606356369,2.2869304073092565,-0.3580375174156858,-1.6478522579068824,-5.38958339862771,1.4975714394239497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9500019,1.0,0.0,1.0,0.0,1.0268715303907046,-0.4914260035381509,0.5233497895203368,0.9879320099902857,-0.05860424869971065,0.017695778481461266,-0.14227700128563106,1.3281114789155888,-0.13293078587797053,-0.014589759479361863,0.8394289786546016,0.4588031456354512,0.354802876976245,-0.3289452695137912,0.42729144997620727,-1.0991717314601182,0.2640780075028794,1.0563056805375588,-1.1041339360467377,-0.3228799328164529,-0.8033949678789715,1.1436562315292957,0.5060263054532268,-0.5925620118723011,1.3253426856713726,-0.7366965890810855,3.61313863958647,-2.624003499220448,0.9615780827916086,-1.1516436693228238,-4.359379998419634,-0.18458692338457622,2.594871019973531,-0.4862589138260706,-1.9047575104263468,-5.32728796501173,0.3096717472025644,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9666686,1.0,0.0,1.0,0.0,1.0475464884236323,-0.5000761881206236,0.5230210478794853,0.9885726214978088,-0.050922007997810693,0.019630676298037428,-0.14051959889817042,1.3163732632638299,-0.16218097482841543,-0.0059749869878454875,0.8072897616166087,0.20969776115532612,0.16969615125935975,-0.34031467015420547,0.4855122528026689,-1.1373203380472086,0.28421700552457513,1.0393807509000945,-1.1810367150242451,-0.3264639639319715,-0.7564072458855794,1.1353194499159487,0.47249223269633783,-0.6814778614503331,1.324267543766304,-0.5647878602530928,3.429784460963028,-1.9092727666550322,1.760288389668724,-1.2428924055496673,-5.136943785314031,-0.1681916885895469,2.8603140684634187,-0.45933502219725597,-1.9284178935268257,-5.10630229753242,-0.27512861944343303,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9833353,1.0,0.0,1.0,0.0,1.0674823313803852,-0.5088880516167663,0.5226508046170966,0.9889576995209416,-0.044755707206183104,0.019410860285349562,-0.1399386070164488,1.2658690184828858,-0.1527293979927835,0.019250147637273972,0.6671369659950606,-0.02107445799424293,0.08106007756825483,-0.34777156917475166,0.5416178273272723,-1.162814284300137,0.32275440451106285,1.0148758508264095,-1.2753657380201244,-0.3284863336488837,-0.708050974909253,1.1283450335003857,0.4417455804411397,-0.7627724288768682,1.3161717133480169,-0.3889498447391512,3.261174918446586,-1.3271410993104182,2.553424797859313,-2.5642887507299386,-5.233910723300567,-0.036092150657119904,3.0901163283713173,-0.5635173722272124,-1.7342925116225638,-4.587775482917815,-0.941463147806622,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.000002,1.0,0.0,1.0,0.0,1.0866901883571736,-0.5166466038486692,0.5230465199298936,0.9892710642870336,-0.03994818604489178,0.01778735453691609,-0.13939337794422188,1.2022873635798828,-0.12501697443447046,0.038523378692971046,0.632230584040234,-0.24272910096406497,0.03536133826370712,-0.3532796909088335,0.5942183008292163,-1.1815584631669624,0.36933133568153875,0.9539042882565132,-1.3555007547283122,-0.32766703802668556,-0.6534031622654469,1.1165354999405501,0.41468236668941827,-0.8344040167326258,1.2928853760752068,-0.21025958361911404,3.1423994378324362,-0.6902942175481037,3.0108019629867213,-4.549652061237318,-4.1148289354191965,-0.07142248924849394,2.9988100157905344,-0.5634218907213531,-1.6151558129820343,-4.085117671539558,-1.5869936793431747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0166686999999999,1.0,0.0,1.0,0.0,1.104891998699277,-0.5238947522736797,0.5233159725160851,0.9895243546545852,-0.03488258980640141,0.013966181805965748,-0.1393904668174541,1.1408579666490595,-0.11840001127831756,0.045146143751796305,0.7122432530584255,-0.4529192706570069,-0.010937774580324224,-0.35478023597936104,0.646364684748316,-1.185824137571355,0.4231146706640844,0.8632204788083615,-1.4125269768560267,-0.33086708805199944,-0.6080904411289008,1.1095642662482146,0.38790694566468437,-0.8989432902693649,1.263271818236999,-0.191326538617708,2.903039940027379,-0.1557165912661585,3.073360784959193,-6.947172008841256,-1.6168403583842281,-0.2381012748252109,2.935726357410438,-0.5142002896989815,-1.62209904139791,-3.59262333486482,-2.06836079709096,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0333354,1.0,0.0,1.0,0.0,1.122197598638508,-0.5308599435089036,0.5241536780672603,0.9897547246737696,-0.02925587997280774,0.008657180376821883,-0.13948021974778513,1.0896877431978254,-0.10624425247793634,0.08180987443328808,0.7883920166436634,-0.6095508206523944,0.04556592754532824,-0.359657254951193,0.690986492366125,-1.1867490265902738,0.4717769000708975,0.7223314248170041,-1.409395541130477,-0.33560376306094425,-0.5555454213033418,1.099395456003898,0.3606122905028852,-0.9541583674030087,1.223939878281455,-0.3058002741537582,2.4867109143057857,0.4871798266546664,2.2972029080897354,-8.576495399110975,1.1782649072327636,-0.34565324031013456,3.2456545949770175,-0.7504586635134237,-1.6253267130016058,-2.924189551931316,-2.601809360770012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0500021,1.0,0.0,1.0,0.0,1.1388892135850794,-0.5371883002948838,0.5259255192913207,0.9900919520383415,-0.023293581121026904,0.002094283355536651,-0.13845919819459912,1.0461948249196908,-0.08480083576310754,0.10597061557469482,0.8039561427701888,-0.7178089046434729,0.11432910324870464,-0.3649735988378379,0.7292552143392365,-1.1695847775375443,0.4996882540806028,0.5773367270716357,-1.373251401397274,-0.3423888857725533,-0.49990173825269385,1.0845489274338562,0.33372928020951664,-0.9964164702797123,1.176544666090708,-0.3553947360841837,2.2737650655168067,1.0659004479342649,0.9587691470080475,-8.1363097381977,2.953474340726314,-0.3686457466067308,3.2378062884845926,-0.889529252247339,-1.5215267811479818,-2.1681153257581474,-2.9155266916957525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0666688,1.0,0.0,1.0,0.0,1.1549961177540653,-0.5429790707002196,0.5278945226741002,0.9903531272438447,-0.017641880986023376,-0.004999279851928861,-0.13734793261849376,1.0103613134822844,-0.04090971454847436,0.09974702232732242,0.8528280153190039,-0.8026375077398481,0.17208550576721568,-0.3715037698469815,0.7667788128010229,-1.1512189405991018,0.5037359355557756,0.4511205577897649,-1.3109461995413105,-0.34789197919088505,-0.4476183291667695,1.0697444216270366,0.30989462969616705,-1.0264290228026354,1.1267554608564838,-0.4535269335078723,2.063779535771046,1.397043972802374,-0.5871133270419012,-6.865524732631344,4.842431225021326,-0.4709137170658942,3.188498405627151,-0.8894978262663039,-1.3985642344045246,-1.3613781190272147,-2.824825971336186,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0833355,1.0,0.0,1.0,0.0,1.1709076151805313,-0.5475351453987254,0.5297906722864436,0.9906555183061226,-0.01107396334268871,-0.013059495728108193,-0.13530876156716462,0.9908746190488307,0.008419938458976345,0.08355818073568382,0.9919957914288196,-0.8378830134361948,0.2718402842788137,-0.38009119352322923,0.798048003116907,-1.1230165519745336,0.4801177707049843,0.3484854449489421,-1.2118367044011482,-0.35808604106899755,-0.3936182454985618,1.054898940591791,0.28711037915841686,-1.041795831672494,1.0823836120577703,-0.6181680247528838,1.848842150385195,1.7432734326049386,-1.6693413052250583,-5.49322602589697,6.644630553641786,-0.6964027523888073,3.0954132480914622,-0.6483918253780748,-1.3067296833817936,-0.4572746554466343,-2.532418164745652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1000022,1.0,0.0,1.0,0.0,1.1868162455539768,-0.5514830049007771,0.5316266123584805,0.9909579157500585,-0.0032185094092883992,-0.021022508461144992,-0.13247680758337801,0.9806859550703733,0.01769709613752557,0.07101922298236538,1.019110250101072,-0.7483114517508468,0.32478333174976876,-0.3921094118832793,0.8284070077366728,-1.0931097099607083,0.4480911140921866,0.26801265737813085,-1.0894580714445474,-0.3711054506973621,-0.3444376812028376,1.0481313175549791,0.26633688646812836,-1.0416715418025002,1.042341353203751,-0.6884414955572603,1.5904114472120896,1.8472133513171782,-1.2659628048488558,-4.393337177671926,5.880433368747343,-0.8532238499244943,2.8598469162982125,-0.49904588248889753,-1.0177284690913584,0.44021152242034034,-2.2163013456904905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1166689,1.0,0.0,1.0,0.0,1.2024792555572115,-0.5555161602386076,0.5335452489861175,0.9911799355102228,0.003986790010007661,-0.02765388969259343,-0.12954421381226083,0.9630666389293807,0.009213540038121998,0.08194739693470726,0.9848226023265514,-0.5746754933449709,0.3827100988199127,-0.4030392892712376,0.8510618240514065,-1.0614426504497376,0.43791892614583544,0.20204057947073276,-1.0158218667473455,-0.3865268929480707,-0.29828982429882694,1.0382640445724356,0.253186029006807,-1.0271220849110478,1.008506752781331,-0.719645303823255,1.3354680603282403,1.8100600526552342,-0.5199682375310779,-3.707701144059255,4.796649710439351,-0.9035316125862081,2.6304081857855683,-0.6988441154298252,-0.7980102396275611,1.2523315492617222,-1.7503434211584095,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1333355999999999,1.0,0.0,1.0,1.0,1.2177182037383436,-0.5594392709847668,0.536085247268219,0.991458841594902,0.011622466776804143,-0.032672727417268344,-0.12572500376788165,0.9511482143398798,-0.0006858261546837385,0.0950970088109648,1.0706780008181698,-0.40158604373595047,0.40594820227952777,-0.4160976366537414,0.8729226987788181,-1.0327742542015304,0.4307588048432682,0.14442237206274608,-0.9295694279865884,-0.4012232313523432,-0.2567572329827729,1.0248364671177106,0.23973649194652702,-0.9999270733383395,0.9839964558089094,-0.8231844541583495,1.2565158247840646,1.6797687411023559,-2.379299471694727,-2.3790639809633047,5.850320660741226,-0.9082723574127876,2.34956601561388,-0.7779832023561027,-0.8733804342493767,1.298535937084202,-0.47971240743262783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1500023,1.0,0.0,0.0,1.0,1.2328939453285366,-0.5635135152476625,0.5386682423679349,0.9916018236454692,0.020614136939066458,-0.03660326767023715,-0.1223154998236046,0.9822321119797897,0.0020841223015007626,0.03172352297974994,1.0503647295985565,-0.2809934079537693,0.4443896015151556,-0.43047882595547954,0.8929457686452636,-1.0054502470950764,0.35860878513604644,0.12273828816769053,-0.820810788034594,-0.4168026987466541,-0.21997080047396325,1.0123312192950187,0.2240732896397988,-0.9838374671058453,0.9925163072194162,-0.818967108800936,1.3014996262966485,1.523073734626242,-3.7478271465751125,-0.17185125059792639,5.582066633773474,-0.8685743543914592,1.9864989163532327,-0.41163066366289924,-0.6143797954028404,0.9736949452323951,1.3198609895984799,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.166669,1.0,0.0,0.0,1.0,1.249326573166838,-0.5673973408813525,0.5393540570210763,0.9918433778902187,0.0281302790511131,-0.03962554287645899,-0.11783555273164921,1.0500606967915862,0.006704828044426431,-0.09473898909865572,0.8432825783921938,-0.217693285036861,0.537822731028456,-0.4433965948782465,0.9163061064220148,-0.98200502817574,0.3058309834356213,0.13869398558606516,-0.7435001680563637,-0.4301757677370155,-0.19054047000440408,1.0111154175535697,0.21925712447444598,-0.96747051025093,1.0279919101195913,-0.7606402710635435,1.6123056654151418,1.0981162556302662,-2.3211371379446537,1.0756372370859655,3.391595589869888,-0.7058199352167794,1.4559881824551877,0.6425617882694977,-0.09807186870153885,0.8709254649801914,2.377139646458389,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1833357,1.0,0.0,0.0,1.0,1.2671350062930014,-0.5714095819677494,0.5380590249657818,0.9921302869697806,0.033768163194706345,-0.04212190442663018,-0.11297322691323979,1.0951180775802072,0.0062863905022850775,-0.21150409346416038,0.4831512569301504,-0.05672134351874064,0.6396146665932373,-0.45583355236694906,0.9466893983128127,-0.9688462986996504,0.2812373924620821,0.15859293444637185,-0.707757375599225,-0.4403300769752091,-0.1714377639929115,1.0337499884081212,0.22080422081162293,-0.9548065602114746,1.0717544539106723,-0.6333678463074048,1.987941102216846,0.35634533035728966,-0.7693551243374891,2.746555009719994,-1.0265384146254868,-0.3632388726078867,0.4729436971108262,2.1020513791330573,0.135687486580645,0.680399029024374,2.5237303481918856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2000024,1.0,0.0,0.0,1.0,1.2854586759014517,-0.575075212512071,0.5351335547324095,0.9927469359402779,0.0355474993656413,-0.041859095411823796,-0.10694724213996078,1.1000786277574337,0.011188401520536378,-0.24719151654454674,0.00542000992886855,0.25850592550080403,0.746854586593515,-0.46450889864634975,0.9825709423586498,-0.9701268267408083,0.28018576133403006,0.2302460023470656,-0.7777181836464409,-0.4422837543732032,-0.17477564857113007,1.0811839369947636,0.22378004973963325,-0.9447904972568489,1.1121164233080107,-0.35748496067333685,1.9957884698187816,-0.2999895724674243,-0.4476963669786209,3.503326795265782,-3.245218696958339,0.503794372238008,-0.9075119866126129,2.917472432025908,0.23999319094618984,0.8598514753308512,2.1030738426214106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2166691,1.0,0.0,0.0,1.0,1.3036625824399937,-0.5784339398138703,0.5326674658273403,0.9936298530224209,0.03377750818201896,-0.038318890424447055,-0.10045127057581225,1.1153483834572573,0.02157046363130144,-0.1986427938791493,-0.3790073208914732,0.5657328386671564,0.7508893648496938,-0.46774974155505766,1.01321581369267,-0.9788459711145361,0.26631415038303696,0.27537072784368427,-0.8159315485124161,-0.4235368976476507,-0.20168822404746437,1.1309992639738136,0.22880400984270866,-0.9261447870436812,1.1418570555363088,-0.09649233667633028,1.679337982847286,-0.7820797808965397,-0.16429174904314847,2.8862685047061567,-2.7645827753631838,1.5352171590010826,-2.3463300525716826,2.693772812075722,0.43778929749425427,1.2834970343452021,1.3074712982524332,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2333357999999999,0.0,1.0,0.0,1.0,1.3224683795281647,-0.5814967457484033,0.5311792925910859,0.9945635696852113,0.029720135209172174,-0.03229378956990523,-0.09443055953118715,1.1305393557227688,0.03839736697095808,-0.16027345325249215,-0.6838506624673881,0.7415299914681115,0.672956174417514,-0.46772531630171654,1.0385489870760916,-0.996196204909345,0.2747093587464752,0.3264551449218378,-0.869871127130732,-0.39110974672535653,-0.252986806745523,1.1709765436488084,0.23837305550872823,-0.9020071772122066,1.1556988870811784,0.024051128931946587,1.4674210582356024,-1.6297025905306264,0.6015516963925646,3.0207123300172793,-3.3094358711585135,1.9797427592853498,-3.765985270355165,2.1119591709617103,0.7625061577630763,1.4920334867945728,0.6261418043518733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2500025,0.0,1.0,0.0,1.0,1.3412077447846564,-0.584046689676753,0.5296382681491112,0.9954135123623664,0.023235375673255176,-0.0253023689373715,-0.0892851995007957,1.113649737208392,0.07331825482546599,-0.14136969535369598,-0.861499518143566,0.7498620589765678,0.6291692775550382,-0.4669480356539175,1.0621299467952607,-1.0331694994457297,0.2863659136995689,0.37606134022508225,-0.9262462981800913,-0.3575453403552884,-0.3272213174583212,1.2013980438031486,0.2542209326018884,-0.876410238014963,1.1627284907574915,0.26990926099750134,0.7877964511857165,-2.7386829548941107,0.5547419136919531,3.0006372781105464,-3.2796464515230666,1.6621031432335114,-5.154142798172274,2.2546463192555874,0.9109901585050386,1.61532513989989,0.2829650934579344,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2666692,0.0,1.0,0.0,1.0,1.3596391888413064,-0.5855398016103714,0.5283180714795941,0.9961500385651172,0.01628157457403454,-0.01881727560583451,-0.0840590336304189,1.0932471517721045,0.1037764124245474,-0.1149635529637997,-0.8386884369807388,0.6268413876766228,0.6023991067789753,-0.45872832294118243,1.0648089213020455,-1.0874858193180124,0.2932007928523345,0.4264765875680079,-0.979192894157931,-0.3357061978106966,-0.42479191029411867,1.2461315712670826,0.2687394548582401,-0.8481628981938676,1.1651310757274491,0.6564875391229729,-0.529757861440744,-3.67654068277284,0.38632511347334053,3.0143637042826175,-2.9195634599711515,1.0827825931845778,-6.083791370443414,2.972025508593411,0.7966676058380877,1.7849822137119875,0.09567753463205739,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2833359,0.0,1.0,0.0,1.0,1.377839947969661,-0.5866512472137313,0.527200476180352,0.9966981555985237,0.010005383492891769,-0.013884458780396989,-0.07937191400008337,1.093209974882769,0.09840341125280058,-0.1058400279500528,-0.8614201373481752,0.3951949600592686,0.5617927541678059,-0.4450650739173158,1.0444713160967118,-1.1557211006408699,0.2992434432370211,0.47654033132541646,-1.0235652748166937,-0.3214525150636296,-0.5300147687258597,1.3004657588912962,0.2807765725743317,-0.8169107118924158,1.1659177482903957,1.1204968564030766,-1.3293131291553726,-3.6824730260842706,0.27652123977278403,2.9836901067169195,-2.2544769840863053,0.7379031391744723,-6.1033981598840015,3.035597402732876,0.7937731687571355,1.9551110426743243,0.14170471704147497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3000026,0.0,1.0,0.0,1.0,1.3962277197454203,-0.5880147917315677,0.525815472123127,0.9971297127406586,0.002374787104383889,-0.011214072277430527,-0.07483943438386634,1.0851800307226565,0.10568446247122082,-0.09364408510569507,-0.8933620754984253,0.17075251280047316,0.5666081477720086,-0.4213783530279561,1.0204983950426578,-1.2102351656856898,0.30241818594617664,0.5259331233712456,-1.0543422772592734,-0.31110937731133825,-0.628238922516796,1.3473183537313387,0.2951986134016892,-0.7829923997639873,1.1698545757424794,1.0011796182177062,-2.0830247857760127,-3.751647274526321,0.16699365790056797,2.825935783487923,-1.5883533400047445,0.5850459841814998,-5.917851296177751,2.26318597358432,0.806801615793748,2.112606440264748,0.1590087347656694,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3166693,0.0,1.0,0.0,1.0,1.414194895886127,-0.5885590638910123,0.5248985187164996,0.9974786417232567,-0.004727058729928971,-0.00995109609961544,-0.07010698901041784,1.0614389770359145,0.1356898832197106,-0.07271179056450836,-0.890853039526786,-0.0025987049758976477,0.6470867358264553,-0.41169235323141773,0.9750370177025257,-1.2807762599015655,0.3048099096332839,0.5707383791707328,-1.0765104920404078,-0.301950943254514,-0.7272768731218712,1.3759054422231718,0.307670013554231,-0.7464903563764949,1.1712180500498337,1.290789726434817,-4.257576129580408,-3.080446655985435,0.14945879744505475,2.7660497881049797,-1.2129132098680317,0.4536254548399546,-5.727407156997925,0.7754871054082817,0.9079779850444702,2.2284048016033533,0.10053978380391554,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.333336,0.0,1.0,0.0,1.0,1.4319338088971678,-0.588507813649288,0.5240818290529735,0.9978054457667208,-0.012537010918620636,-0.010160452209547985,-0.06421745063765417,1.0416617094135454,0.1602280415954668,-0.033625279941470104,-0.8545862204235817,-0.13039186014909426,0.7427241371017569,-0.3783519427608138,0.8785789068849023,-1.3129169262483147,0.30740015582493163,0.6181349673780642,-1.0947727984490885,-0.2959884985749761,-0.8191528762438707,1.373167975610755,0.3254646067683705,-0.708712091150222,1.1732059085719289,1.7319321158212897,-6.913165090595292,-1.520494175270521,0.10758368762328807,2.7129545334884173,-0.7773861749893616,0.2443719815149476,-5.166259154281525,-0.7622881944482247,0.9567468139480862,2.3682830922260383,-0.09564225901043465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3500026999999999,0.0,1.0,0.0,1.0,1.4493302143281694,-0.5877342536125982,0.5244115479650737,0.9980785468764254,-0.01920025367057188,-0.011039401113303357,-0.05786791984414494,1.0533220201610085,0.19116754164227912,-0.005341249866316334,-0.7388766464274409,-0.2401895824887692,0.9668054344635326,-0.35396116724190035,0.7445977204716766,-1.331459500443528,0.308396039726306,0.6611703778173156,-1.1024234163657982,-0.29380519424588364,-0.8994858560151989,1.3504957849223513,0.33956163780228815,-0.6675474287500874,1.1680299683733353,1.3079687295780331,-8.184561864691444,-0.2463655164510756,-0.1765808293114409,2.602721596238163,-0.2796799776701894,0.08329713509046141,-4.170008395229922,-2.0080747050143564,0.88737224213967,2.6120791219777506,-0.30564028213966943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3666694,0.0,1.0,0.0,1.0,1.4675432158558466,-0.5862308628904533,0.5245196119715562,0.9984336672505146,-0.025232224210681765,-0.013107381949061442,-0.048184473645687564,1.087291512594558,0.20919954183331352,-0.00011194818279275723,-0.6007590887970846,-0.3574826730645387,1.2635904624494543,-0.3347528979102974,0.6057596324243965,-1.321129126554385,0.30151411640916165,0.7048925274341094,-1.10409548301676,-0.2932119218521517,-0.9581534340854277,1.3062320182386296,0.355043740664509,-0.6216426129456889,1.1630178787912544,0.999632828659567,-7.855316139174225,0.7496377795040312,-0.6038409554201027,2.5042406416681393,0.24268243331089626,-0.3846935280275723,-3.183372640228484,-2.9713709565447197,0.9699991552048959,2.8771280226620473,-0.4140008836812157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3833361,0.0,1.0,0.0,1.0,1.4860682505995273,-0.5842656418609071,0.5251020221711159,0.9987516880560106,-0.02975580523826648,-0.015949273289089513,-0.03681410519680775,1.0931848275770897,0.19226976456684874,0.027679161751573415,-0.5063216295654145,-0.4423545235401528,1.438717875909421,-0.32064000631105954,0.4827533254781265,-1.3064715244842082,0.2882679676229056,0.7446452328222963,-1.0943339857432728,-0.3066283374930379,-1.005598489580991,1.2514498882794636,0.371895007642395,-0.5716429695194843,1.1542299113172358,0.7117323300090489,-6.875496195852077,1.4385585185309666,-0.705436678436018,2.3758180344194137,0.7407324101570251,-0.8594522810973675,-2.4469838336313603,-3.5954169113004655,1.1594297651742327,2.916825521939341,-0.3005522549611313,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4000028,0.0,1.0,0.0,1.0,1.5043154774830112,-0.582439699990089,0.5263074938893069,0.9989303125042333,-0.034309714647142525,-0.01944070192387204,-0.02414815416825518,1.1011492844609243,0.1786479359786357,0.04896166012542203,-0.43949888077421495,-0.485368171180926,1.5453042527005936,-0.31102843946117376,0.37657596752958084,-1.2731770800327848,0.2779995134321825,0.7840866203026254,-1.0794043532960318,-0.3218603885188827,-1.0397197250053953,1.1863845481674866,0.39369147679896777,-0.5244149010926761,1.152999450255733,0.5650298442517633,-5.841551104910638,2.5955059536371405,-0.6795487286366881,2.2416752841317216,1.11061725845432,-0.9009909820390806,-1.4300442532328201,-4.007704380838177,1.3004971475854352,2.8686288174998515,-0.15570531825073475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4166695,0.0,1.0,0.0,1.0,1.5229373012037999,-0.5799401173442612,0.5278128469553413,0.9989628130033334,-0.03777020937682576,-0.022953105233341736,-0.010948263800487015,1.1155491349903492,0.15385105594577675,0.03976329394696199,-0.4193799405688917,-0.4561632228393185,1.5761185970419227,-0.3018056405006778,0.2880345658776982,-1.21995448632924,0.2656162980317674,0.8193678917383727,-1.0573133364203116,-0.3366614302937394,-1.053266726691702,1.1178594750712323,0.41524499926171937,-0.4760218176942348,1.1490397236618568,0.5839075267806665,-4.849417542583713,3.2999968429931528,-0.6182592579386942,2.0117402775991224,1.4357175204969552,-0.974263984435021,-0.3930381604254861,-4.170692045191579,1.4061486201729465,2.879228879729668,-0.38830015003562046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4333362,0.0,1.0,0.0,1.0,1.5415138095295442,-0.57797539995607,0.528979348154797,0.9987780635332234,-0.04198428597632606,-0.025976800257274994,0.002214810212181238,1.0925560699184682,0.10146970592427307,0.014547438666740388,-0.5687406781313803,-0.36360756798909716,1.5378129412151456,-0.2915648163079831,0.2149283928156209,-1.163176965266557,0.2573908302836088,0.851144763671948,-1.0315470068982986,-0.35433591961764904,-1.0528210232221222,1.0473612019482976,0.44056319121464066,-0.42844041315309517,1.1400560860345357,0.32002923480702156,-3.779188242001857,3.61735867004172,-0.2679852220048602,1.8180946852335924,1.4907388897171456,-1.0640846340000454,0.022099170114935653,-3.7331582969688193,1.675456530442398,2.873645169292715,-0.6151618143796287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4500028999999999,0.0,1.0,0.0,1.0,1.5592735632985948,-0.5762885710228797,0.5298943399173134,0.9983527627287613,-0.047901020168082474,-0.027976279478533282,0.014648590554922885,1.0508526818097637,0.060858447123063236,0.01569973543214012,-0.8700637058196837,-0.2950657205057168,1.5142977115582446,-0.29113797800516145,0.1620613725317535,-1.0993756228372713,0.2566834394325906,0.8799711691191381,-1.007621940713814,-0.3721309890327165,-1.0525300862145928,0.9934206162950519,0.471093661973568,-0.380233453808133,1.128534288838415,0.8545225586960534,-3.119750302815329,4.961824600779213,0.2703791195211744,1.546275568956564,1.5274874440887591,-0.7222732512377872,0.3015188738514239,-2.880955614589311,2.0220865136204225,2.7819091084326617,-0.8154107275048335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4666696,0.0,1.0,0.0,1.0,1.5763885723136772,-0.5747889083540519,0.5312113121467121,0.9975484053066035,-0.057094433852066515,-0.029929060979771605,0.027233361934095864,1.0213368490362473,0.03888459003403277,0.030908252066284003,-1.099813874807743,-0.2754245003809184,1.4906554656693534,-0.26308067404994406,0.11093650807175641,-0.9977824811189431,0.26640348562625593,0.9026873857222047,-0.9806306569295103,-0.3784117428104587,-1.0427703739924832,0.9513291560649463,0.5079662098077556,-0.3357099240780659,1.112875674090326,2.7249515262019557,-2.1429270508087375,5.720225993110148,0.6528770251953482,1.3179334290673084,1.571606500749015,-0.19676643793688706,0.6910344831827859,-1.6864613594921696,2.22675341116469,2.645801736470545,-1.030588930800114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4833363,0.0,1.0,1.0,1.0,1.5930759856092334,-0.5729210069073284,0.5326932792107181,0.99649549206207,-0.06680585775154724,-0.03164899427357018,0.039141446466943036,1.0048406339659988,0.0373984021139875,0.02222122204082909,-1.144552344208767,-0.28278409898183077,1.4924258716732186,-0.20030607880166118,0.09063032797632554,-0.9087010417185335,0.2784460504642372,0.9239023712836103,-0.9552349525817468,-0.37868988341504195,-1.0294955573728677,0.9372051252145556,0.5453189241292851,-0.29203988620566573,1.0941812557724824,2.842711950005954,-0.6542066132759948,4.921182603481123,0.6336294226296512,1.2805970267763322,1.6907712951964637,0.0348891996748633,0.8128687165480057,-0.17521235591784498,2.2017323566326814,2.552092639249836,-1.0060593078200069,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.500003,0.0,1.0,1.0,0.0,1.6095710250377875,-0.5707059384484366,0.533712409331998,0.9951404385966941,-0.07670176938935729,-0.03370571280064775,0.05173268760388772,1.0004183551042674,0.03929409746597312,-0.05477156588715872,-1.0502288882170874,-0.3249318803217456,1.5669046830994648,-0.1683234195356156,0.08912957734878237,-0.8337427329240654,0.28752450862253914,0.9453740386545509,-0.9242715010382085,-0.3772487671620166,-1.0156746959163019,0.9454887325201944,0.5813574351443355,-0.2506399992968954,1.0793402967590386,1.2890670939426987,0.604592221034004,3.602098135903994,0.4834018808122058,1.3211993693858726,1.5908593452906796,0.045662712587820446,0.8529731823737391,1.5800223450354338,2.1112323915393842,2.277117273128756,-0.49045784488784716,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5166697,0.0,1.0,1.0,0.0,1.626177944390161,-0.5683000140868535,0.532661090888293,0.9936274335721329,-0.08482390070508122,-0.035912120053223334,0.06495959325083617,1.0218902754526176,0.07404838321329206,-0.14169905487955567,-0.7278269043870778,-0.2919085112083286,1.6251634596050506,-0.15733708973243163,0.11078344231694041,-0.7886308637151913,0.2945594787181028,0.9679424383430973,-0.9022062016814345,-0.3771677899512671,-1.001063061095531,0.9898726420505597,0.615693477929424,-0.21613582529355566,1.0778326282456978,0.2776591837215783,1.9305900003077683,1.6613253776331265,0.26376813725815146,1.5320181659809133,0.9839286502944743,0.12036869756443902,0.6846704752986321,2.5783394657883343,1.928718029706028,1.7528054377138251,0.2958231408054017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5333364,0.0,1.0,1.0,0.0,1.6433443084141508,-0.5644633876952687,0.530697243843296,0.9921963012856071,-0.08942877611866012,-0.03698063954352758,0.07862204535644632,1.036869686918069,0.08482657463250615,-0.18513950559285913,-0.44629832989030377,-0.10299021344733318,1.6526644839098452,-0.15906809490095075,0.15348270606504133,-0.7783651095812694,0.29631679744902,0.9964414129884591,-0.8914738137664827,-0.37323646921862214,-0.9928523010949825,1.0314335532691032,0.6456481647157384,-0.19221303451940538,1.0892010878407614,-1.5575794042942264,3.0631314370415357,-1.825816497075828,0.07375756060954587,1.7953143526505313,0.26260096321933485,0.3445657485883255,0.40791828337725144,2.3440737294017304,1.6693232184324605,0.6376475457651976,1.4300183833984665,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5500030999999999,1.0,0.0,1.0,0.0,1.660335728542911,-0.5609910026790459,0.5281374346917551,0.9907368516744901,-0.09311964040600738,-0.03572510293918637,0.0921571501553723,1.0379945533924946,0.06710384127576463,-0.2125936639910187,0.028656357869992682,0.15162018979338326,1.6807971602603393,-0.2092565070475328,0.21288802776042073,-0.8494915353388187,0.297018068988925,1.0277863697857386,-0.8934528187340591,-0.365682242027273,-0.9874657577884036,1.0680085893021993,0.6713376964987205,-0.19488086459154602,1.1255000030268723,-2.615969049115157,3.075628639378179,-3.670904844440535,-0.3565376002176752,1.8695528315797303,-0.5364644272808184,0.17626473613955584,0.4812233569624175,2.1736783981599666,0.6491490486453029,-0.9159337891128863,2.498172316168178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5666698,1.0,0.0,1.0,0.0,1.6774978618208667,-0.5570158779520442,0.5251797320878755,0.9897410011373966,-0.09022514258287867,-0.03173290252111723,0.10613763334005684,1.0505146298370303,0.041421329158630615,-0.1908707624377563,0.689884601759184,0.397522429460817,1.730678019817875,-0.24626723760272592,0.2560038657528899,-0.9007288491229435,0.28443218700592415,1.058759965344639,-0.9093559971068051,-0.36736096626298786,-0.9768114904480114,1.1038896447863287,0.6672865096138517,-0.22274422188542087,1.1724736649245218,-2.1275166142108133,2.6703645570172823,-3.157084882683712,-0.8367933077676253,1.654878095417534,-1.7003804743945934,-0.2830995951059685,0.7723804209002002,1.658965835284013,-0.9693271361662873,-2.162478005620321,2.3371241587251546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5833365,1.0,0.0,1.0,0.0,1.694732805905272,-0.553199783874335,0.5231644957551066,0.9888864430792115,-0.08338813685713388,-0.025289826139956118,0.1204593127136802,1.0685328482293057,-0.01131387278786905,-0.1667932497426162,0.9807556894452603,0.5567467624888058,1.7022663718007938,-0.2801738693556675,0.3019003576853006,-0.954727908567268,0.26912490294378366,1.0829490832915294,-0.9501322812392439,-0.3751189140707783,-0.9617196922663689,1.1233075610760554,0.6390267273380352,-0.26696360894409044,1.2034042974593213,-2.344299337932174,2.849718421388197,-3.3854452812902927,-0.876498375364431,0.7410685269693965,-3.0945574447278714,-0.4714162952311983,0.9760450225545748,1.0853401097383226,-1.8463154011101146,-3.3993007312912606,1.8251248198956744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6000032,1.0,0.0,1.0,0.0,1.7125145115508886,-0.5496240184408426,0.5208348362759186,0.9879244315473393,-0.07591215638090625,-0.018207560803892624,0.1338325326482314,1.1065308502208744,-0.07650611925848924,-0.1724123454782904,0.9064241978816464,0.5617314137147491,1.5392187522329732,-0.32441070515375425,0.35099466978039123,-1.0135772508623053,0.25521551606055143,1.0834622989815206,-1.0125081182348972,-0.3830748741984475,-0.9442765912931907,1.14006772080028,0.6057425398224878,-0.336054472881845,1.2333112805960322,-2.2958952825288153,3.1324849668840433,-3.532045097241963,-0.2557991382563146,-0.7047223577019357,-3.6975549578765943,-0.31522723913770234,1.1380857855628448,0.9979947997738078,-1.797995926760244,-4.584384516764098,2.1510776018028883,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6166699,1.0,0.0,1.0,0.0,1.7312623392506057,-0.5466078313204604,0.5184598662146728,0.9868096292549621,-0.07018696043614925,-0.012082997933253231,0.14537725872832985,1.1520277986960616,-0.1403973623763479,-0.16622643843218643,0.9373412196648907,0.5102006102250579,1.315759107209511,-0.3567038651663135,0.4063167320804332,-1.0724629806116732,0.2605982479486306,1.0594582910533077,-1.0733843596721275,-0.385626509723851,-0.9237834235418884,1.1565741209348357,0.5790934099129653,-0.4197767317951948,1.2751070275912577,-1.8388739169412995,3.379051427718648,-3.338484205111133,0.3879826199003867,-1.358257940545844,-4.0000688180671204,-0.2173459961298381,1.3577455369952975,0.9069412727367596,-1.7167221265615076,-5.00385358371144,2.460634635050656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6333366,1.0,0.0,1.0,0.0,1.75086115752282,-0.5437249618362998,0.5161469699400522,0.9859406368498079,-0.062009108415434375,-0.0059673165507055,0.15504941862161842,1.1856372456206028,-0.19418543217560508,-0.1289358984854727,1.0431548901150582,0.39770229097641957,1.1367430472058397,-0.38570662497672537,0.463629942641108,-1.1248602802649568,0.268148295922739,1.0381869437461297,-1.1458440121750557,-0.39031975522584184,-0.8990183162103117,1.1702991570209236,0.5485183544889625,-0.5028499259291319,1.3153325991400298,-1.5213486373534835,3.401213592086084,-2.7426894563768127,0.5427902489798268,-1.5488813673292074,-4.394494552011431,-0.2100566090127388,1.6873132378963442,0.7037253192180603,-2.0705543094445074,-5.126962174854922,2.1595786165117183,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6500033,1.0,0.0,1.0,0.0,1.770988066542664,-0.5411248034512475,0.5147038838278906,0.9850134351651901,-0.054176247493897205,-0.0016733394624982036,0.1637396307757991,1.1895608378723346,-0.2423320244677298,-0.05532845795450011,0.9490204084832495,0.22881191247427374,0.9878989529789661,-0.40741558783467213,0.5196907452308754,-1.163886145336864,0.2786912924339748,1.0078288088835763,-1.2198678043721454,-0.3926284106947162,-0.8675395364577944,1.180031678490459,0.5100747948945278,-0.5906758127545039,1.3470931254468894,-1.045741522954222,3.2886741670141437,-1.9592653854825892,0.9909723912114846,-2.4004051579715715,-4.527647244832929,-0.028905679898836648,2.0828498183008826,0.34102513210508484,-2.134706039743634,-5.369444104590883,1.5564538874299993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6666699999999999,1.0,0.0,1.0,0.0,1.791029831370666,-0.5387201544853252,0.5146072972012603,0.9841303948478197,-0.04707657216503619,0.0012747633118479979,0.1710834219565518,1.1715321330415673,-0.2718537889730346,0.01439743714072619,0.9075996963116255,0.08000229498175443,0.8043022340384719,-0.4205647454579676,0.5732526341198573,-1.190169257065402,0.3011807750279479,0.9581732784534002,-1.2967658888459697,-0.3912832798161817,-0.8295898500769611,1.1816666841594352,0.477361344183772,-0.6818317540451017,1.367214499151289,-0.6913278993961169,3.16358180646544,-1.3475052208348057,1.5225417899088278,-3.8807228029113134,-4.2100955012351315,0.11524328841535392,2.4370940109030217,-0.04623488466915877,-1.9985456975813314,-5.326587420688582,0.5919858332573966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6833367,1.0,0.0,1.0,0.0,1.8107990771490114,-0.5364260294179525,0.5152903566215686,0.9834425281524908,-0.039496094267353905,0.0028726690283804764,0.17684060656793457,1.178010657530136,-0.2963903208959775,0.0383999477678838,0.936857259128607,-0.08982360518228966,0.5675407864076188,-0.43045989723640266,0.6251436830185105,-1.208803075865039,0.3294427869337217,0.8784711234050123,-1.3602046017530165,-0.38878696006465185,-0.7863029069547596,1.178490512585828,0.44345647173877023,-0.7682290818832846,1.3668260260211915,-0.4714649575048599,3.0435366894533398,-0.8426813234500478,2.0292349263291976,-6.040323744518381,-2.530262190554667,-0.04240136953599836,2.663062710377464,-0.21340206566199466,-2.029670215929991,-4.844893228122184,-0.3833434000683062,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7000034,1.0,0.0,1.0,0.0,1.8312683159698615,-0.5342011895076462,0.5158703521904647,0.9830887374002245,-0.03142419624690057,0.0029570940332625246,0.1803893286254687,1.1574753879837307,-0.2921544110330166,0.06304439693337832,0.9983739509102515,-0.22779117975050475,0.3596784415045926,-0.4362802754724601,0.6747040600040812,-1.218258690692492,0.36882207452124954,0.7568287509478712,-1.3811081305486046,-0.39269666162747296,-0.7408209155268649,1.1745532677438977,0.40970553500809126,-0.8433285179753897,1.354436360259452,-0.3424866326080135,2.664974466878591,-0.18374699371196074,2.319376528723882,-7.796160203282942,-0.6355580430788028,-0.28354626489168294,2.794970883976538,-0.3949570427676738,-2.1665907840630156,-4.159008141109745,-1.2429247002816415,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7166701,1.0,0.0,1.0,0.0,1.850314243123582,-0.5317022216243519,0.5173172190339803,0.9828918355219164,-0.0224330114634109,0.002342874970184561,0.1827974578540814,1.129115555333437,-0.2712705498546788,0.10184871763971538,0.7621072936234551,-0.34708172198179643,0.2514573194504344,-0.4418761411557786,0.7139763429127614,-1.2149279879052373,0.40675549251628634,0.6185985968849007,-1.3813899122261795,-0.3982385211307923,-0.693137024490816,1.165325251496436,0.3712366344972841,-0.9068629638541522,1.3253951198168235,-0.2045214260845015,2.49672589027272,0.345705474955281,2.2307634353336288,-8.2387224261862,0.7468539982258413,-0.0954055674808754,2.912046197086576,-0.5998276303406092,-1.5470538180364475,-3.426458303679856,-2.1741892745610594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7333368,1.0,0.0,1.0,0.0,1.8696279021733926,-0.5289569111456598,0.5191708516368797,0.9826525774083023,-0.01786792329216252,-0.0003180121228470575,0.18459292591628657,1.1251814721376008,-0.24111575580343556,0.1300907695661837,0.3892542762036837,-0.4457695666744106,0.2548835241624704,-0.44309766997670524,0.7579284227948979,-1.2067351518136176,0.4431810044165995,0.4822041208268361,-1.3562129474841433,-0.39587685357054,-0.6437525148208992,1.154558973410702,0.35813697126995514,-0.9575440231952718,1.2819632394947984,0.1093825861694667,2.383318339961118,0.755835277398685,1.7518346106463014,-7.756293516831528,2.2172893844270924,0.21364472699382892,3.0639565576286336,-0.8156686953254234,-0.7411754451649162,-2.5994684990879007,-2.8961107716055148,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7500035,1.0,0.0,1.0,0.0,1.8881486941820267,-0.5254278511829447,0.5217100231812019,0.9822240974865317,-0.014688618600478237,-0.003690119335790771,0.18710010641275895,1.1222711473888445,-0.18077127430792786,0.14166812085644187,0.3782124248773983,-0.4892050529505846,0.29317718210731936,-0.4382300476579573,0.7934204464660213,-1.189733428269596,0.46515009632680376,0.36005496257094866,-1.3074801182593174,-0.3911170159880162,-0.5910049349727577,1.1381362406076756,0.3465307369134239,-0.9935120871216488,1.2288579010225882,0.1818175073226677,2.039228745789429,1.167039774269344,0.47356756464751065,-6.474475343490461,3.8687429163790683,0.12515955817188526,3.144152318833932,-0.9369490921744273,-0.703018170925116,-1.7547901426319212,-3.2742535222407323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7666701999999999,1.0,0.0,1.0,0.0,1.9065707793482984,-0.5206746956679866,0.5241387202666369,0.9817951007407569,-0.010168663338838068,-0.0070716672383055006,0.18953883499119384,1.1192277340593184,-0.1282740108421646,0.13547259540566195,0.49824125631601335,-0.4457469262771273,0.31290821762431154,-0.43703707427811583,0.8259028502697953,-1.1678337482019878,0.45896662147602085,0.2663878444121312,-1.2272545923553133,-0.39170485995417326,-0.5389472279162802,1.123327274541615,0.3347029853712399,-1.0160371449356786,1.1728212371365392,-0.05290555268869351,1.8588742347302663,1.359239428557109,-0.8153112557384423,-5.12886021244891,5.753639289274755,-0.08722747554550155,3.0225523298448933,-0.8927023089242244,-0.7304135156853311,-0.8972873697319377,-3.5186097320069596,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7833369,1.0,0.0,1.0,0.0,1.9242827038739414,-0.5154270923577258,0.5266954760661499,0.9812660117550683,-0.005168630986249863,-0.009357597635480445,0.19236094924522143,1.1040157810206128,-0.09772997523325505,0.13182095201914376,0.5839966209431885,-0.3626695846871911,0.396442131976091,-0.4399935696079506,0.8553830448819791,-1.1444253567017304,0.43797300011477197,0.18909261356530416,-1.1156917583742063,-0.3940246043213646,-0.490252989141106,1.1083794374633809,0.3221835710296785,-1.0234217259318714,1.1115706753817074,-0.16285704273245685,1.702198283037467,1.5985856373455352,-0.6722397484264567,-3.853463108230203,4.837953210927824,-0.13113659514978124,2.8833463308847747,-0.8960696962755831,-0.8545146922529886,-0.12164998526378833,-3.4472150370322536,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8000036,1.0,0.0,1.0,0.0,1.9417815597521035,-0.5097660352458803,0.5291791791685904,0.9805114185149606,0.0004793155249245219,-0.011099487711716734,0.1961477244092952,1.104043815150135,-0.08072220397276259,0.11714371607968298,0.6365314310677666,-0.31465191090887945,0.4606350848015457,-0.4424656532263339,0.8826429065175964,-1.1145474537180942,0.4365585850458224,0.13793881724025056,-1.0659891627941718,-0.396076088534939,-0.4428354913303657,1.0934582249277824,0.3062191053284941,-1.0200921525544706,1.0579138394211283,-0.2886709167891157,1.6013144818010157,1.6846461968479167,0.012860718929928358,-2.778693762068951,3.2251540530366203,-0.07697086493808629,2.847783933635721,-0.9498533457254316,-0.9890299412927811,0.5237179359136208,-2.956861219430877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8166703,1.0,0.0,1.0,1.0,1.9591941362766112,-0.5037761377563856,0.5314164525232301,0.979696419584026,0.006175069630049008,-0.012422631333201,0.2000061804046655,1.087116163932075,-0.0658140040253205,0.07754641776137317,0.8002245724026125,-0.32546015606048584,0.5245815495427395,-0.4496159527456489,0.9087603010296451,-1.08827037116372,0.43840169160315084,0.09646930291675498,-1.0081864082627154,-0.3965903049506918,-0.39532666816765305,1.0767175959489768,0.2892158403845897,-1.0059644264868883,1.0130084376099302,-0.5502915537721197,1.4401801432852872,1.774755577900467,-1.4558700013841888,-1.2728113500978453,3.6561856582350813,-0.17400323915252736,2.7569446603346153,-0.8893839663054596,-1.198542252732248,0.610477258195824,-1.4729251876704679,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.833337,1.0,0.0,1.0,1.0,1.9759120267107466,-0.4976327857757499,0.5327189824931737,0.9785897210470604,0.014520445256401183,-0.013795215154213268,0.20484385899860766,1.070301887945809,-0.06072408400155732,0.009459793802093299,0.9860974062415527,-0.3534675268383659,0.5800664978890491,-0.4608087417048415,0.9306490073057821,-1.0553888161377067,0.3880294879416827,0.09551168738289904,-0.9441160637739585,-0.40187620810690583,-0.35093715218956784,1.063812033425336,0.266267617001269,-0.9997428699161259,1.0088162349704335,-0.7473082033175172,1.4277721120637545,1.7435863066164423,-2.8939141600375313,0.5450866278411302,3.5209717219228565,-0.3367220578722077,2.6026143234203665,-0.5853684115174862,-1.0797978730541098,0.510412129398112,0.6186642051511276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8500037,1.0,0.0,1.0,1.0,1.9926689726948532,-0.49135118386038246,0.5328609414456985,0.9773923173513508,0.02333028036415413,-0.014958578040564783,0.2096096298925473,1.0480446123838845,-0.05640715469559199,-0.055065320752320845,0.8788926529700335,-0.3228033513279459,0.5788939377441066,-0.47452627601011305,0.9563527999499111,-1.0301507113707515,0.3419376933409558,0.11463889351723451,-0.8908204494671721,-0.40781439599456926,-0.3085726838793526,1.0572052765404998,0.25322250596292784,-0.9889506548128093,1.0336306190259148,-0.7866376258410436,1.5136032408129825,1.3931841378314695,-2.562277815643671,1.2566359966156497,3.342355416190336,-0.38946211189964464,2.1748968887053355,-0.03426520050357408,-0.33367878525060773,0.8882579012096757,2.0665256462180204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8666703999999998,1.0,0.0,0.0,1.0,2.0085689161987106,-0.48496064249400406,0.5321755337287379,0.9761629522513209,0.029821583188157526,-0.016219937796674938,0.2143676221960987,1.0470167751891621,-0.04713644470804751,-0.12117522632896909,0.6246826203693079,-0.21543266846903275,0.6137015367617493,-0.4870300483420513,0.9811025495730976,-1.0089492519977152,0.30262005660170593,0.13739963771248714,-0.8327039937439196,-0.41485830446770144,-0.2784404442395974,1.0626698577908702,0.2551449685809964,-0.9701342139919433,1.0777005609460772,-0.6561848799110646,1.5636410959245564,0.9420741711465792,-2.4995815388764795,1.861752183560185,2.965168526277692,-0.25964318091211014,1.4518055713126887,0.8484716414975464,-0.038395972041703585,1.0532041091088413,2.453020842150744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8833370999999999,1.0,0.0,0.0,1.0,2.0250789903643356,-0.47793925586366226,0.5303019251650077,0.9748398569257378,0.03409223300734338,-0.016551273366270526,0.21966116713596667,1.0607424351343226,-0.05568361202353339,-0.16975714930010916,0.3593687583210834,-0.04246783998371789,0.5449762228712989,-0.4963991490861405,1.0084742740568027,-0.9987481761942542,0.25861814207297057,0.17669742375271957,-0.7919813009133473,-0.416469186001185,-0.2601790680485582,1.085487721155194,0.2519426376684729,-0.9538437809622407,1.1153981439656624,-0.36071151252416517,1.6527666474062086,0.3265000164875231,-0.8354453991805245,3.0592758783856926,-0.8354358401309944,-0.005410889518858143,0.5004918143684528,1.8991673257044117,-0.03320608639488207,1.0480523624730869,2.1038038880155625,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9000038,0.0,0.0,0.0,1.0,2.041390425699327,-0.47111317215729465,0.5280938989944297,0.9739664203250196,0.035661279583911375,-0.0159116172648825,0.22330361764584405,1.0714839303763666,-0.0587281486114159,-0.16515453027664365,-0.05724445595940178,0.24971251038749853,0.46260176214663495,-0.49905378947362433,1.0361948813377477,-0.99806589634813,0.27477182093266184,0.23937570427706878,-0.860551910777342,-0.41503866781238935,-0.261757350394528,1.1259755619255056,0.25403809682076123,-0.9351990653726829,1.1478274974668552,0.08833279392982826,1.3808154528740917,-0.20140370110823558,0.3057026862759864,2.950409347722157,-2.6870606739989724,0.5433757748562658,-0.853341330966747,2.3485724438056708,0.2872793612800137,1.274746534464174,1.5081347695172482,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9166705,0.0,1.0,0.0,1.0,2.0581518619724704,-0.4637797968372047,0.5263673296212098,0.9732067322620436,0.03210232014164495,-0.0130053130020908,0.22730807102933273,1.10877015924699,-0.02973995596296991,-0.1355734428677705,-0.5338864053867142,0.5649215031338328,0.45230235067663466,-0.49345471673296,1.054501547873636,-1.0054616463247754,0.26880825199568253,0.2750445987040813,-0.8815501691840246,-0.39835662394759114,-0.2886238359702052,1.163773625853546,0.2615186355297641,-0.9113521448303326,1.1656694034918886,0.2765148347239164,1.0355803073196386,-1.1708912429744975,0.2771823434083477,2.664384193698374,-2.331159758964983,1.3302224035620542,-2.3908577744603208,2.226514699515409,0.5840561852525991,1.5626065190863794,0.7315165090136956,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9333372,0.0,1.0,0.0,1.0,2.0750055999485495,-0.4553697792613146,0.5250044977107664,0.9726375425534725,0.024756888690966844,-0.009030150365528067,0.23082842905989948,1.1427084515544013,0.013404014465778546,-0.11989631334141479,-0.8518254774144046,0.6669865795199545,0.38757330098513704,-0.48983660988183814,1.0707142939537562,-1.0370956825066961,0.28401125085842965,0.32818868835929416,-0.9382573914868254,-0.37069783234549397,-0.34145276893372367,1.2001928670103326,0.2735066752662602,-0.883112077229369,1.1722114298684123,0.530631149474596,0.43507071942352266,-2.470704918155993,0.8546910814551307,3.2063117052616454,-3.347986091166637,1.4133483386700807,-3.8915538356778954,2.396887901528131,0.8469775666546615,1.7465993104256268,0.2843779607601857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9500039,0.0,1.0,0.0,1.0,2.0920006668531945,-0.44608554097289566,0.5235004253742871,0.9721549785546415,0.015669015995245224,-0.0056406991624395044,0.23374636279977545,1.1571554164385502,0.03758807157365557,-0.1083524759442511,-0.9094953946083428,0.6039198923120103,0.333377602228306,-0.4757669763750635,1.069003934192468,-1.0878186416436364,0.297298011690259,0.38192186930024985,-0.9931499287553186,-0.35124491843536587,-0.41834255659639075,1.2436700490303438,0.2897512775500906,-0.853132051376191,1.1751486878090922,0.7219276946042474,-0.6026728680446896,-3.5760752094909805,0.7224579731497044,3.247117884305,-3.173389614872997,0.8392291848985276,-5.086520042172007,3.0663665565606553,0.8819980942130219,1.8638713619047493,0.08968981753428693,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9666706,0.0,1.0,0.0,1.0,2.108803636766866,-0.43661164120608836,0.5221351857240504,0.971644181116231,0.0076377393132291945,-0.002875464048606283,0.2363069655081231,1.1677675329152626,0.041456105187481274,-0.09614129384473781,-0.8586463191293534,0.47473683979798387,0.3512527932636519,-0.4657723052665169,1.0506251581740753,-1.1562984278947428,0.308093231460618,0.43642616764398645,-1.044037256875233,-0.3427234702335974,-0.5110037761074601,1.3024052899867915,0.30290667053990056,-0.8209829075744532,1.1752010964322097,0.7313413186203777,-1.3564317711296852,-3.939754079056691,0.5783273625604126,3.2548957517956114,-2.805214729448585,0.46776946204647174,-5.491169233427545,3.3434733098311833,0.7433451465739255,2.0980188849128765,-0.01449347561247311,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9833372999999999,0.0,1.0,0.0,1.0,2.1259500963208935,-0.4269327950544467,0.520672789359681,0.9709043575163805,-0.00011728899326407115,-0.001373471267248917,0.23946362641469043,1.1632643508504577,0.05479691836899525,-0.05213445219809532,-0.8931239322689912,0.2637181182701887,0.4228597373122289,-0.451388883664963,1.0237894513926937,-1.2191440402624647,0.31657562899743025,0.4904186113531537,-1.08665727341792,-0.335652571849186,-0.6013818971219245,1.3551193822562706,0.3145294986588979,-0.7831979486778361,1.1746655709891114,0.6339636585900748,-2.2019884044944327,-3.813412008683292,0.483962657463064,3.122147131415429,-2.0847157250490547,0.6448601143122094,-5.267789557021701,2.405159284475739,0.7388717534683815,2.425236525136702,-0.18749828977292363,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.000004,0.0,1.0,0.0,1.0,2.142287438952769,-0.4169634500562665,0.5204969932593833,0.9699554775045639,-0.007868322797305212,-0.0021673786735503164,0.24314556057007555,1.1175118298715836,0.09249161027606317,0.02086257582767714,-0.975347982386971,0.04062082976627934,0.5715259362045619,-0.4446401410492705,0.9772253978917006,-1.2834124157449864,0.3242253523068973,0.5404979468343095,-1.1135279200245831,-0.3212280900991828,-0.6865971125274872,1.382577426479935,0.3275357782469635,-0.7401415283874615,1.168951140939893,0.5566634229725979,-4.126814911121719,-3.1439930740324114,0.42164166427525035,2.9210856975968684,-1.2191707026164846,0.7717810864732972,-5.31434432208544,0.9137248393414072,0.8943662659787012,2.611591209930264,-0.4799913915986254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0166707,0.0,1.0,0.0,1.0,2.1573360377779593,-0.40663317557452544,0.5213318975802363,0.9684441154628146,-0.016065002002496553,-0.00458107171025588,0.24867031330275816,1.083020596547164,0.11569645724742961,0.03719423646543507,-0.8205271165729855,-0.1721275023762665,0.6755837316531134,-0.4328333991216482,0.886228679234309,-1.3239440189964167,0.3306303792493829,0.5877883293454291,-1.1272963781165164,-0.309926484181337,-0.7785270621477273,1.3855769378159735,0.34434176714927234,-0.6961447342407466,1.1586658259363978,0.5504706966356774,-6.29996941164339,-1.6773612859406675,0.09208539320667118,2.790153158971154,-0.592081794576931,0.3423178993705177,-5.388013861238624,-0.2309558772922347,0.9131394203426926,2.6483320134820127,-0.4553617805152843,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0333373999999997,0.0,1.0,0.0,1.0,2.1720441263993973,-0.396156964716936,0.5216392098334466,0.9669389317605682,-0.020443702223341666,-0.00814473790102629,0.2540567269915484,1.0624124433092657,0.12054257609105684,0.033122069743443956,-0.534211478114317,-0.36408711826348134,0.7495859453390173,-0.42629108113003483,0.7672259975056268,-1.339324570433761,0.32729487155281256,0.6335032381435586,-1.1332640193159338,-0.3098174706323056,-0.8661979337696988,1.3748788818398021,0.3579738198010146,-0.6518636180492602,1.1537723845652648,0.1856768723190969,-7.764845191108123,-0.10188474164763783,-0.2841119918045613,2.6900649068714024,-0.2868624308901105,-0.011973986359203102,-4.739437511761615,-1.3770780238582914,0.8350767556485909,2.691252611528617,-0.34233451036996004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0500040999999998,0.0,1.0,0.0,1.0,2.1861719317070065,-0.38568693111044594,0.5224493445693928,0.9650306374740515,-0.023235069974598378,-0.012439942802697357,0.2608088343648791,1.0507054982005126,0.11048604807045848,0.0530486093481038,-0.40479472257028537,-0.5165104666095627,0.9630011219806657,-0.4266441576658868,0.6273999885410255,-1.327340183843654,0.3211599605817647,0.6774573389121363,-1.1368584782703488,-0.31032561785824286,-0.9365086285022819,1.3396742452154955,0.3721777146760091,-0.6064361344396186,1.1472546527684317,-0.12799477800675163,-8.43240466621348,1.3193073411968181,-0.47068471794560235,2.5042021566907526,0.04439062811528228,-0.23977311004527865,-3.775558664637474,-2.5066831766050934,0.933714068280353,2.8557858215476775,-0.4351723476331714,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0666708,0.0,1.0,0.0,1.0,2.2003765432005666,-0.3752609525639136,0.5236324184732817,0.9624673161052434,-0.02491012203531879,-0.017824501887911712,0.26966356517298185,1.0858567824155074,0.09988530333729811,0.04281110214897635,-0.2818835661612015,-0.6787038846601144,1.0941656985221133,-0.4305575822632451,0.4861452798048664,-1.295347571106711,0.3116053495756446,0.7169768103133941,-1.1317843287527158,-0.31780992361868887,-0.9920501409615256,1.291322608840754,0.38909768432463093,-0.5566705669452828,1.1392666106326692,-0.24917421381146268,-7.87688093281274,2.139152331490467,-0.5640332352792412,2.5165121078381367,0.4240842455129301,-0.7040534756244441,-2.909345124890259,-3.110942164660345,1.1978221032770602,2.8676921627951386,-0.04811761899451385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0833375,0.0,1.0,0.0,1.0,2.2152866199268106,-0.3639705031733867,0.5244376712131597,0.9597877137357591,-0.02502330516966828,-0.024124954665709755,0.2785666263618953,1.1301815264331834,0.09605655439792488,0.03206118018336885,-0.06814650893175506,-0.7722356451584377,1.1154288257772038,-0.4349499814045498,0.36483676565520534,-1.2560349635171497,0.30235881513690765,0.7613412436075481,-1.122722308480968,-0.3337941139826227,-1.0334869932882988,1.2359759656640064,0.41210519797338463,-0.5108462045003032,1.14565072892744,-0.1739173311043157,-6.404131230709727,2.574971598372175,-0.7533370900946265,2.535770690166632,0.8824911604485014,-1.0251944535728106,-1.7973271030810016,-3.648311950321017,1.1337741394655618,2.829392128414605,0.2665802867224532,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1000042,0.0,1.0,0.0,1.0,2.2303860431185463,-0.35233278572420396,0.525721114481346,0.9569429741471691,-0.022869601325899422,-0.03000733287286697,0.2878136298708278,1.1443626941364766,0.0575905878087376,0.0285345383577313,-0.14208412689673172,-0.7485251032840188,1.1278447042670932,-0.4363548382278777,0.27267381183912676,-1.209515012829532,0.2864940630166844,0.8015026690369945,-1.1023678979050218,-0.3519831404174128,-1.0519611642193658,1.1697119672759233,0.4268902312250923,-0.46235730737198744,1.1481526379621034,0.4886784048799027,-4.740961736268731,3.2567161339049835,-0.6035362100759464,2.325785399204876,1.3652670372152542,-0.8652170430685889,-0.7808598969362165,-4.096004281390233,1.1737042228117294,3.071100010934797,-0.050827850714530096,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1166709,0.0,1.0,0.0,1.0,2.2459217717422124,-0.34128114423156075,0.5269574912812778,0.9539555519139815,-0.024256893055923753,-0.036348433315297135,0.29674770345747886,1.1383786066468962,0.007721465647901216,0.008297688956128577,-0.41359217723473346,-0.6505590418141156,1.0748465071122135,-0.4186606686633261,0.20680439171546525,-1.1474775419392413,0.2822409012319621,0.8388675786334039,-1.0772133162226571,-0.3626347397660452,-1.0595157085768325,1.0994422165507132,0.4512287503140571,-0.4084759993958092,1.1439564638484323,0.7916523771146919,-3.448876234764741,3.2994757456634547,-0.08769413147984613,2.223460790213198,1.3933850780490862,-0.6367868780817985,-0.30139516885758993,-3.8998361969817283,1.5432739774770343,3.1873230625501345,-0.4080542729635532,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1333376,0.0,1.0,0.0,1.0,2.2613803780226807,-0.3305634512404208,0.5280644409092045,0.9510762522761477,-0.02688097422558036,-0.04197457862166792,0.3049090197592959,1.1097527710801924,-0.026067598207261677,0.00018770653824778938,-0.6465767301451575,-0.5253692544370019,1.0102170399162402,-0.4099663728805628,0.15771104075521974,-1.0995322680090338,0.2835709194544141,0.8756181769414871,-1.0559216357443804,-0.3732094121392646,-1.0620076899409634,1.0397171673874526,0.47833280002592526,-0.3561129927987788,1.1345508016597001,0.3933696917611541,-2.9027540349946634,3.69244011283645,0.22338810665111503,1.9668219037229573,1.3656826790319367,-0.34369965805258945,0.1382959272045942,-3.3600866066272843,1.8210293098633157,3.099456448693496,-0.7141055841270505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1500043,0.0,1.0,0.0,1.0,2.276406427535943,-0.3204489557387103,0.5293775032465196,0.9481613077187571,-0.03254010113164011,-0.047536480996765676,0.3125244939806211,1.0795259880308632,-0.052868324172084535,-0.010500734942221049,-0.9142852284200451,-0.4293718171740392,0.938274785141046,-0.4055483193799748,0.11004573036537413,-1.0243959586820188,0.2896871863462064,0.9044284398789627,-1.031690469209414,-0.3740914179477754,-1.054905835116951,0.9874391056573633,0.511929848711455,-0.3051605778089294,1.1201528967704917,1.9625739496869168,-2.2827197870324225,4.489951939707917,0.617345497881883,1.7194361256756796,1.4502828603213396,0.15712960614112007,0.38873595281900497,-2.3132407706527935,2.0577324779668635,2.983718795662237,-0.8873629289071112,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.166671,0.0,1.0,1.0,1.0,2.291250372357922,-0.3105516453155945,0.5303897396800368,0.9453521432234268,-0.03983115459855929,-0.05303122445942462,0.3192342300859255,1.0489323588579689,-0.05520710236751397,-0.008342287596892525,-0.9340506963227262,-0.34284783503511046,0.8537888374412139,-0.34454711038606894,0.08162022900615319,-0.9498669040219739,0.30414914387351005,0.9329328290930848,-1.007578777048145,-0.3679717481259202,-1.0490497989312664,0.9626089874829747,0.5469240198069859,-0.2566555006954512,1.1049719782052678,3.128117026066846,-1.0278978004155448,4.104713517508921,0.7418740341914053,1.455775486511966,1.632398871182986,0.4385253316733827,0.4296648481194621,-0.7381028771899555,1.8978034206330439,2.8496685053902047,-1.051318069903032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1833377,0.0,1.0,1.0,1.0,2.3051856592377162,-0.3006683176025341,0.5319193496242383,0.9427120682804945,-0.046193101493795435,-0.05733948860904141,0.3253802955600566,1.0143298199133322,-0.04469016152576272,-0.06164192211140579,-0.8187636912898797,-0.32804739930855364,0.7780229887704799,-0.3012775433032782,0.07578240182500261,-0.887571901117487,0.3144163702775222,0.9529543864810607,-0.977277064676723,-0.35947387765697386,-1.0405836448686456,0.9628356272108396,0.5751900892527845,-0.21017143765135557,1.085108891019186,2.0086147827526264,0.09162505229513862,3.397225313187469,0.6677096508514042,1.3650970260288198,1.514286281289218,0.18830259730360252,0.5112008511486842,1.1665050779424804,1.6542746655588247,2.6125041077749303,-0.7195963689581912,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2000044,0.0,1.0,1.0,0.0,2.3188696893935457,-0.29090030012363755,0.5311815183282983,0.9401943893705489,-0.051655036572504746,-0.06202477197979107,0.3309368445091738,0.9956189325830183,-0.019887675569901286,-0.1674728069619432,-0.7012067939520465,-0.3043325482940331,0.7437455772895608,-0.27759315038666255,0.08467440352432797,-0.8366258337673708,0.32640617674920025,0.9784361543005139,-0.957102466719419,-0.3616949823289603,-1.0320097364795868,1.0014925678480626,0.6020666189439244,-0.16957185626934632,1.0809853846002369,1.3663663801895178,0.9254824086458825,2.9088979144054314,0.7473971633057342,1.6798092481779674,0.7192073835854219,0.08159574535079168,0.4577733666415614,2.7517526505796077,1.4412253771633003,2.138127815507878,0.11596166067699673,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2166711,0.0,1.0,1.0,0.0,2.332098593296762,-0.28063073554619916,0.529237278381881,0.9377015195266084,-0.056280261489374754,-0.0653306796622318,0.3365713813428707,1.0053004811629154,-0.0019093850716446203,-0.22296563295282457,-0.4122794156875406,-0.07367604140573189,0.8063219088927873,-0.25573190620586894,0.10663187714535927,-0.790608443377445,0.33932965888085753,1.0089481400742761,-0.9533034372767167,-0.3567540140388978,-1.0253245021290358,1.05456089901367,0.6232310312399196,-0.13890036792590527,1.0889742874391966,1.1121555062639985,1.5021151404187838,2.8396174351190284,0.5522095770717365,1.8890210347706236,0.10467179733052781,0.1843742325397885,0.3173621789201416,2.758519043068022,1.0549733576633122,1.2859396072940588,0.871000074934024,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2333378,0.0,1.0,1.0,0.0,2.3457335355569002,-0.27000851353885047,0.5267055406707059,0.9352147145699174,-0.05859043379557072,-0.06471463145754656,0.34315100931640674,1.023237565389123,-0.005497431568907363,-0.24436004986303902,0.006464694437334884,0.3560183546101803,0.862071249971613,-0.24052122603416218,0.13474500834596345,-0.7419717299555741,0.34481319946556327,1.041403648060937,-0.9536133998302816,-0.3555491622860185,-1.0214309760247702,1.0934433865182662,0.6372324678642587,-0.12670711696357054,1.1100187784980426,-0.5128917926453963,2.705395932724664,-0.7333233737186218,-0.0019078503908984425,1.7826501034493052,-0.2945171939984958,0.11104384816445402,0.33357088268402535,2.18745410107303,0.40797726293528547,-0.20773884375775017,1.79427179752856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2500044999999997,0.0,1.0,1.0,0.0,2.359317987586491,-0.25914993344851817,0.5240013615942843,0.9331527404480514,-0.05918148982294714,-0.058890206713842416,0.34965047949320616,1.075957944457777,-0.005456199102893078,-0.21109574044624635,0.4090259691242538,0.7580332339243644,0.8695991794174331,-0.272828333486835,0.19681192192924357,-0.8150526047229573,0.33926606374063756,1.0683699290325932,-0.9631206967111462,-0.35305254503049277,-1.0142054504681761,1.1274761815463776,0.6368303005362467,-0.14582500990041986,1.148783466974935,-2.007779047460048,3.328307629434536,-4.06504622506201,-0.4057099877246231,1.600086189716149,-0.8330702720534159,-0.05970925941700413,0.6398902328192739,1.5554581822981772,-0.812926816934907,-1.6776772391179418,2.0356998930129526,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2666711999999998,0.0,0.0,1.0,0.0,2.3737626321320877,-0.24697796838264996,0.5222522209869876,0.931273925737897,-0.057521102223565906,-0.04966716058369601,0.3563051658329773,1.149477869939737,-0.0026609728696391777,-0.15266720230948827,0.6497525365186247,0.9801846606688188,0.9140625284346179,-0.30744732813476694,0.24568881788095662,-0.8774735417940561,0.3312895061607433,1.0947399610572213,-0.9813824644367469,-0.3575394749138693,-1.0001012589381122,1.1452920962920843,0.6101348531046407,-0.18262980344598453,1.1778755773118006,-1.578897322126877,2.8806757399767364,-3.785629543275486,-0.4510909848235884,1.5363497311665701,-1.7581720776552152,-0.31417565187356056,1.0584862281271457,0.816797747260578,-1.831318666689058,-2.844504294605074,1.5665059494742817,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2833379,1.0,0.0,1.0,0.0,2.3884539784807073,-0.23393382663508047,0.5209578073879845,0.9291406945575081,-0.055678323976778604,-0.0389409365555015,0.3634296320011739,1.1861206238357946,-0.01763515444813546,-0.12797159017169724,0.7055638399784501,1.0352710609445066,0.9418198226127268,-0.32545834948421903,0.2928346386401841,-0.9412405085407763,0.32422966750711896,1.119581689161461,-1.0217265498444585,-0.3635250877046549,-0.9789225056315227,1.1547028275749134,0.5757862228920336,-0.24064200935420862,1.201000436391141,-1.5892855453770605,3.0481796773152774,-3.9583266749116186,-0.6241737761999724,0.8364792956883796,-2.7661138735994704,-0.29958740398087175,1.3089549662872264,0.48468244178527387,-1.9938438490397268,-4.122368805532546,1.6287491787540012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3000046,1.0,0.0,1.0,0.0,2.4036116295929073,-0.2208542647678973,0.519364301865597,0.9269005220834887,-0.05347653850927567,-0.02848545857976468,0.3703839368006157,1.2290147122304358,-0.06373363717394731,-0.1280114713323706,0.7587419864175317,0.945750843738912,0.8296646833705343,-0.36042361893303865,0.3472950103367777,-1.009418028179555,0.31048367200915916,1.1226226600121203,-1.0735864446309875,-0.36752574168572527,-0.9564693394648736,1.1614482099970895,0.5436732585470598,-0.3200423717883231,1.2321673251868792,-1.7432005615222195,3.385090176408213,-3.923528076104748,-0.5419353706973025,-0.7834508571531525,-3.5269704236427257,-0.02048954665807914,1.4857113731573317,0.49421444205309495,-1.7757497446011459,-5.083783931537866,2.1682465788239007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3166713,1.0,0.0,1.0,0.0,2.4199611946450204,-0.20754256445150154,0.5175179836152133,0.9251643694205597,-0.050201050175001545,-0.01889690784708122,0.3757574363732596,1.2557605704486285,-0.12817137096137377,-0.09682462248942461,0.739933741098258,0.7898164180449848,0.6862028520917989,-0.3835651510816638,0.4056712035264696,-1.0720250393128063,0.3061651190215175,1.093466608359632,-1.139292465763911,-0.36420807395922733,-0.9293986941455201,1.171176675257646,0.5165944463553458,-0.41010181265773293,1.2732754669017097,-1.2027020716354195,3.4396266043396295,-3.5508512938313412,0.0702320530716014,-1.9754553016721885,-3.655549255657282,0.0994851313970643,1.7311647643826311,0.33398809792616185,-1.6157898238564372,-5.532233033205125,2.639969900018394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.333338,1.0,0.0,1.0,0.0,2.4368171105128775,-0.19496984750713497,0.5164973229961434,0.9234904607184375,-0.04722609905008491,-0.01109943456167275,0.3805415444901788,1.2468626088445767,-0.16253794019360646,-0.02292304532699154,0.6236353762103214,0.5807420987964964,0.6378682735067309,-0.40051376816769074,0.4619494597898723,-1.1277799746973527,0.3128247451270161,1.0567740182593606,-1.195438330189514,-0.36420956400681437,-0.8987637319078016,1.1725811688605015,0.48981349003252367,-0.5044505083773628,1.3201664978521523,-0.8133489653732124,3.35344937867008,-2.7834899114024934,0.38611729985043186,-1.959337687600642,-3.8095175457051837,0.06246147861782211,2.0152591439989123,-0.08537438000683474,-1.43153548636862,-5.519282089620335,2.1647371934462942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3500047,1.0,0.0,1.0,0.0,2.453321198496291,-0.1821717021032398,0.5166340040616386,0.921733896391492,-0.04439371137116634,-0.005501943279159982,0.3852344107862183,1.235812378721072,-0.16701852722243793,0.049153951079570615,0.5654058169366475,0.34103979793834827,0.5543532810626539,-0.4106768374840352,0.5174530730454309,-1.1648082219255502,0.3190357214243519,1.0281552214837648,-1.2662766379219201,-0.362126020507868,-0.8622232549949468,1.1683308568991262,0.46887650137402603,-0.5940782502638834,1.3454335176657324,-0.5208194754231513,3.2214712062804116,-1.8300476038639617,0.6946651466974781,-2.2467971937663447,-4.261292394557506,0.14660253806183765,2.3662622151088875,-0.3605572052430505,-1.381289035584671,-5.549081101030956,1.15522035659413,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3666714,1.0,0.0,1.0,0.0,2.469659989808067,-0.16946098948888513,0.5176172748347055,0.9203953216845816,-0.04077815081929384,-0.001812855003393237,0.3888525527672812,1.21607263497158,-0.18951987047020058,0.08679338971493114,0.5862442507036237,0.11721114605060734,0.3781530755038276,-0.4178744520697608,0.5693320480972998,-1.1887816834959917,0.3359802963279418,0.9818806286806695,-1.337481694094257,-0.3593228029645839,-0.819888166986691,1.1605625713152528,0.4437704300937656,-0.6894202483504681,1.3586739200866471,-0.3394636680989131,2.9633649722700786,-1.0602289133035319,1.1514083821755074,-4.255113802523463,-3.4818860279620454,0.10330754354880584,2.6490375036237994,-0.5024641017875624,-1.3463295839165845,-5.3585889620990175,0.03069260363007441,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3833381,1.0,0.0,1.0,0.0,2.486017809173916,-0.15732311211689903,0.5188503373112654,0.9196935823192101,-0.03617225623146259,0.0003621425264934499,0.39096694409217553,1.1823931616675896,-0.21593305633665688,0.10205773228865872,0.6453998322255952,-0.10068090347202219,0.21710389722707313,-0.4219923157182435,0.6162321030120983,-1.2001492563842622,0.35741607759076094,0.8863178110587292,-1.3823397376463902,-0.35868242883573825,-0.7739218282716532,1.1515820200086007,0.42399875882150095,-0.7726982395731148,1.346456606499575,-0.19306115167861704,2.8425324636370135,-0.4723358083667326,1.4940447025529304,-6.679713879557917,-1.9174172861047434,0.026754915504239588,2.7865350237723963,-0.5343245554728031,-1.1791287985195502,-4.671735886860589,-0.9729855867987309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4000048,1.0,0.0,1.0,0.0,2.502106591181592,-0.14586964221145007,0.5203461387288386,0.9193713279002811,-0.03022646529714925,0.0009875487547449135,0.3922266525594241,1.1523857912389175,-0.2295864536802164,0.10827412925881116,0.5877985054798943,-0.30375546244657925,0.052676960238136145,-0.42430983666312483,0.6640833197206978,-1.2045262419306033,0.38578188601601965,0.7592230540478137,-1.401395731458901,-0.3584309706641149,-0.7270034804252762,1.1427517171778556,0.404466058201194,-0.8451450893615469,1.3262410023276503,0.05051940666628406,2.8304506796718516,-0.13701463289591337,1.856845986434141,-8.087668300078532,-0.3504211767945725,-0.057664903047808413,2.932321234738662,-0.5341149217095243,-1.0829747467853275,-4.10189735032964,-1.4640137027031392,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4166715,1.0,0.0,1.0,0.0,2.518052376510854,-0.13470270213360155,0.5218917188121476,0.9196593954040851,-0.025177580525878273,-0.0004143129146678616,0.39190880856222704,1.1351124221667628,-0.2302854679772221,0.10542284378082904,0.45533753344487204,-0.47735677062157555,-0.10579732150048353,-0.4203083321280736,0.710580647697872,-1.2047164199484348,0.4193110675949647,0.6167283285448915,-1.3940204669009544,-0.36060459611499207,-0.6761775916256155,1.1337781536772884,0.3878995283970069,-0.9094284247105928,1.2976560521418903,0.3706431483274882,2.501045633595937,0.5141621066323335,1.9130826088475403,-8.317174433410255,0.9659623010633394,-0.13949649972837133,3.118353727466856,-0.5327712776818283,-0.8896371481440718,-3.277317329522707,-2.3359276648964085,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4333382,1.0,0.0,1.0,0.0,2.5337818895340507,-0.12374097602300464,0.523495890133516,0.920249462047696,-0.02012784873578783,-0.0033951348004528244,0.39079952707991106,1.1157694035711412,-0.20873643083792381,0.10043331145843212,0.46479041137035715,-0.6245666918740835,-0.0989557942372618,-0.41195504034266534,0.7474516742436046,-1.187387470765385,0.44955143384977825,0.4819833517891763,-1.3691969236926362,-0.3630808632881606,-0.6230581482861325,1.1249926390703762,0.3748114272872484,-0.9543892188334591,1.2483765911025924,0.3586320825117498,2.2862945218741006,1.0489510003708749,1.0371660663867377,-7.481087995161311,2.4456384099274837,-0.11894570001576943,3.053841578431259,-0.48724675825764946,-0.7768302708858428,-2.2450735247360067,-3.152573357106962,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4500049,1.0,0.0,1.0,0.0,2.5488135869307,-0.11265823740278347,0.5251602321287115,0.9204175011781801,-0.013979004881732765,-0.007005953923151159,0.3906240232718132,1.096907834797431,-0.16991520213502387,0.0871841955965594,0.5232172360042644,-0.6459011348857706,-0.011896360849647077,-0.40835390546887645,0.7867906175133101,-1.1697513166726723,0.4538833389522604,0.3673582299669814,-1.3124990235274776,-0.3645694607118977,-0.574382668755135,1.1175365625855829,0.36200513424546077,-0.984264358540028,1.192570063400101,0.11435313772819379,2.2374652074978654,1.1128543109593148,-0.2810422870179062,-6.143365299210405,4.219424744153321,-0.2612645329951426,3.0748221879422344,-0.6096300621938928,-0.8167515455861324,-1.4340990444611847,-3.486303968153991,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4666715999999997,1.0,0.0,1.0,0.0,2.563186080581793,-0.10131611645726236,0.5266496034114933,0.920374255955609,-0.007896605292190268,-0.0099025158689096,0.39083348472013574,1.0900982104653103,-0.1205523367024604,0.07983004509129708,0.560630183017456,-0.5594601146138158,0.0662199018184279,-0.40814326146151636,0.8220339969912139,-1.1502922528764539,0.4401833388796956,0.27720409892447617,-1.228549150925876,-0.37178969847230087,-0.5205638703665788,1.1046715963552423,0.34758632131760764,-1.0021926159221015,1.132166226410528,-0.05930755635332355,1.947023627556423,1.2665390817765025,-0.9339795524518749,-4.930736535981329,5.6150906625689,-0.2811172366628607,3.040793741250221,-0.7943846517278212,-0.8755268647505835,-0.780274510150105,-3.511402178735855,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4833382999999998,1.0,0.0,1.0,0.0,2.576867622990697,-0.089283199285359,0.5283479578428061,0.9199665042340133,-0.0017485598743352986,-0.011932373980663472,0.3918114241277312,1.0849280398169143,-0.07707710161572923,0.06904426463894309,0.6663909758892089,-0.4488666034969703,0.15566974449059426,-0.41033082796782433,0.8516915349000994,-1.1275332628441834,0.4227506249385611,0.2030000167185014,-1.1253289604358034,-0.3739400540084755,-0.4730226746605449,1.0910570212356787,0.33282084705198367,-1.0102735608966655,1.0755230900154273,-0.29393183971621717,1.7768780651284868,1.2945817804802244,-0.7244116320932803,-3.877615880272159,4.483777081323438,-0.3210024469019894,2.8342535729664866,-0.7383102215417832,-0.8434713909273281,-0.2684815109313165,-2.9894441994208623,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.500005,1.0,0.0,1.0,1.0,2.590034893670698,-0.07703799074440447,0.5297271304842238,0.919279503016453,0.005218243813172911,-0.012431742497285082,0.39337439805331864,1.0684302643756012,-0.06098612881146925,0.04639942956697968,0.8969560304828685,-0.3356164173523122,0.22299750464297352,-0.4179410090475129,0.8812633842873678,-1.1071394405549944,0.4160362361824774,0.14794997774101218,-1.0790896159632892,-0.38248980143586364,-0.42608856231745773,1.0800612064165014,0.31947055205527064,-1.0111420175185795,1.0325178871335527,-0.6192736197795725,1.6736135982280922,1.2961593407533272,-0.6972602865085241,-2.915362993059492,3.680088035329852,-0.6863584940793884,2.804516951039795,-0.7496779989348938,-0.7975783525912904,-0.14219596237279836,-1.7327402592611558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5166717,1.0,0.0,1.0,1.0,2.6028903591540797,-0.06496356113383679,0.5308546592935014,0.9183360478808875,0.014144744384586426,-0.011213258875448778,0.39538979778719535,1.0494128047539588,-0.05785445679084239,0.0379207645281538,1.0248091886909099,-0.1959901061063093,0.2648555258537256,-0.43097332324538473,0.9074787664152757,-1.0843278650751165,0.39950856890425784,0.10582105592565214,-1.0026591139189394,-0.3968187162350214,-0.379538589324755,1.0660677046259823,0.30623484879371715,-1.015013435788823,1.0177649658573715,-0.7848257081839662,1.471427248475253,1.3963137238858507,-2.215081274615601,-1.5800605649598713,4.4683990906568,-0.7449893618232102,2.6513450313912683,-0.9937479443314193,-0.7577309953548691,0.06564952162218812,-0.39534103349950284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5333384,1.0,0.0,1.0,1.0,2.6154585619881034,-0.05301498983648356,0.532069030602247,0.9172557032148458,0.02214297850329829,-0.0087447374452172,0.39758671128428763,1.0435486881208764,-0.051122873326896745,0.03685887943968839,0.909393994159173,-0.10770713830176532,0.30490469042395063,-0.44410191830869233,0.9303110573316928,-1.0605955566712177,0.34220004602320575,0.0952811869049788,-0.9301426817147899,-0.40732282982926143,-0.33771021784808003,1.0469362086889245,0.29421280169470865,-1.0089536957545384,1.0193398263275004,-0.735631922165875,1.35188783441361,1.4433910655231608,-2.8615647541065985,-0.11442277052630978,3.9675762606952185,-0.5243788377286065,2.4002506964904926,-0.9665669647167787,-0.503674470298898,0.7207044000507179,0.729661006775871,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5500051,1.0,0.0,1.0,1.0,2.6279182799407703,-0.04082775089831361,0.5331950349401872,0.9159747946973695,0.02871924825392662,-0.006953224432204448,0.4001462644194452,1.0491634836879635,-0.035726477438970616,-0.008853821517067494,0.7761634373747917,-0.09301267861323265,0.2928462437699435,-0.4554944363597087,0.9525417843549183,-1.0362147333316067,0.30412288632972095,0.10200695594659044,-0.8704063073906814,-0.41429804578456414,-0.2995300727583588,1.033848741364292,0.28944566620545586,-0.9909899077401724,1.0420870480606343,-0.680339366819579,1.4336298662921292,1.2200352016373863,-2.070296852060835,0.8190097595432729,3.427719961664564,-0.4243094185135042,1.9874849041567455,-0.38780947377521513,-0.1166535758351414,1.1848238125532804,1.7169176688247918,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5666718,1.0,0.0,0.0,1.0,2.6400985084635167,-0.02818306254574976,0.5329676576379121,0.91492536239531,0.03457730315567212,-0.005126440508562086,0.4021065915401087,1.0696581205906424,-0.036250523427550085,-0.1223185982536344,0.6144565399368402,-0.04794857089516419,0.2929790668596345,-0.4667799425586361,0.9780988151167549,-1.019927635280958,0.2731900129347211,0.12258156682373854,-0.8158851211446403,-0.4214665054003395,-0.27146058854386157,1.0340092003757857,0.29032434138996555,-0.9694594896811749,1.0765705297495047,-0.5748757825525275,1.6573089402514083,0.8251618528040671,-1.5811758009079773,2.248245098467328,1.4992568862736324,-0.3959771696201959,1.232052806854814,0.8313821407745773,-0.1098272879266169,1.0133503302501181,2.099353845251253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5833385,1.0,0.0,0.0,1.0,2.652855940738601,-0.015145289428550222,0.5303821876750671,0.913660851149704,0.03838763537553921,-0.0037434672881421875,0.40464333057562657,1.0778687878554871,-0.03954913334232735,-0.20098009427359537,0.2637969334779959,0.0892770785163253,0.3054878197421407,-0.4746570007698451,1.0077855261838946,-1.0087092832273477,0.251416920887735,0.17694860911184127,-0.8204309778977679,-0.427497311170382,-0.25846156372634455,1.0615615348155873,0.2857847492860828,-0.9572114958418131,1.1120656495259325,-0.3241633415878839,1.746130246951452,0.4488276588727603,-0.008002949000723009,3.523444329072821,-2.202606626237878,-0.1234671045481479,0.23933690481745193,2.086089639236707,-0.10618250246935754,0.917500561431998,2.030733558049733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6000052,1.0,0.0,0.0,1.0,2.6650736189689757,-0.0020194566422059522,0.5275617252647385,0.9127066809746123,0.03797239490948908,-0.002193680187904982,0.40684124606089106,1.0962183810855919,-0.013733922725837844,-0.1881093879633666,-0.3039678361632358,0.33355819626559163,0.29619352137354477,-0.47758540888912165,1.0363032730904864,-1.0049666833966888,0.2729232474345004,0.2400299460224545,-0.889305488859678,-0.4255820837830847,-0.2634826757608195,1.1035456607563185,0.28678491756215346,-0.9388760764667375,1.1442617837333997,0.15076512512972257,1.5540248575354747,0.012518081995452053,0.5679795343043924,3.04790352683945,-2.9568865401238043,0.7186886601337363,-1.1465955601198143,2.7870998723068814,0.28853100189439923,1.2522658551758443,1.5199964893536442,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6166719,0.0,1.0,0.0,1.0,2.6774712941640573,0.012126582302768706,0.5253744270542805,0.9118337555417899,0.03149147592650142,-0.0009323964807587116,0.40934901958515635,1.1335665094364535,0.02093957804902513,-0.15480273481758,-0.8562587957140945,0.5199641465860692,0.36621227176699167,-0.46963148654784603,1.0595864583700676,-1.0082920129929605,0.270349609896517,0.2785455965333914,-0.9189940596943307,-0.4035409745866801,-0.29668149217004236,1.1544650496991415,0.29540246858462954,-0.9154692171848946,1.1627323005041532,0.5787278220960217,1.3629235767533399,-0.7207343041093279,0.4910569393367813,2.763777167313395,-2.5410443117430646,1.6254302885877767,-2.774826385822945,3.0346146960631564,0.743893295561564,1.5170442895151928,0.8577143497783086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6333386,0.0,1.0,0.0,1.0,2.6895505962391546,0.026948885543012068,0.5234898593618048,0.9106329410099887,0.02140853995480155,-0.00032956118431903147,0.41266113525982545,1.1416064767675587,0.04511755949423368,-0.12931633677006138,-1.0720209807283216,0.5404763960357912,0.41113739436803387,-0.4582944429040661,1.0817341498438362,-1.0289912082492867,0.2892918448161891,0.3321560358513788,-0.9740071353207342,-0.3714009658014729,-0.3559770736100101,1.2046996862660702,0.3115814103404253,-0.8883078323466118,1.1728523192403,0.39258878877284953,1.512243874874159,-1.9998468909068035,0.9301778876154879,3.2090083289848153,-3.1491956373894285,1.6041203814903362,-4.382125767972219,3.2090835587046955,0.95268460959604,1.7429616960342866,0.48828071813456597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6500053,0.0,1.0,0.0,1.0,2.701360774718467,0.04188542636186749,0.5218212637963199,0.9093917301707373,0.011503826561575028,-0.000250161929243177,0.4157815297611515,1.1493764228903667,0.055392558323098195,-0.11260562591365907,-1.0695369396951753,0.4287105386958896,0.35134269619134045,-0.45654516741616513,1.1099946883487979,-1.0749537093463133,0.3013556014955591,0.3855127547667738,-1.0239674575536875,-0.3500701882623101,-0.4427526432441675,1.2614347155948686,0.3271586857501382,-0.8573703777863053,1.17900835699402,0.30678441522834193,0.9700313337169373,-2.8546095498340773,0.663582598273454,3.2974387120636774,-2.8757151763882796,1.0228405798876274,-5.553140034186758,3.7850749184594825,0.9125104108269345,1.9307745630858886,0.332053273772559,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.666672,0.0,1.0,0.0,1.0,2.713186176073581,0.05720815769279124,0.5201595099248278,0.9084076628427854,0.002229924762714551,-0.00131708157651026,0.4180775177167291,1.182042272245085,0.07287805580554207,-0.08835988904437561,-1.1226365814887027,0.22916576873224465,0.3088582565820693,-0.4480682752774937,1.1140685923031564,-1.124145050217726,0.31141130899747743,0.4420708794160822,-1.0698644995813553,-0.3373062116158467,-0.541082111625571,1.3308691025530475,0.34199848486868384,-0.8239485515254447,1.1839207838362702,0.5087937921787787,-0.26816678443422265,-3.1911002875467016,0.6444179875165774,3.374892413338984,-2.4677093099649055,0.887767872628809,-5.777040574564827,3.608777480222951,0.9394712561468997,2.182587236962275,0.23728164362774837,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6833386999999997,0.0,1.0,0.0,1.0,2.7251445870035167,0.07340857482489864,0.5190508844579053,0.9072726289497871,-0.00709097197930517,-0.004613274311567546,0.4204578606412978,1.194072715729274,0.08682291307332024,-0.04244597285464917,-1.140790820007328,-0.012472548869756572,0.3307549399474203,-0.43958534042395303,1.1010557776565382,-1.1813239316712225,0.3228362440406442,0.4980093935375675,-1.1062245990664716,-0.320477866656825,-0.6353210475323667,1.3817275388541324,0.35847445691978524,-0.784617324381747,1.1869177609337211,0.8136135767270981,-1.2315884067384,-3.1710852741101108,0.5549949502044933,3.294393561105887,-1.7650894205952885,1.1603916681296953,-5.648160101288678,1.9115767448834715,0.9267033887379916,2.5566436565766564,0.07431686269563359,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7000053999999998,0.0,1.0,0.0,1.0,2.7367264727379186,0.0894355053164797,0.5187922262485478,0.9059511337076438,-0.014954743890289172,-0.009454706331599012,0.42301242002711237,1.1733948079150371,0.09854447234076447,0.0033797085688098832,-1.0085117116435014,-0.2578689172984087,0.40965552631005625,-0.42094776847901866,1.0730155633059826,-1.229848104093748,0.3299111776706239,0.5518842177458492,-1.1287009312738263,-0.2986264119854123,-0.729354491545867,1.3945884548209462,0.3728886596068428,-0.7387269258633123,1.1863980175472488,0.6969294545212205,-2.1378870546970528,-2.9733617303244926,0.3248585248844286,3.1259229254927905,-0.9837032835058142,1.0980914269166797,-5.521950533499226,-0.10244449506927608,0.8577430497557773,2.877406153366122,-0.09665858642912414,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7166721,0.0,1.0,0.0,1.0,2.747732923478855,0.10550819284698047,0.519223373812489,0.9040882486351344,-0.020567156991246224,-0.015499509269256598,0.42656909867636367,1.1375929888266358,0.11197214321169857,0.051491243982847865,-0.7360759999948242,-0.4431698050169078,0.47695835006655374,-0.4163543121446154,1.0297927333074994,-1.280436187572821,0.3336648831940268,0.6022070327821889,-1.1390147740968843,-0.28387474588684053,-0.8193864334457098,1.3783127155221901,0.38706594909451447,-0.6887035941091327,1.1836958016088446,0.16168042638996769,-3.7003058641862827,-2.528569358362882,0.07821441589102673,2.8387154536295625,-0.17660033709211995,0.6280751916496196,-5.033573368429097,-1.3966966760541835,0.6272299860949081,3.051954668620028,-0.3359537352639866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7333388,0.0,1.0,0.0,1.0,2.7578735207648992,0.12111979971525666,0.5207155387554632,0.9021994606960221,-0.02302055497639159,-0.0211891866475835,0.4301827582988419,1.1090076446119213,0.11735173850848052,0.07075320732049298,-0.5261480424106361,-0.5749098750302335,0.5252465188276215,-0.4155584101539913,0.9496717878127156,-1.3141339179438012,0.33251833008128584,0.6465082554478648,-1.1345876209502528,-0.27769053039207886,-0.8971406060650614,1.3480318058393617,0.3937963676253388,-0.6369949001123335,1.1751995373082003,0.04502505023975779,-5.684951619545644,-1.4168049934393443,-0.1301677571770942,2.6462559801893852,0.27229434807466224,0.23268016247431222,-4.345230249230073,-2.4025087116937853,0.6328055998861065,3.133789423016627,-0.471507661300402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7500055,0.0,1.0,0.0,1.0,2.767815268518151,0.13675359439159793,0.5220246170733429,0.899908244820615,-0.02454327347624125,-0.02770901043571917,0.434505453788124,1.088869469566654,0.10806003137212827,0.04734831500959873,-0.42290063205339967,-0.6606793489660905,0.6102457522572632,-0.41485347413495344,0.8402939669925367,-1.327663115141132,0.32932594927693987,0.6904157418722338,-1.1299382776747724,-0.2761187249590193,-0.9642277314353955,1.2982289316318165,0.408159511277758,-0.5842437377559503,1.1679788481316538,-0.02533601764438415,-7.276693212684124,-0.1012123129635634,-0.21211202652102254,2.571921540491487,0.31663695397731934,-0.2050572538199122,-3.6036686359218915,-3.27749453689691,0.8515004352880748,3.086757441963326,-0.42454381934161994,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7666722,0.0,1.0,0.0,1.0,2.777484254325405,0.15182281346086032,0.5230796269838155,0.8972987137178708,-0.024866675940954527,-0.03390428449164165,0.43941684797127645,1.0766943564666214,0.08553808288035125,0.009046403389768164,-0.2668606490379697,-0.6976727280982383,0.7158460310333556,-0.4164029457645386,0.7071148622770306,-1.3175076684567408,0.32544791505645,0.7322391449256838,-1.1240330347085452,-0.2845257858565595,-1.0172631341737002,1.2387817694431622,0.42217977223497033,-0.5341027795963932,1.1610480483605583,-0.2777516967086545,-8.090068309216074,0.972885975559469,-0.35557005714814266,2.527075177785601,0.3023567295500864,-0.699544775428696,-2.6858715774652198,-3.7239887297396868,0.993021858660959,2.8804141630079516,-0.12627181124084472,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7833389,0.0,1.0,0.0,1.0,2.7874943116253523,0.16686715570862878,0.5235122787125635,0.8941521514088829,-0.023837928844478634,-0.0397921982758147,0.44535408860327086,1.0946476889377965,0.06147826435137477,-0.011073413452884172,-0.003196781471956789,-0.7724000952042192,0.7519208498406493,-0.4241118825420217,0.5706244840141136,-1.295233517763418,0.31747359033399797,0.7746517496034323,-1.1198596998659875,-0.2994369307762942,-1.0537569630756747,1.1740957257079117,0.4412603061012472,-0.48822974029474103,1.1637697793388382,-0.4820116370449383,-7.969628246627626,1.751633396368752,-0.5263964609259951,2.4719272367576117,0.5739407021021905,-1.1346906437106934,-1.6196097956455948,-4.071936855961511,1.1264732363561165,2.692143656483244,0.2803461617461991,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8000056,0.0,1.0,0.0,0.0,2.797788707712151,0.18218377539857636,0.5243738945122686,0.8911941989457034,-0.019681243437154165,-0.04511839054469418,0.45094332155709993,1.1097063865446661,0.04985316753008756,-0.004452262811074324,0.12880701300383718,-0.7846362073159473,0.817352190855986,-0.43247003246681237,0.4414600560808933,-1.2591197718022227,0.3079013312658194,0.8146368842794199,-1.104901639709092,-0.32234888295962555,-1.071250235335873,1.1030502694486548,0.4597289552117233,-0.4443644782373746,1.170392939108509,-0.36910731761710314,-7.146173086236981,2.485080779664693,-0.5730529354441576,2.3246940424199023,0.9894981786327202,-1.4343593769993714,-0.7278406945202984,-4.038211792864392,1.2685953191104027,2.610223700069628,0.32044408286046616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8166723,0.0,1.0,0.0,0.0,2.8079719158517107,0.19764949712463203,0.5255567903361538,0.8874581086620023,-0.016651680183681277,-0.050223450971537874,0.4578410552687818,1.0974387903245144,0.028937562864091104,-0.013303143921532812,0.012161110196106995,-0.752606197087879,0.8949893982806907,-0.43641548440307965,0.3324182380613418,-1.212397326102543,0.2983717876156637,0.8521417059970319,-1.0868763612783516,-0.34724900563356503,-1.0780183680823976,1.0394883967316457,0.4835469013112819,-0.4012221096108401,1.1744512701304592,0.14044350170771516,-5.8535891933019775,3.2842542080732975,-0.43308677761634595,2.1992001869399393,1.2015937886737564,-1.3309950002421636,-0.2389690853875686,-3.3477895652068477,1.4426747453171493,2.7594335851926735,0.06385868475295593,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.833339,0.0,1.0,0.0,0.0,2.818113323195374,0.212539008620987,0.5265632413368442,0.8837423645410056,-0.014501467170026991,-0.05591486483650581,0.46439494878358034,1.0613312683758704,-0.01146525777317059,-0.031018627924214504,-0.11382948929165737,-0.6842098427969495,0.8550765412952775,-0.4277885730469884,0.24634002606488115,-1.1496444125828322,0.2934650764728227,0.8879437037907637,-1.0648484333137143,-0.3667154717006977,-1.079215887446731,0.9914570607557889,0.507818209567278,-0.35238317476871317,1.1725215661908532,0.7139920716030618,-4.682583783336263,4.14862895784951,-0.1754787219767981,1.963184174761373,1.4008462390848517,-1.020060289692236,0.20913406393837988,-2.4518934517347324,1.3979899942577585,3.0820154993927,-0.40340477660655444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8500057,0.0,1.0,0.0,0.0,2.828298332721168,0.22655536121053022,0.5275792194445337,0.880185479495833,-0.01383148862208296,-0.06098605107271461,0.47049220310409395,1.0340544220187633,-0.034046482954476265,-0.054221313887574146,-0.49448728143634096,-0.573260091578959,0.8306633268725812,-0.41261570108350615,0.17633179977788083,-1.074109417598962,0.2925224851845223,0.9175813093680226,-1.0401813932524406,-0.3812510832939922,-1.071047218675514,0.9577584515475912,0.5301466609858735,-0.2984880541633835,1.1610044173499223,0.7768467625025671,-3.919425119662996,4.706540595618182,0.26456545759221295,1.7998151399340407,1.5094077822321814,-0.4957845424843035,0.49830545071904225,-1.259503982981179,1.4916683085528644,3.1463928288857823,-0.6464154146167677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8666724,0.0,1.0,1.0,0.0,2.8382209619352308,0.24057312353895502,0.5281146183663734,0.8765262761223874,-0.01808850057996591,-0.06804373349976098,0.4761770088372626,1.038819642953966,-0.021288466518291083,-0.06900752127740774,-0.9794979434820352,-0.48140855129660265,0.8599186057126996,-0.40189362917378535,0.11569226078110664,-0.9927594122928531,0.302283942696927,0.9479376617762411,-1.014534739945456,-0.38324165616914396,-1.062605672535733,0.949473510689484,0.557540585963594,-0.24750320404633183,1.1509743426092667,1.3819459734478274,-3.0108373248780014,4.988056262071078,0.6650463860043465,1.666800878956799,1.5933510827419761,0.05156068588132247,0.5037666249398213,0.28435999580446464,1.7749598204235824,3.068639528156043,-0.7879044980696231,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8833390999999997,0.0,1.0,1.0,0.0,2.8478065587784327,0.25523504640835787,0.5289042437981033,0.8725078787019379,-0.02529402487388245,-0.07554972380572572,0.48206063222545203,1.0383513019439456,0.015830367646722132,-0.08509491880466974,-1.2109681761647122,-0.36925739990139045,0.8773931005749175,-0.36655074317218034,0.07597035489279245,-0.907840542992842,0.31469074238775957,0.9731414497866412,-0.9870695842709692,-0.37953239032723574,-1.054254964259745,0.9672371370317397,0.5893121066639809,-0.19619986531554684,1.1347408815539684,2.3730937283448768,-1.6908273940330958,4.979808414248881,0.8994323605405352,1.4875376299217145,1.5380496118305627,0.3370635740248367,0.483377648753594,1.5272052045433648,1.9606042276629136,2.839286906373859,-0.8686064249093366,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9000057999999997,0.0,1.0,1.0,0.0,2.856352543980511,0.27018412018485205,0.528971397745904,0.8685013036444117,-0.03383483488717785,-0.08278399704002884,0.4875525606026405,1.0303145654074697,0.05087937128032932,-0.15262538032130513,-1.1441616296362758,-0.23143156510220148,0.850899081034355,-0.32279034668937423,0.05933123492484385,-0.8267654664973295,0.33226508134376886,0.9975223486094735,-0.9632663170144632,-0.37200618123074447,-1.0464930520187699,1.0003804526546098,0.622894190925973,-0.15286011788140944,1.1220207372051938,1.985477575533536,-0.2780111787515553,4.2340859951342535,0.9437136829198997,1.6211997755223273,1.1004291459300912,0.5658304110553249,0.3593053775365809,2.4946362370988884,1.879020500309584,2.3902748191879386,-0.6425994336138153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9166725,0.0,1.0,1.0,0.0,2.864824739529678,0.28551007818141694,0.5274669438166921,0.8646562390431325,-0.04116397033070478,-0.08771230242979246,0.4929317070678886,1.0263408974516,0.0527161411668699,-0.2046990105486564,-0.8409109456130641,0.05479586645794943,0.8703253348755485,-0.30036802495589077,0.06670329706699536,-0.7667040608826339,0.34614792806600175,1.0271815503840371,-0.9503885393780231,-0.36067133890336417,-1.042278094388167,1.0503918445774518,0.6519462486090004,-0.11652387865762762,1.1133208575935456,1.0958227408622345,0.8374746186820227,3.254065512383462,0.6272495644641275,1.6535110568034899,0.4968555833256028,0.5323963039011683,0.2774589590515066,2.580829383767806,1.4432975601823843,1.5838750259562397,-0.1759819436516948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9333392,0.0,1.0,1.0,0.0,2.873238731229636,0.3005957407977784,0.52580004732111,0.8608806732290866,-0.04770665059951295,-0.08829880967507427,0.498810447123129,1.0171383821340527,0.04112675159430418,-0.2225427454675536,-0.537755439863568,0.4918773720913833,0.9134700752776546,-0.286262848939117,0.08724711137921919,-0.7182963991468466,0.3531734419758774,1.052639494070327,-0.9467044311132375,-0.35425960227428527,-1.0372444015531224,1.0864082708354956,0.6710042058185565,-0.10006417809119972,1.1161546606846744,0.611676036285833,1.5109429848292182,2.1914633294114356,0.24547481613801914,1.589005034915628,-0.3450957851846628,0.41007005206244734,0.29849908571710715,1.9965894739007315,0.9250341779126907,0.1523570522367704,0.893832131993592,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9500059,0.0,0.0,1.0,0.0,2.8816439615274128,0.315640761300046,0.5235057921328236,0.8573650950728064,-0.05434402381032758,-0.08439916215770994,0.5048253185548212,1.0242554736472929,0.04290386435279242,-0.22095134617384588,-0.24545738220053176,0.931073612788172,0.8857110306464429,-0.2799787829679606,0.11706816395750162,-0.6936551371380307,0.3543304383022568,1.0801484908148937,-0.9618917552238976,-0.3470023098299458,-1.0323281049643245,1.1169449601467745,0.6827807828750353,-0.11144530009259845,1.1431153215821408,-1.1901544009930944,3.227337993134471,-2.8455028710752384,-0.04149375205766468,1.6170773316567142,-1.4700647153125894,0.30599534546980717,0.3923931059343519,1.447576620720861,-0.045927875433411286,-1.5117195381191044,1.5809307611729642,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9666726,0.0,0.0,1.0,0.0,2.889737343126833,0.3310975519109185,0.5213960459654067,0.8545163755234878,-0.06032563702020668,-0.07625717574898952,0.510242515503261,1.076283738227872,0.038465979592246013,-0.2047380739191063,0.16453628450572588,1.2690521624341558,0.8781873387775371,-0.32593474164918024,0.19482525963956776,-0.813146684549546,0.35179031414103845,1.1065421795973729,-0.9957066862946382,-0.344059737025602,-1.0241646051957702,1.1346609213646324,0.6694732735755844,-0.15045493014313907,1.1688524581191573,-2.011808608521507,3.377413439646082,-5.519537008844342,-0.29574482860204926,1.4325738112398756,-2.7214561591240334,-0.003686854752632445,0.581033135384438,0.8486436187367463,-1.3483222326415003,-2.7565349516395035,1.3432747270867738,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9833393,1.0,0.0,1.0,0.0,2.898625603538793,0.34768835679428717,0.5190452596927593,0.851669408081968,-0.06392790204346868,-0.06402383045294385,0.5162106080000329,1.1465252306227205,0.00909438613210728,-0.19284349643063123,0.4982468030635727,1.462779478861078,0.8971666789541524,-0.34703920403925137,0.22964883710660033,-0.8776400720686427,0.34447225763253325,1.127901046694477,-1.0526071419584426,-0.3471252052341572,-1.0129602950493009,1.145233137347574,0.6378366185655031,-0.20332998224957868,1.187891235370015,-1.7080003493565057,2.6379272958519304,-4.595217095792589,-0.25035232225331927,0.6140805814291449,-4.236733056546747,-0.1973991233131769,0.7516045633649675,0.4606812446143931,-2.091549396451713,-3.646909711377809,1.0772200339635891,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.000006,1.0,0.0,1.0,0.0,2.9081348820669817,0.3648784511133467,0.5166655183205013,0.848882685955335,-0.06680747282365046,-0.05024724056704324,0.5219292690351549,1.1929122412665953,-0.03538749973816091,-0.15751817592890024,0.5474867074165496,1.4861425711979983,0.8224089215413262,-0.3828682004944204,0.2827563453631185,-0.9663208940904386,0.34344522004243966,1.1270115732503831,-1.1369314039617335,-0.35063972096264945,-0.9991110696433004,1.1500169935638618,0.5997548209239009,-0.27201883031638013,1.2047598643992792,-1.8666613275130672,3.124712804002526,-4.963437974143961,0.3591260685410309,-0.5189060092845366,-4.9209623803668165,-0.10375354484245164,0.9859776371484522,0.18618936897303198,-2.184352297169883,-4.5951404442714265,1.3905441509476657,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0166727,1.0,0.0,1.0,0.0,2.9183759085367016,0.38234404196048083,0.5146828308322414,0.8463812746742742,-0.06980752464404671,-0.037325071618631335,0.526661643194647,1.2140209329995248,-0.08698582158267776,-0.10287919649996241,0.5573656348293792,1.3342777637818661,0.672324311667529,-0.40926137273377544,0.33380613888753813,-1.043088335435973,0.35644315052563885,1.1106041451245918,-1.2166395493681619,-0.35058366364580856,-0.9800943080791766,1.1514394620592996,0.5650247297030205,-0.35650163673465585,1.234242799771214,-1.4039505914564159,3.2369681565317716,-4.47917050285675,0.5827468369714593,-1.007882124191895,-4.646069771887823,0.02381216038486383,1.34286895855295,0.016723780716508773,-1.9861627074580017,-5.173960854826973,1.73142340110841,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0333394,1.0,0.0,1.0,0.0,2.9290791517594523,0.3996334093630099,0.5133170766119931,0.8444913457287256,-0.07108690763891662,-0.025747324124273573,0.5302057089961045,1.2156942878649055,-0.12363825705413117,-0.03819477648038986,0.692578592404781,1.008685550067798,0.5329630108889132,-0.4296666471396737,0.39065549971205465,-1.1156268761303638,0.3628701534579441,1.093415435251845,-1.291800706095979,-0.34984598069567663,-0.9543486815002715,1.1505744540359975,0.5335492649311203,-0.44448453707466956,1.2624740931977863,-1.1337940840051073,3.3998316497156953,-3.852296766893957,0.27804686467641065,-1.2653727474624814,-4.30194075030834,-0.015357260894666961,1.7336009467586133,-0.07767010345895375,-1.885874704057702,-5.327771264061243,1.708528242161538,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0500061,1.0,0.0,1.0,0.0,2.939888677313393,0.41690066611369375,0.5127390956630038,0.8429639647937355,-0.06920185457087694,-0.016365493867943205,0.5332494988217387,1.18886812875483,-0.14064008690009155,0.03854775495080531,0.8841933171754031,0.5722056547750948,0.41633648057294764,-0.4470545844535513,0.4471340872001713,-1.171498484485556,0.3657113978846435,1.068424969184326,-1.3600378611744899,-0.35109557336611485,-0.9223074942804931,1.148850453432661,0.5021621138427835,-0.5340943673881149,1.2911938550784814,-0.9244120377816073,3.2293921938449657,-2.6390425515345974,0.5316060391760413,-2.0221463746773476,-3.9956572806584756,-0.1926611407968673,2.091702369013344,-0.17572952464051697,-1.9117625221629782,-5.508742571008599,1.572948031399731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0666728,1.0,0.0,1.0,0.0,2.9502232349549034,0.43350095156958746,0.5133864176396582,0.8419949945428183,-0.0638644592602039,-0.009356707224453888,0.5356101306343606,1.1482402771951539,-0.14147430348494222,0.10731024262867736,0.861054377240758,0.11136708071590332,0.2884700179873671,-0.4604804433598631,0.49830212146636643,-1.2035951371176872,0.38059039020421476,1.0260104212861751,-1.4249895484950803,-0.3562680315663149,-0.8846251297530021,1.1447167914993452,0.4698237200748529,-0.6281096566911276,1.314905799107646,-0.5804857732564752,3.043237294171841,-1.4286774841011463,1.2613176044099648,-3.4057742052893105,-3.3783649883217595,-0.24179529897153682,2.3967166218958202,-0.19175907924966137,-1.6504737360779325,-5.429628425927939,1.0801511747744938,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0833395,1.0,0.0,1.0,0.0,2.960143121828372,0.44984601078169484,0.5148253386257432,0.8413548537473744,-0.05815299738776159,-0.006804512420247434,0.5373024637774109,1.0926574391499857,-0.13290133607767463,0.14015257824017469,0.6509281081965639,-0.2780852803781181,0.1841024625759592,-0.4664041489278187,0.5485755332217189,-1.2191211625340932,0.40775540211948264,0.9548989352897352,-1.4726502526762144,-0.3591554327848527,-0.842416780436191,1.1424584713404002,0.4471462126086034,-0.7150823435609412,1.3271989662477095,-0.1389587069006984,2.861863592672708,-0.4948471084586744,2.1388120863124227,-5.07538879677495,-2.415632416663453,-0.23418741902261817,2.5835631500089975,-0.11608895605876446,-1.2550134499897767,-4.896115602507955,0.3545201207551446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1000061999999997,1.0,0.0,1.0,0.0,2.9692686104792476,0.46504053310446275,0.516633011657323,0.8409578555682314,-0.052263645228288025,-0.007245349103376761,0.5385219600553942,1.026050061842165,-0.11349494818920203,0.13550707313143762,0.5117254599147365,-0.5246357893422259,0.16226013169248293,-0.46511240952046684,0.5936977653463629,-1.2200900737227836,0.45188426900210127,0.856830456367757,-1.5055107900926898,-0.36407429447956347,-0.7985061858484922,1.140847151891456,0.4279898547409637,-0.7913138365157663,1.3267231601008256,0.0821535061786833,2.622967740553242,0.12598640371163947,2.8550341426887327,-6.67108136450637,-0.9780619000064957,-0.2734808724985197,2.6219728515916407,-0.011867469631134138,-1.1450160133725307,-4.486286489965671,-0.19983100684578406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1166728999999997,1.0,0.0,1.0,0.0,2.977618293335514,0.47964366854617047,0.5181707352845355,0.840283624254104,-0.04628937350290141,-0.009425975086950499,0.5400850633971994,0.9887334086963467,-0.09403697563394925,0.13700352925577727,0.3771079006285861,-0.6815744379786822,0.16993674773830691,-0.46366569324496215,0.6360079661046764,-1.2149216073446116,0.5029233972113832,0.7325291117340986,-1.505252381213891,-0.36827148010019484,-0.7550175105849461,1.1420628882281978,0.40897893582845146,-0.8646255256455629,1.3205379193641162,0.046319933302011736,2.421112513469705,0.6655201169992404,3.033968578007446,-7.880731356869639,0.5149571483690101,-0.2893221565147758,2.654249946229525,-0.011919492831578683,-0.8165114778533107,-4.006297253786694,-1.0281927361474381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1333396,1.0,0.0,1.0,0.0,2.985535200912884,0.4939997421943628,0.5203293633443135,0.8396168772396514,-0.04087079036412975,-0.013265009484078803,0.5414767931063481,0.968980797824305,-0.07068393842647203,0.16033031473346002,0.2098146450637985,-0.7663976113842563,0.16293324581642754,-0.46356840865573756,0.6744016772028539,-1.197906025454801,0.5530167572002547,0.5941388857566786,-1.4883455174832463,-0.3737183856515331,-0.710031010690845,1.1404498346691039,0.40077275104508814,-0.9248573453951396,1.2924500003497286,0.2685913832044192,2.174832766075361,1.021311920763308,2.6809754440884856,-8.248083797281343,1.5089464027925181,-0.17334050546784238,2.633533089104478,-0.15993433015124806,-0.2969999740688528,-3.2058398346908623,-2.125533369238888,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1500063,1.0,0.0,1.0,0.0,2.9927503613720123,0.5083708409161373,0.5229807676408463,0.8387921291094674,-0.03647186350119416,-0.018148412235579506,0.5429255956851585,0.961288840549917,-0.020536139360384786,0.17481568500935069,0.18168414747791697,-0.774972769303597,0.2143202792652836,-0.45471262923205596,0.7085025366293728,-1.18087780856504,0.5922894240793624,0.45759243528580074,-1.4549540671910468,-0.3740495085051566,-0.667232898712591,1.1367317332275342,0.39907891689282476,-0.9714870671912473,1.2496866653539287,0.36311488892417937,1.9311955807805168,1.1943583649992051,1.502341474039084,-7.482002175697967,2.5324522418133646,-0.11046615400514215,2.724546864661558,-0.37721620730226196,-0.11539062698645311,-2.376117025294775,-2.8381681874362847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.166673,1.0,0.0,1.0,0.0,2.998880976482528,0.5231896029056912,0.5258991616088492,0.8375485674854138,-0.03138800746119226,-0.02232683877346565,0.5450033966510034,0.9877800911414137,0.03826376277903604,0.15842345138692532,0.3233694842677037,-0.7380847373573876,0.3321967379777621,-0.4514645548172723,0.7387749919752432,-1.1580940003309366,0.6030949064909891,0.344738314433268,-1.4039302739259847,-0.3774005981494481,-0.6192126002323354,1.1278759359446147,0.3969263891194979,-1.0040614046461005,1.19784420489064,0.0033531630931003835,1.8041703035854308,1.4748362466288742,-0.20817453973736263,-5.524929987780942,3.63413451106978,-0.22534785823803732,2.9043817656051942,-0.5569195930020403,-0.11980767661023396,-1.569344286378826,-3.1648349876649347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1833397,1.0,0.0,1.0,0.0,3.0045428327626977,0.5391406939759747,0.5282527067839204,0.8356598468146413,-0.025384889826209373,-0.02534402354664968,0.5480747287192762,1.0187867580598993,0.07592060705473619,0.12618799773465528,0.4639934569524857,-0.6529382175341729,0.3892315094003616,-0.4546008569054084,0.7686416670269074,-1.131716502021661,0.585350258876481,0.2734277340311035,-1.3338160078797534,-0.3815611188029484,-0.5704199795669668,1.11816770966616,0.3950853196853052,-1.0237986480268273,1.1441919547760984,-0.2300423577079557,1.7398126726123524,1.5155030298247938,-1.545564229080902,-3.5922483399471266,5.503056641518301,-0.30426836815031527,2.9058545581394855,-0.6410428423352951,-0.06603416658109185,-0.8559888446811539,-3.2255294212519874,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2000064,1.0,0.0,1.0,0.0,3.0097849010720266,0.5554092563989023,0.530410452111214,0.8339109097152068,-0.019129918380470807,-0.02701513906356478,0.5509054575352191,1.0127473262698075,0.09872315089274691,0.09905819472873334,0.6144053454662031,-0.4864508476151097,0.3751161202623471,-0.4591326487436947,0.7967688637164998,-1.1075771316365748,0.5515759958173437,0.22499646361847447,-1.2204946856715986,-0.3875428973723498,-0.5223505879040486,1.1065077984639153,0.39472524583118374,-1.0325944232013953,1.090326342480279,-0.46948479746601374,1.6458308883668213,1.2864164568023948,-1.0002500879910987,-2.508784484694884,4.564319370788942,-0.48894827466469226,2.778870124858909,-0.7024373794618354,-0.10468527688478325,-0.34620521241753827,-2.9823674858555247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2166731,1.0,0.0,1.0,0.0,3.0145222123270705,0.5714910865840134,0.5321539583856518,0.832183347504021,-0.012555818673268649,-0.026342863979635877,0.5537321383772087,0.9969477186310259,0.10183415625141373,0.06727344380251686,0.7385997986232531,-0.3287270445374355,0.4376196171837686,-0.47025038145326203,0.823502806361194,-1.0888358677004841,0.5520085225934385,0.18980141728897504,-1.1816717245654973,-0.39785942722165646,-0.4777907901469948,1.0947530835216068,0.39159580347679396,-1.035338844854426,1.0447795064230818,-0.7497193280113973,1.5890981282241443,1.1278952142348635,0.7735789923967787,-1.7182150777632899,1.4724510673815379,-0.5573619300926227,2.6228870054400284,-0.7148932020706928,-0.107100645018261,0.04445882677616777,-2.356767992765372,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2333398,1.0,0.0,1.0,0.0,3.019335851190788,0.587351201651031,0.5334740442866831,0.8298748345514412,-0.006046766234908533,-0.0246731502282891,0.5573709996529518,0.9872151676810317,0.1225876029109195,0.016157933015365746,0.9407260788379843,-0.22998503245786328,0.5931076833502243,-0.4841233429920298,0.8497389072638465,-1.0699805493023984,0.5773620138025025,0.16772251314535963,-1.1714128852621428,-0.40612166553289925,-0.434920846196914,1.082677977402012,0.39115521719053203,-1.0311124593449346,1.0117672522702337,-1.171790273075677,1.6892167392640745,1.0075618200421457,-0.7746939174198063,-0.8179709943561287,2.0563753062226806,-0.6419426341104805,2.5232893426140866,-0.7033491853719402,-0.21318476192889374,0.5387863563802969,-1.5549163989726744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2500065,1.0,0.0,1.0,1.0,3.023138646613157,0.6034809294435167,0.533664241154105,0.8266435929745537,0.002341027686139345,-0.020727009178696267,0.5623391155468374,0.9720631692684076,0.08284516450717294,-0.013126528210588764,1.0354275012047953,-0.21122241956224186,0.5140506800961878,-0.5093101353418028,0.8798101436177791,-1.0552504065282913,0.5261853403665171,0.16253566294570446,-1.1131257439330542,-0.41925755782151475,-0.39368097717390244,1.0713080637859298,0.38448963053351337,-1.017379263722659,0.9929488561295661,-1.2646713022510074,1.6921939565282653,1.0549062175909147,-3.098500108265405,0.18169377554965677,3.7668022782104478,-0.7884359692457206,2.4186602571793885,-0.6945544380778508,-0.2020863359195914,0.6842266294949868,-0.08196993692406346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2666732,1.0,0.0,1.0,1.0,3.028663585062075,0.6184994709222172,0.5341788467485824,0.824966320791255,0.01001555044144149,-0.017879091209567058,0.5648102304376358,0.9561629642882503,0.04752419551509568,-0.038730185940726795,0.8673015591036476,-0.22859198238240075,0.3963310931080753,-0.5262791373784835,0.9061454852943858,-1.0348169383889534,0.47407847029364847,0.17377898444326656,-1.0458525582016427,-0.43240291707015455,-0.3542986763802506,1.0595261164957879,0.3844189925207899,-1.0083048594133264,1.009034915574769,-0.9620487278203818,1.454831700488192,1.263027175533046,-2.4071019093140276,1.0935948300755434,3.607236041116043,-0.7426396848147181,2.206743662508917,-0.4741497280754154,-0.18618357168580554,0.6272521361075916,1.458773002210501,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2833399,1.0,0.0,1.0,1.0,3.0332019666615637,0.6337916622395168,0.5336693011091934,0.8227075605368388,0.016304545181195118,-0.015783307035352957,0.568011724228458,0.9617909157668968,0.09136432201545552,-0.09748891546070354,0.6069411099593578,-0.1559065605052649,0.4551561025358275,-0.5413784904057307,0.9283046306228322,-1.013149416475378,0.4459484495825889,0.19898889685454457,-0.9928843020801167,-0.44401226349131767,-0.3201227079740277,1.0555030412401007,0.37828349906508174,-0.9964708173689303,1.0415747201214496,-0.7465102867239641,1.322824890085428,1.2183807484193145,-1.7498966959148625,1.683623013337715,3.2247891803886737,-0.5060712282288311,1.8817143835217376,-0.10881199599944064,-0.4801376416004072,0.7466832991481563,2.02049159890647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3000066,1.0,0.0,0.0,1.0,3.0371963027434528,0.6496706449308939,0.5323860707802532,0.8204631140628228,0.019696945826090734,-0.014406083361395573,0.5711784078111182,0.9647569744301202,0.1154629794537714,-0.1509967796336343,0.3906561773014274,-0.014068456011231995,0.38375956008538614,-0.5511628633699681,0.9502397364855594,-0.994204165549593,0.41574846377004,0.22989986379605795,-0.9383593705360749,-0.44927199174919746,-0.2915747381485671,1.0558990427083401,0.3684143724582669,-0.9834153663295012,1.076384770237758,-0.5802236261398745,1.38269794970266,0.7263893694246577,-1.977946551262545,1.8498439552523582,3.446487260461047,-0.3197720571558233,1.449064699567846,0.3816196211254892,-0.5557034178636048,0.6912902916265907,1.9714764604761925,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3166732999999997,1.0,0.0,0.0,1.0,3.0407603163017214,0.6654944764213029,0.5301869255382285,0.8189258551129411,0.021684259034447085,-0.012384185515157672,0.573355795895351,0.9356577346885285,0.11430492887228902,-0.16788705322683442,0.12673070890257968,0.19742570739351023,0.30312983349107175,-0.5607193166253016,0.9743946544594508,-0.9889363890685982,0.380016766010734,0.26065048535255353,-0.8780011636322644,-0.4546713533813156,-0.27182045471745286,1.0682237207189251,0.35976001475606706,-0.9734277615620245,1.1072907335690867,-0.5706741764878527,1.5794829510673936,-0.2749075636051308,-0.6497548871338432,2.949665589074545,-0.374021362028442,-0.06752102673591738,0.696972242780508,1.0106318149218962,-0.38932403534373305,0.7889074535141999,1.6623928445720735,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3333399999999997,0.0,0.0,0.0,1.0,3.0442639549805888,0.6805220057642417,0.5282861538912503,0.817557104361242,0.019477823426806717,-0.010620788376835277,0.5754200156036197,0.9479620562547131,0.11422109166961239,-0.13596427430632665,-0.3545292546481285,0.45617501227302626,0.32878112628812045,-0.5701853739645083,1.0028892734866692,-1.0033677693302683,0.39408992421525274,0.3282222467429154,-0.9508267742051137,-0.4515226971417965,-0.2683422835910673,1.0895868372478577,0.3554368786585401,-0.957118398618531,1.1317979758830168,-0.18257687175141799,1.3409012107725191,-1.4373821481179387,0.502894731238541,2.7241106686963583,-2.582822061966516,0.502568457463438,-0.23191207234436736,1.492135269052241,-0.051654642365268906,1.1048843674345052,1.099805887253447,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3500067,0.0,1.0,0.0,1.0,3.047820007249361,0.6966949179286517,0.5269910228567164,0.8159439156975318,0.01242292585795579,-0.009685815796045697,0.5779164146497936,1.0085921294940856,0.11748935259917273,-0.10179630435388361,-0.7069511154904189,0.6227910853538362,0.2703113749351259,-0.5668052245221403,1.0190914508786155,-1.0368492231646727,0.39677995724500076,0.3514543559164767,-0.9640954045526191,-0.4379190379613038,-0.2795508725897366,1.117961662496351,0.3580381899002486,-0.9365982089885831,1.1439510031312607,0.5930623641442535,0.7698262186993802,-2.375907416814015,0.5495568926136127,2.2581470690033574,-1.8824623910224803,1.0847168108642717,-1.0582248837396964,1.5906865701999686,0.2124714188496617,1.3796039127931214,0.553193318475985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3666734,0.0,1.0,0.0,1.0,3.0517307786926837,0.7136264629553694,0.5259443129978262,0.81519139905096,0.0038210357335714687,-0.009032231708201038,0.5791086265888556,1.0492421258726834,0.14136529893549846,-0.11367193496566923,-0.7837191398012271,0.6575810365998933,0.20876231413706628,-0.5504165889555422,1.0285501987650632,-1.0825648416178966,0.41240852393949934,0.4034939662528319,-1.0135756460700225,-0.4153653977985334,-0.3036165169307161,1.1426098289669613,0.36251927345162344,-0.9111315095518328,1.1502377900451042,1.122381828429852,0.2495988204284784,-3.2810547105474854,0.7345851700429427,3.0128917131742474,-2.9373654448718387,1.4277544104573838,-1.973394330909657,1.5712018848975668,0.2857611083982392,1.5132190340766913,0.4198440368070254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3833401,0.0,1.0,0.0,1.0,3.0549199344633107,0.7313292942794495,0.523852562862206,0.8140787775035165,-0.0046029223129044694,-0.00832451943523701,0.58067655325554,1.0585938628254894,0.16162738248825292,-0.12286279810634816,-0.9143996897673528,0.61176157134607,0.24753179374957932,-0.5293924220823567,1.0274114281994862,-1.1462179322532362,0.4212661785521102,0.4518842805483992,-1.06200778187271,-0.39032712909576367,-0.34533081517968056,1.1703351634063957,0.36756357923093047,-0.8861574736380912,1.157945832347764,1.374791346272172,-0.36359474614654796,-3.731007031523076,0.574113232171667,2.8412421386983397,-2.7700593767620454,1.4971804139056264,-3.3396025554140545,2.1296636121593027,0.4138474490328421,1.59024203540277,0.34832436123916577,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4000068,0.0,1.0,0.0,1.0,3.0582004318631935,0.7487532476495866,0.522046789836607,0.8127884668485489,-0.014536309191397928,-0.009563898384970277,0.5822990088612202,1.052995111669036,0.16838672487836134,-0.0727144452570071,-1.1195419167555254,0.49063277770418234,0.2776636880317218,-0.5045901190937134,1.0164303496538618,-1.2069319914024679,0.4315456699527704,0.49820222695891914,-1.1059111432993824,-0.36545928418965157,-0.41493682475135496,1.2135987580165122,0.3763142160092148,-0.8581233356889381,1.1618486253080338,1.747107299332294,-0.9306100634844283,-4.050992191975226,0.6136322694854012,2.8350955718194175,-2.374141085841617,1.4308905913456305,-4.704439240933321,2.988733338003905,0.625267823075169,1.8269064350875264,0.07438081901589175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4166735,0.0,1.0,0.0,1.0,3.060977880787241,0.7663375321924734,0.5211865498727748,0.8111772084976524,-0.02457122177129741,-0.012472424290349983,0.5841508624550197,1.0448225549123495,0.19332623992956424,0.00022403035125328,-1.1382709693646005,0.28509985224675466,0.345389901825023,-0.4711553956307936,0.9963910307093343,-1.2812512753852232,0.44172062844377485,0.5463876552820846,-1.141145976343503,-0.34263068065820323,-0.5021457701734073,1.269959807255415,0.3884058816846243,-0.8252604706747446,1.1604251979403484,1.746908338133287,-1.898684624072475,-4.370406304098263,0.5192880572923925,2.7738443982206547,-1.734441807556467,1.384937666855057,-5.2633336707856575,3.290657256729459,0.7068144515974969,2.0485374977645048,-0.20179811578999993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4333402,0.0,1.0,0.0,1.0,3.0631449594316615,0.7838192721826226,0.5214084011306764,0.8090166359910342,-0.03277211036626059,-0.01663721768058487,0.5866355550593066,1.0168368583281977,0.22093014601297,0.02960641676915604,-0.9058390952341302,0.02760572188877153,0.4837285267777688,-0.4463597246953813,0.9531407356058044,-1.352612492899497,0.4488553064817206,0.5906638918225675,-1.1637259858473852,-0.3192946029653052,-0.5903816313331216,1.323287552617978,0.3998747448500948,-0.7898386158609547,1.1551220079951594,1.4714551897766968,-4.1327649702347085,-3.122706519382629,0.20507378924556527,2.584222196623768,-1.1269866439745169,1.398664124740537,-5.225920577280431,2.600110537521415,0.6388146834471402,2.149419025397548,-0.1776818099030884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4500069,0.0,1.0,0.0,1.0,3.064477969275377,0.8008599805599844,0.5212456705098488,0.8059666858852869,-0.037196731416713195,-0.020667477244827124,0.5904294706392414,0.9703585363432156,0.24369979152605217,0.017107207826284464,-0.46277649853871217,-0.21688629187355776,0.6522774280025876,-0.4221067912078911,0.8586319228505127,-1.3853417008784121,0.448556435090213,0.6325285674510233,-1.1787122729417632,-0.296008449922577,-0.6763434711441269,1.3566303318468313,0.4096997470538412,-0.753613026533558,1.1545024590981248,1.2201254273967377,-6.684570620598316,-0.8197319030988689,-0.36299062810660754,2.446325593054343,-0.6048164508753194,1.1281470422412725,-5.564457342979508,1.5495311754845422,0.42066270799315575,2.1740286648866625,0.060576672772949126,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4666736,0.0,1.0,0.0,1.0,3.065148240820695,0.8171105693450151,0.5209480916347876,0.8022331759875012,-0.03708950394971266,-0.023672283287903176,0.5953872043012922,0.9422269667449369,0.2496634800719668,0.0174749715017548,-0.08002250635045548,-0.4256995499831507,0.7600853087247834,-0.4056887957737949,0.7303212692811525,-1.3799369443182528,0.4367555946787918,0.6722082413460851,-1.1838865745309926,-0.28168962634746,-0.7758639137295947,1.3749386951028744,0.41389686316071383,-0.7173708487628216,1.1571412344593692,0.8358387190814159,-8.342081432707397,1.0204571107087552,-0.9137857807444992,2.427824259365059,-0.21621814550260043,0.8609121558776454,-5.765984191145933,0.47612062259939036,0.22676020085443402,2.2405626588517302,0.18232713623494198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4833403,0.0,1.0,0.0,1.0,3.0656000799337217,0.8333354941881015,0.5209018673915972,0.7981964802003924,-0.03434381447376118,-0.02666701482587345,0.6008258913557016,0.9372116525346009,0.23999332105156773,0.040170480561227045,0.08543482624263894,-0.5865874596763418,0.8315049280808186,-0.3942454448492626,0.580561985621504,-1.351326395824313,0.4180968481463443,0.7134562046181425,-1.1859195588730596,-0.2673113206658451,-0.8685433285812707,1.3725010510081859,0.4172584355330024,-0.6789274552009897,1.1605800424610986,0.6127599226337025,-9.079737968715152,2.136480674616743,-1.0991586867082723,2.4264313977143632,0.08762638611368175,0.8397340110707461,-4.989925149928139,-0.8831198145282271,0.15997007784043596,2.4265514005702147,0.10002018210869329,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.500007,0.0,1.0,0.0,1.0,3.066018523301526,0.849367910962833,0.5216277661911408,0.7936854106971728,-0.030447206668625427,-0.03013821433312897,0.6068180324358766,0.9415133783299202,0.2263388638747591,0.07270199937254902,0.2630026761750966,-0.6605719003806423,0.8597616426486396,-0.38526342416867665,0.42766273167478286,-1.308720779398983,0.4001168985112703,0.7530894496986571,-1.1809656891521108,-0.25369843666283437,-0.9421950847222094,1.3455013090772792,0.4192292097534002,-0.6364856403070545,1.1604752471976711,0.6475861177449794,-8.650582890305976,2.9018382513034338,-1.1344001330564435,2.2010522350646884,0.5444579464238666,0.5729997471870288,-3.8670669448355293,-2.269874482146578,-0.045140398091815796,2.5794337319180998,-0.02385304066435443,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5166737,0.0,1.0,0.0,1.0,3.0663551005590417,0.8656262684039678,0.5230175063536138,0.7892924687559995,-0.02462509313551804,-0.032293588871060305,0.6126729369500123,0.9691543824984964,0.19948140477939244,0.08513451119064022,0.3421451142687437,-0.6571772489596314,0.8138811262741364,-0.3726591977520221,0.2922086459057787,-1.254598260658315,0.38028343475112064,0.7868247591904478,-1.1677709243617342,-0.248211290892961,-0.9974458178802513,1.2968384169450011,0.41575375258724867,-0.592946158841471,1.1597849395154174,1.0328804662349598,-6.8555426029763655,3.3538685809667386,-1.0575427529650907,2.0723238085618902,0.8059491207702418,0.3504059697967249,-2.638956926748709,-3.5141541271330237,-0.08178499022565833,2.5957743459794203,0.08208159986558547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5333403999999997,0.0,1.0,0.0,1.0,3.0673529372890767,0.8823108859010083,0.5246067006672165,0.7851705555570944,-0.01966907887318835,-0.034958607137063044,0.6179791435068669,1.017804637346266,0.15943539986618477,0.09439977188593746,0.18668455461625338,-0.5755850310413698,0.7665596689820967,-0.35083400643548024,0.19914418787273047,-1.1969249364421863,0.36486540290958375,0.822167048138974,-1.154100664729828,-0.24201821430921222,-1.0301604915442948,1.2283626038959032,0.41650303796021226,-0.549959655722784,1.1632113059986307,1.2623279977952222,-4.472741631317964,3.6174748409522235,-0.8459962941670007,2.0425544500635473,1.0111970261460201,0.3840821292934374,-1.4665105814966335,-4.4873125213162055,0.21444774352966753,2.665712615217016,-0.07764296810455108,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5500070999999997,0.0,1.0,0.0,1.0,3.0688864820778634,0.8998092989415852,0.5267979828495747,0.7811336871772381,-0.016699649883509988,-0.037663998936856,0.6230029756227056,1.0533408442493737,0.13989973382283039,0.11300165977525402,0.028059824440407985,-0.4485964387823935,0.7182681934878415,-0.33058151367031485,0.1431169600124045,-1.1340155247949182,0.35208350187913434,0.854910043696196,-1.1340642894103985,-0.23540852764437115,-1.0463296016975112,1.1472610337469595,0.4229020250014205,-0.5040888939533961,1.1571968354024011,1.0833939830710777,-3.2284645802956216,3.878858582410844,-0.6551092326290149,1.8088854376915418,1.287700300625339,0.28574720170581386,-0.5998142687292898,-4.846225144719294,0.48441355798894004,2.837207895040985,-0.6091691639362541,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5666738,0.0,1.0,0.0,1.0,3.0702760021584754,0.9174911617964105,0.5293555372499535,0.777446441612964,-0.01509543401354071,-0.04031467816237826,0.6274742106413195,1.0412084056331272,0.0972861479031041,0.11054021178213655,-0.22344220013601798,-0.3779496553635102,0.5795189922577548,-0.3147208014401788,0.09152848663190441,-1.0676293917712527,0.34302838481466774,0.8824633499877212,-1.1111772355289633,-0.23249328853587165,-1.0501543404895557,1.0668214426569171,0.4326501888540808,-0.4553858700742249,1.142905626589478,0.08947007593786442,-2.605865524597111,3.5565123697483,-0.23826442641352108,1.5713543022519993,1.349173673670934,0.29301648658402135,-0.0620591804274931,-4.272074973166879,0.6735351748396007,2.901243834464481,-0.9594304853014197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5833405,0.0,1.0,0.0,1.0,3.07268995839276,0.9343014930244036,0.5317469450194044,0.7747713553250927,-0.01601655191525261,-0.044764065319539914,0.6304514219894607,1.000405829983688,0.0715106108966432,0.08434670466872274,-0.41717609590206484,-0.3089919178930428,0.5562235696891937,-0.32759917184104764,0.05625460213479915,-1.0154648753691502,0.3441413384477219,0.9072886251948828,-1.0890917436764558,-0.22564129189047133,-1.048398245182373,1.0048582498363987,0.44535324239841884,-0.40738057272165773,1.1252157552636548,0.6276459244526205,-1.6463347766128291,4.096158129274583,0.024550828830620177,1.3479224906762848,1.3923058146184406,0.2662204339722472,0.290099016227549,-3.142407913979628,0.7824675897606767,2.8131308247797313,-1.0990461490404648,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6000072,0.0,1.0,0.0,1.0,3.074403508775648,0.9505146395541563,0.5336003060836678,0.7712590485046832,-0.017658995010427687,-0.04854111430061451,0.6344220994080574,0.9889119227076654,0.07989308462764243,0.0525183916324118,-0.5236686588292203,-0.26565057841485634,0.5646892274888828,-0.2937992287820298,0.036650550989158336,-0.9310905143848913,0.34384674741241034,0.9273941895384301,-1.064766948887961,-0.22361925632210114,-1.0404843539420363,0.9620743026970686,0.45873249401060934,-0.3616146550395122,1.1062706816850525,2.9033922335701305,-0.2713577411116505,4.311099761829922,0.15488337555738088,1.2993641000802982,1.3900326790035233,0.18309202852041093,0.6076758386245528,-1.5889825405428815,0.8156985126321814,2.715551011687215,-1.0200203362836218,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6166739,0.0,1.0,1.0,1.0,3.0761912486791623,0.9670741804234881,0.5349812335269108,0.768431054621283,-0.020384584645000488,-0.05355735943577963,0.6373615867407921,0.9708257823056321,0.08554932081533038,0.02416211065805344,-0.5117449918166683,-0.264057912516135,0.46473650280794265,-0.23081923716256106,0.04720932600722806,-0.8717612625681687,0.3493041279585263,0.9506008484884995,-1.0427572283741597,-0.21953821206698906,-1.0281423433831653,0.9518920592194666,0.4725432471993924,-0.3168620246286831,1.0912150093861783,2.8118317405180457,0.9727467593733752,3.4825524260031124,0.2129635156164663,1.303339502022077,1.2788115575206964,-0.08593658796244939,0.6537854619620674,0.41326044741291446,0.6730823462784408,2.5777339919331874,-0.817266689353674,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6333406,0.0,1.0,1.0,1.0,3.077412551519815,0.9827866936761417,0.5359391474771817,0.7659190388336993,-0.02182650673808785,-0.05719761200330867,0.6400156738211912,0.9303565061523817,0.09977923287386621,-0.02127469502461841,-0.16459234207369694,-0.24193451219361603,0.40461567012211686,-0.20007131664264557,0.0690755078180548,-0.8150052013479592,0.35094554546386025,0.9708389264951328,-1.0221398117165006,-0.22648381498328865,-1.01869146162427,0.9758496784948623,0.4811686170920471,-0.27569001679280647,1.0790284042221507,1.250524889370004,1.6412534224654416,3.1348122131063363,-0.11366080174388254,1.1973379901746666,1.292598609735668,-0.6209150891605348,0.6459368223501805,1.9641838944155277,0.24802927938757927,2.4220225773543436,-0.6310908226167318,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6500073,0.0,1.0,1.0,0.0,3.0784235076376305,0.9981819810370114,0.5357734352620648,0.7638260009324215,-0.02029876673225794,-0.058244440955342265,0.6424681980195858,0.951535179168328,0.10111434941944746,-0.10286715651376684,0.18610542934843433,-0.10993989568151735,0.4161402814042521,-0.18913499081523497,0.10191788283963761,-0.7672673131438099,0.34551542698967674,0.9905121946501877,-0.9996705218763968,-0.24023542310001283,-1.0066110729090378,1.0173649866455772,0.4808109063809303,-0.23612777724869985,1.0701786065595658,0.5497560538523817,2.286068743736186,2.42113459776517,-0.37819184640510495,1.4100455973221986,0.9716146340460513,-0.7688376672336013,0.5067975466302367,2.1574711940746623,-0.11669158047067327,2.1901165590363605,-0.39591223091332867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.666674,0.0,1.0,1.0,0.0,3.0798256262682573,1.0147273552091525,0.534174445541675,0.7614135817353596,-0.018693809900529195,-0.056464194080851134,0.6455321012987146,0.9923326902109688,0.07812218223986246,-0.13711582293888522,0.276904185895107,0.1944469762708655,0.526198652613409,-0.1817460781971626,0.14527795168051058,-0.7343005533468137,0.33833912537090033,1.0178405404089126,-0.98975259247399,-0.2521117884802532,-1.0017981762834256,1.0477655287954306,0.477278889963586,-0.20268598548382386,1.0658313034642244,-0.6674094878628525,3.286911902995925,-1.5239888420835375,-0.35144430380924324,1.534997459763845,0.3373590969101445,-0.5082222948962232,0.45011162782115066,1.6099370869801821,-0.20533078326419196,1.591112737904379,-0.17504885032133896,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6833407,0.0,1.0,1.0,0.0,3.0816714901837794,1.031403462582637,0.5330171441147905,0.7584219677355607,-0.019378093363627308,-0.05264368463760008,0.649345247785404,1.020738340210543,0.07254988399879245,-0.11905196691716319,0.39922071268404746,0.5327917239901008,0.6209714033406086,-0.21138201823796257,0.21148183206696197,-0.8180670428125173,0.3338005934330817,1.0416788789754798,-0.9884251961554522,-0.2571762001447066,-0.9916073219742243,1.0710296635407224,0.4739665332500717,-0.18309057991103803,1.0643436332122644,-1.2982166120205527,2.8311556456339297,-3.4811511801805515,-0.513109439286418,1.3899542621914254,0.015978206769478673,-0.2634643898643799,0.780828443619812,1.2112590231792517,-0.26784267874562867,0.5920641527105195,0.31336633821935456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7000074,1.0,1.0,1.0,0.0,3.083008493758284,1.048841372731393,0.53185527237018,0.7552743018789222,-0.019974021373469642,-0.04520664851116936,0.6535427501869076,1.0631862323236838,0.09448754699114378,-0.12238180822425906,0.7304102885354865,0.6871532538392987,0.6457552893193151,-0.22502005181228849,0.2396499952786846,-0.850339158096244,0.32123544318739045,1.0641724418122442,-0.9892199845164602,-0.2608939523733585,-0.975770509440869,1.0881409103186739,0.46835078281588644,-0.18295047425586303,1.0762768689626254,-1.2252838980102372,2.344105001585345,-2.7159482666551584,-0.9928797510941025,1.3469588622691542,-0.1461886439723048,-0.4448988755267502,0.9913066571708365,0.9851188109213905,-0.5279875959556739,-0.8390582375161578,1.4663188739141502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7166741,1.0,0.0,1.0,0.0,3.083973908598714,1.067028283233782,0.5301713468386413,0.7521482726336608,-0.0181649049025108,-0.03580983219494209,0.6577694642671195,1.0935782621998442,0.08467710223408317,-0.12158902284903099,0.9401715074599097,0.6969998856434793,0.615226799719228,-0.252224896523897,0.2896188217268069,-0.9085988327642404,0.30070453553796156,1.0865775975150425,-0.9932981607004386,-0.27200619232219,-0.9585637006480859,1.1038670229126895,0.45636691151904285,-0.21105924376545912,1.1132210267639944,-1.8320898982085094,2.9099079004278416,-3.4043139103556985,-1.1367173146838239,1.2772975250371654,-0.6557153074051651,-0.7345535134692207,1.1248347362012452,0.8002661067158945,-0.9725794731437347,-2.299809368338909,2.2360954350959137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7333407999999997,1.0,0.0,1.0,0.0,3.0853503720009035,1.0854164693214325,0.5286978273227939,0.7492290606107109,-0.016202855125047374,-0.02597469279664802,0.6616030513505121,1.1071257675849313,0.03961886635375604,-0.10185388456977869,0.8452709632298924,0.7329869623530066,0.48682816587611843,-0.286089837225232,0.336647119286806,-0.9638165153956947,0.28334479025010867,1.106749111133318,-1.0110772051443195,-0.2853791184592334,-0.9382759432451784,1.1148165005602775,0.43593140220579707,-0.2596109398544512,1.1508135325388515,-1.665380840013943,2.8282159879237767,-3.261602477366708,-0.6794957211852779,0.8214849216059231,-1.9260299529345757,-0.6383808124266537,1.276327637426711,0.5006028015425488,-1.115613052221008,-3.6995737827724873,2.5158595656234253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7500074999999997,1.0,0.0,1.0,0.0,3.087417804264956,1.103843729695141,0.5273502910166562,0.7473300550224898,-0.015915210536353693,-0.017210312659256127,0.6640393814163711,1.1108644682676738,-0.0052435756035371095,-0.06726692835859609,0.600648432709441,0.6660236410133507,0.37048242430948064,-0.3077377022164178,0.38389287653866533,-1.0173191327832958,0.2780546328654042,1.1139604830009013,-1.057499287533588,-0.2932855952951326,-0.9160193609786864,1.1205538163376279,0.4191797354041391,-0.33437861649612755,1.1970831800087463,-1.0448920311091923,2.84355748218474,-2.897515658626247,-0.03716914755642938,-0.3468916843926071,-3.9607352505420055,-0.3546903862028706,1.5171404049282236,0.2694640051448624,-0.6959391683743291,-5.00299342377551,3.0773475853151675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7666741999999998,1.0,0.0,1.0,0.0,3.0899801277367316,1.1221657727949046,0.5266360572293517,0.7454909317253847,-0.01619344482535915,-0.010935357002933367,0.6662292856270463,1.1095406795419325,-0.03472627458028553,-0.04599740405035096,0.43443021789445885,0.45584411652427215,0.2779918404856551,-0.32091964125500716,0.43143255826346283,-1.0604005638509468,0.2821058161869512,1.0951860318607856,-1.1431019775447364,-0.2972021549786882,-0.8877044952715439,1.1237986520293732,0.4127333835307082,-0.4263777208465298,1.2533919905391961,-0.6288765153171727,2.9244353064928146,-2.295071816166547,0.5825286793737735,-1.7377388464384453,-4.605571832437031,-0.19552315745062265,1.7674771438595531,0.26685462181332814,-0.3223634943735068,-5.335049287576228,3.0532388280698384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7833409,1.0,0.0,1.0,0.0,3.0927690025256482,1.1404510802447112,0.5256680177128682,0.7444565761654813,-0.015632168463057188,-0.006645791302946057,0.6674547737270812,1.0997207574556453,-0.07051299089684775,-0.02384813663746853,0.34573850787334187,0.24202566491416957,0.13997104382148662,-0.3287002946520912,0.4813742483841129,-1.0938216796603017,0.29747229434644196,1.05603573893703,-1.2110186556529445,-0.2998030469116972,-0.8571033383515584,1.1294489881883802,0.40843426410078926,-0.512213948418621,1.2988580111603294,-0.28742658527159803,2.8902375934932696,-1.689843340538267,0.7836840737006535,-2.3449794161583326,-4.110696051842434,-0.07990512897051424,1.9062220326097765,0.213755952657802,-0.5316687880719275,-5.206045486141014,2.202282590000683,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8000076,1.0,0.0,1.0,0.0,3.0963326413236523,1.1583363741165495,0.5255149101783566,0.7440575585304672,-0.014613073476394043,-0.004048616932271688,0.6679434230368541,1.0860554333381758,-0.1238557547143214,0.027126320904945763,0.26283884888402037,0.07787216991889855,-0.007788474441874827,-0.33050054659249944,0.5277740040624114,-1.116728787858445,0.30822867088924455,1.0170198949902134,-1.280125453319221,-0.2998656646047139,-0.8241636337697492,1.1309238647016968,0.3950110551503914,-0.5999129174542627,1.326801557024725,0.009261239975226475,2.79074536394015,-1.0720688786518273,0.9650889803890006,-2.5877195524183163,-4.4919707539286895,0.014001045228588993,2.1083219612598585,-0.03955623002942152,-0.7859500523927618,-5.360521573710037,0.9573200338407017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8166743,1.0,0.0,1.0,0.0,3.100746955513817,1.1760111088207057,0.5261953193696576,0.7446154994028459,-0.013242034889294266,-0.0027542877285935815,0.6673565916810513,1.0748099392675763,-0.1522015751627458,0.035235764449151274,0.34018039238511777,-0.03233649057846102,-0.19871408153061113,-0.328391586035501,0.5743992798984755,-1.1295573804199546,0.32964199136534067,0.9697782480084494,-1.3607513135819511,-0.29933634447067453,-0.786825799088099,1.1281304445503175,0.38223587662436037,-0.6908983582437271,1.330768742776355,0.13602779948556762,2.728380481073441,-0.7229858254486592,1.096881706560866,-4.108602828761121,-3.7717022352234126,-0.12927927037721493,2.372957180378111,-0.13247072864169634,-0.9170800250553017,-5.125546522326243,0.08368850453396622,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.833341,1.0,0.0,1.0,0.0,3.105263172891352,1.1934119053275662,0.5263214440445233,0.7463360237629326,-0.010024077506640106,-0.0007091878179097881,0.6654934669525429,1.0376565360871701,-0.1613687640733057,0.010657651503993988,0.5483773925062526,-0.08976781315650506,-0.3968058300964136,-0.3259662775411272,0.6187202019902248,-1.1408283635724554,0.3447914675667205,0.8800661934579874,-1.405849112606817,-0.3041749822359058,-0.7450649028933335,1.1265081649155917,0.36444165984321303,-0.7707648099015723,1.3295911794217574,0.09333014503666574,2.4864535294553107,-0.4895687389840074,0.8780220274394843,-6.5690103964473705,-1.789430174740517,-0.3920465048337083,2.4509477582786907,-0.13267380537055765,-1.0351602847387398,-4.611540909332357,-0.7660343188643468,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8500077,1.0,0.0,1.0,0.0,3.110036296841942,1.2097622579188554,0.5262112009037642,0.7490979058288918,-0.005421541121026123,0.002146747508876765,0.6624336388271469,1.0307381653707433,-0.20842265611209337,0.003858977407899968,0.5156299333730383,-0.1713633609948462,-0.6307553276626712,-0.3252805749789358,0.6572812299772212,-1.145876371024004,0.358909450814792,0.7508107968595106,-1.4203991053686467,-0.31240458743489846,-0.7051273770822921,1.1237079755263786,0.34773046478905006,-0.8446166959908663,1.3052342144119222,0.3419417336332901,2.3605323849961737,-0.17186761996398828,0.9021070365832806,-8.27003162073877,0.1887021397180883,-0.4680058266335107,2.3874735525585358,-0.1480706804426729,-0.7586654105692446,-4.090705629842215,-1.84343603947396,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8666744,1.0,0.0,1.0,0.0,3.116361688013113,1.2266615999624815,0.5261294479589144,0.7533540827831623,-0.0017327669591388662,0.0028015909260775515,0.6576068541012089,1.0555299061447296,-0.2462462479962482,0.04154589803363484,0.2575750002982811,-0.3215846043720814,-0.7354891476904328,-0.3145681969572353,0.6974047721922563,-1.146557295695763,0.37486176225996565,0.6043979214312537,-1.3995590287027382,-0.31977520765741124,-0.6654822919764788,1.121572465696124,0.33915276224654417,-0.9071219369433547,1.2681431885435561,0.7027869186154008,2.299523060081315,0.36460263549383215,0.7521739855767663,-8.51626377824788,2.2392233580311878,-0.29576305815975434,2.4878385504082363,-0.2193734732026921,-0.3051256371396718,-3.258867677430186,-2.508330302886487,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8833411,1.0,0.0,1.0,0.0,3.122925039872392,1.2435231645365206,0.527358518449842,0.7571904414030591,0.0012867788566246715,0.0009129302040865279,0.653192273535486,1.0489477080699265,-0.20743446531970589,0.06807519301883677,0.2795081030553279,-0.40418949074622024,-0.7484543792350865,-0.3018542975059612,0.7339321519481357,-1.133722925534034,0.38398196714561655,0.46693476983366267,-1.3457581774860499,-0.3222633757577608,-0.6221992595461142,1.116395511794724,0.33755958987601853,-0.9532458358297177,1.2216230370936858,0.6201746886347969,2.1521383186640066,0.8424760057172896,0.22002343417345643,-7.535134093642995,3.658974507229155,-0.3853615896654315,2.603282835990212,-0.14264407757806702,-0.19074341286892477,-2.4157710185326224,-3.018372084904736,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9000078,1.0,0.0,1.0,0.0,3.128336914496627,1.2602325116294035,0.5283873309062156,0.7614885160008745,0.006194911947870213,0.0007510086487979719,0.6481483619131915,1.0108824945946862,-0.1237953804920558,0.07815412098514425,0.5731657027468772,-0.3843855482279592,-0.7723123906388059,-0.2938956659910962,0.7691428596236111,-1.1184747060067863,0.38219589140064314,0.3532262826342143,-1.2775929678634659,-0.33262061967036494,-0.5787060238912827,1.1168176536005832,0.33279463576801915,-0.9876477986125101,1.1675305844885926,0.2541454258066683,1.9224276839961458,1.13977078334899,-0.3695213043033159,-6.193444341140525,4.407018394003654,-0.80886413897383,2.6459082787230526,-0.21320917613142756,-0.3146997790020479,-1.6683072172889848,-3.44365870711848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9166745,1.0,0.0,1.0,0.0,3.132407108867549,1.276104281589419,0.5301525627603507,0.7654672418015026,0.012714809157976235,0.0022932311614691967,0.6433451456626655,1.0081054914556373,-0.08578304750310994,0.06622906519503398,0.6273564167361511,-0.35946911002234566,-0.6706228086055972,-0.2933827663693772,0.7980132029098528,-1.0957304901043488,0.3716645657007524,0.2604862122326891,-1.1988572705513685,-0.3492255676478311,-0.5340021405281272,1.1092885250430646,0.32706957626263167,-1.0088561876264983,1.1068341839458227,0.014436817989427479,1.7366989898450864,1.3169404032316483,-0.5029149907292197,-4.741981757106716,4.44727429823058,-0.912766173683375,2.6543483247696167,-0.4427721332135363,-0.11751263844732975,-1.0327498616798705,-3.22986577783798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9333412,1.0,0.0,1.0,0.0,3.136983589204313,1.29280331805705,0.5309619162981836,0.7685738532305444,0.018024412510615928,0.003032983319869078,0.6394999247038128,1.005604858524669,-0.07027716742694443,0.038238652638959474,0.6166041014768522,-0.28728064267617365,-0.6092786985853103,-0.2934144377623274,0.8270329417317133,-1.0745766047697045,0.36543202484866977,0.1951599079318733,-1.1293501947708267,-0.36304621964422235,-0.49022756944240714,1.102058552975323,0.32887753998559893,-1.0220728628518299,1.059868176569608,-0.15173379053515124,1.6437666891977514,1.2043076102182717,-0.705200709801459,-3.5079204277922966,4.449632298235808,-0.9294296821019871,2.5782102727734526,-0.5730849319768234,0.2467015426609995,-0.545463533359358,-2.4509105069597266,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9500078999999997,1.0,0.0,1.0,0.0,3.1408476825155587,1.3086031434316872,0.5319688173873954,0.7717808451857131,0.023651901447764863,0.005367948484929638,0.635425919908367,0.9808533507346722,-0.03574420386707025,0.0337332794863931,0.669890614558258,-0.21317250983473968,-0.5770646073568041,-0.2984405695028016,0.8528055354675571,-1.055586822809899,0.34815782836065645,0.14355529744491735,-1.050535897301355,-0.38020661901320946,-0.4480616262216606,1.0901856557715084,0.3352929774647678,-1.0270383417693791,1.0251370036531313,-0.3183665761909809,1.551209015342428,1.1760957974161168,-2.041162846629972,-2.92131350969788,5.558285572996395,-1.0257194877622704,2.55306983463513,-0.7341988326159226,0.5593929605698117,0.05272987945098764,-1.5817670905830463,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9666745999999997,1.0,0.0,1.0,0.0,3.144485909058265,1.324618306255817,0.5327452609433135,0.774444750949739,0.028848639026427092,0.007610589188316354,0.6319376256284527,0.9876657044577086,-0.011084327415950251,0.019704005613701944,0.7815643190796324,-0.196879273219168,-0.5512250725592762,-0.30402667819313184,0.8787400123237286,-1.0353733331161141,0.29739312721681427,0.09778259618770999,-0.9440736384519086,-0.3972369376175972,-0.4051250714165805,1.0775852096082035,0.3475240092974567,-1.0203151966881383,1.0071425014323672,-0.49445875310623666,1.5263910762350554,1.2912139958220068,-3.137382758447976,-1.4369034128009748,5.343980090179552,-1.1042636580486636,2.5431359007333323,-0.7951779689744788,0.6976554107650305,0.5869283666373856,-0.5382570057866595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9833412999999998,1.0,0.0,1.0,1.0,3.1478646111283615,1.3407451602695069,0.5334166808294216,0.7772206132193452,0.03574863970313809,0.011317511222781854,0.6281099164047982,0.9898400038762168,-0.019608360414801268,0.010666080282928538,0.8716002848705239,-0.12898986446940947,-0.547982931616445,-0.31492256090359305,0.9036853397681307,-1.0125462702015657,0.2435781939202067,0.09565842122465734,-0.8724028713633639,-0.4170154812324088,-0.3632902599881562,1.0636796704604945,0.3585482043339629,-1.0074740237529085,1.0071950675764423,-0.584223004461492,1.3755043406786644,1.3438140598218244,-2.2698055557752848,0.10737232514194364,3.7450112978899806,-1.0521876335584848,2.3437171598120687,-0.7863155555976461,0.46521400798161006,0.8528664769901348,0.4843277435123449,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.000008,1.0,0.0,0.0,1.0,3.152097743376408,1.3567088251733566,0.5339554601899276,0.7796882018959322,0.04138960657459123,0.015393397633464692,0.6246088789003778,1.0005145266241853,-0.06260365152340178,-0.013516627107809133,0.8428099669152211,-0.021937410138715974,-0.5754015854524912,-0.32350081729004854,0.9245902487133068,-0.9905794415344493,0.2217327907039344,0.10136168085059645,-0.8192396788548227,-0.4323099288820556,-0.3270010098417009,1.051374638667245,0.3630311739111109,-0.9918862572640353,1.0232867918379616,-0.4763624837250667,1.2454966157239336,1.258284678437011,-1.145393503925756,1.0913721540607317,2.617815467034235,-0.9242715522286573,2.104868286153144,-0.653936458724386,-0.19289147378935523,1.000747342281365,1.2758588226781715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0166747,1.0,0.0,0.0,1.0,3.1571726055420704,1.3728401452406804,0.533716896737775,0.7826269006209269,0.04678090171233581,0.020208790091415702,0.6204017137810822,1.036511541284761,-0.07577445695526147,-0.08573013463422982,0.7749351975096594,0.03764264593159995,-0.6899227370278208,-0.3308013421185942,0.9452019766587029,-0.9706033637013535,0.2053983340964479,0.13203756578482534,-0.785142181274525,-0.4478245945914675,-0.29312784345849896,1.041881744907251,0.3521184756815528,-0.9741157122937069,1.0497237800563028,-0.37678074648005405,1.3636368820406881,1.0094766831406903,0.29733077086199344,2.8361918733626195,-0.9634219934555773,-0.9621761148739911,1.6935913117667771,-0.09091587401508668,-0.6415039084310379,0.9277513769354593,1.6962413604034305,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0333414,1.0,0.0,0.0,1.0,3.1622148989533088,1.389892815658581,0.5317769556108615,0.7862055236382306,0.050868202521384895,0.02444739251984982,0.6153825034659007,1.0517741036580657,-0.0515338795071478,-0.1483470220629919,0.647002270173989,0.07667045515894183,-0.8424265811676587,-0.33606020062476677,0.9700449023571218,-0.9569301514646474,0.23164383622138557,0.195901599042142,-0.8513538095314749,-0.4643825301895963,-0.2705478532100542,1.0483441034723504,0.34164766752981574,-0.9609611495160949,1.0798282836008333,-0.3015326854460799,1.4552166587127437,0.771432822847707,1.217987260843648,3.12673676114367,-3.2305608294069277,-1.1746470697563418,1.002548577479327,1.0375390360145538,-0.6958558448117932,0.8596097848709331,1.8055142372089446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0500081,1.0,0.0,0.0,1.0,3.1667946228074637,1.40669070497123,0.5294616230041446,0.7906800860149282,0.05412178309613784,0.02857453718628877,0.609162810748087,1.0595922686670594,-0.04105010040325868,-0.14075121514320982,0.3732159734530254,0.19875655343622325,-0.886240102547497,-0.34085245173564255,0.9937092956302382,-0.9448888848442417,0.24599799065705355,0.23626233293873175,-0.8928277576254778,-0.48697957522648355,-0.25970949070594956,1.0764664486103386,0.3289232344641034,-0.9454619954906901,1.1099077083308835,-0.08601364384937388,1.655284319801193,0.13352364266650213,0.5865063777316263,2.530606344227424,-2.401350429404245,-0.9303325682671231,0.10371206558349892,1.919531397218397,-0.5734752389175225,1.0844469010090623,1.4838112780270325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0666747999999995,0.0,1.0,0.0,1.0,3.1720566612382544,1.4239192550610325,0.5276885721889253,0.7947750442145141,0.053342907180943935,0.031683665637992804,0.603724530459913,1.0821795737786009,-0.037825507715058215,-0.08070319793243558,-0.07562625337927503,0.34255181264555146,-0.81960684098235,-0.3389273278206555,1.025221156702783,-0.9524793544741879,0.25119408791286496,0.2802553125568124,-0.9313989839349783,-0.4953936778206716,-0.2670907774431332,1.1123286113483901,0.3225317880008824,-0.9248128471859994,1.1292887584558196,0.19593589392238425,1.7279756039706369,-0.9942964621533128,0.8405059618939177,2.798943094016192,-2.6125400607394784,-0.0025801237554814965,-0.7506596090283155,1.806265661169509,-0.23270637789254567,1.4469613993473756,0.7977524779383839,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0833414999999995,0.0,1.0,0.0,1.0,3.1773960792490845,1.4412204678977032,0.527143756282213,0.7988044518642514,0.04922987401846581,0.033102666051905115,0.5986585677046933,1.068163499439633,-0.013107292470493026,-0.03771271167953274,-0.45863351861173185,0.40022087221437475,-0.8199317844998782,-0.33432124220917014,1.051308597627633,-0.978032166535783,0.27401491208724826,0.3295606226688111,-0.9799126004861312,-0.4870655795236745,-0.284731527717534,1.1366754244003663,0.32116633968726,-0.8972298523816843,1.1364995107789948,0.3994654191748341,1.1639639991350614,-1.952954060554313,1.4233815999525203,2.84272862584777,-2.733498341727328,0.7804282212774948,-1.7479164797454785,1.6816596701969848,0.03678943416971025,1.7150460088843094,0.27481588963057385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1000081999999995,0.0,1.0,0.0,1.0,3.1823385444152477,1.4580166405297612,0.5266043695502718,0.8030952657530748,0.042781244797249825,0.03312198949792327,0.5933891581671303,1.057694765953763,0.000797579016543426,-0.03857431773031129,-0.6026094678003597,0.4020378410447954,-0.8756561928121999,-0.3256117872171331,1.0640200342715516,-1.017577953356269,0.2986402361367223,0.37501312293364647,-1.022515777559112,-0.4693793517495404,-0.32535477662908113,1.1683840457989343,0.323758104925835,-0.8676445325534552,1.1384493064312313,0.05342233578822728,0.34611746536442256,-2.969337512738936,1.462087183836634,2.757738767469865,-2.495542080890132,1.0075721985064683,-2.9978147984770014,2.2023755946014525,0.15686005167865935,1.7791434478959083,0.06303696838009806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1166749,0.0,1.0,0.0,1.0,3.1875879065797608,1.4749688529138913,0.5257827268951649,0.8076706917665077,0.03670461645954903,0.03314193636799084,0.5875563265302728,1.0760941394048762,0.01347177724797649,-0.037437023310886386,-0.6591314063184919,0.3084803782116783,-0.8504935573935116,-0.33254049412140685,1.0628458695476115,-1.077010281582915,0.3227512490209483,0.4214854321003911,-1.0630975028852743,-0.453479772401979,-0.3846588875210873,1.2100880910454543,0.3263950185338854,-0.8379249521755908,1.138600747260796,-0.4177500406886542,-0.2852050166680834,-3.8176455639001743,1.387105896225172,2.8543284347972935,-2.2393683770498383,1.1030743648838348,-3.773186825720218,2.6961122812004645,0.2167623291089645,1.8635507575692245,0.0036374816517032956,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1333416,0.0,1.0,0.0,1.0,3.192817706368097,1.4923113416055946,0.5250335123158344,0.8116533112939505,0.030404829346768743,0.031347919397648284,0.5825047266481176,1.0828387748134574,0.04453177105491413,-0.02157079851467864,-0.642980284951832,0.14312653109849527,-0.7784558750365278,-0.33953681642342426,1.0545131813689477,-1.144833059995979,0.34487719181795445,0.47015759438211857,-1.0971615394186651,-0.43261013271512155,-0.45112792236554344,1.2582546349131019,0.33098353034695577,-0.8055260497310972,1.1385705560621202,-0.3909067343978025,-0.6813156930521597,-4.14947484278104,1.129191425193146,2.9068295712473793,-1.842269623725083,1.3189120609253713,-4.122128125092621,2.6018476549725182,0.180389734604796,2.0222730612432196,-0.026214694834032545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1500083,0.0,1.0,0.0,1.0,3.197654104624975,1.5096517541686565,0.5246356989003107,0.8154850636044608,0.026208579736698673,0.0292176153960129,0.5774457137573924,1.0677374113912312,0.09827937588963803,0.02220800828643094,-0.62180175860917,-0.07346467413324922,-0.6639785521713044,-0.34557074466178256,1.0401353010248267,-1.2153263863072725,0.36039103847348153,0.5183799449306085,-1.124506613160752,-0.40951594911032924,-0.5220634331660496,1.2968165196677153,0.3324080217133609,-0.7705157153159461,1.1377269223520152,-0.7107001342813479,-1.392295190767906,-4.331335201610056,0.8203422952332767,2.831714467907378,-1.2162166809400095,1.4716711128719604,-4.272654948837525,1.843907384176545,0.06862102672040055,2.2801931940011393,-0.1530943864052363,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.166675,0.0,1.0,0.0,1.0,3.201590254153721,1.5269657447955185,0.5254033205490584,0.8183468008392358,0.02231850244708239,0.02466041765191078,0.573761502547828,1.0387010861681147,0.14123815788241015,0.06405340050565246,-0.6986197555823283,-0.30343832747337995,-0.479953409372252,-0.36322686827947814,1.0081032488570048,-1.2892111888053277,0.37222198968188336,0.5645482654266624,-1.1377021765311108,-0.38355433084131535,-0.5935500388371242,1.3197183373128123,0.33327090247903757,-0.7295194579181796,1.13346739964232,-1.105572276018249,-3.1559549482523415,-3.429876443580232,0.5344095927974161,2.64648346537527,-0.49914108562756476,1.693505984172322,-4.342145899520706,0.9909612437500002,0.06962644086775575,2.536933572877595,-0.26525498130735903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1833417,0.0,1.0,0.0,1.0,3.2051641435312406,1.5437897120016046,0.5265605795989518,0.8204537531208047,0.019371668253808875,0.018577401794038332,0.5710825313399396,0.9928244852455268,0.15115432862731776,0.06768967849162436,-0.7229796622906426,-0.435843494704242,-0.390059865842291,-0.38242322756720926,0.9349365923527521,-1.3296558297517098,0.3782047271940349,0.6065962368753485,-1.1411446826244098,-0.35306563673751956,-0.6668019192931331,1.3298486271901315,0.3347289077173822,-0.6859510937577881,1.1288850719581045,-1.1313399563668582,-5.389815000611875,-1.4720163330805374,0.37292633884629917,2.379676669223518,-0.02351577212048481,1.8233184140278031,-4.34894441901958,0.1428176820340112,0.13489158111221447,2.61295675287995,-0.3004885488041958,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2000084,0.0,1.0,0.0,1.0,3.2084760417105476,1.5597263453935906,0.5276468581876921,0.8224244194779599,0.016457036918517506,0.011945603920669423,0.5685108114444033,0.9385982219913215,0.15907182205254883,0.045422932459470614,-0.7990137163518591,-0.49130456750473495,-0.3424020295668033,-0.4009382755810372,0.8284423895156089,-1.3382784980424345,0.3846528925051826,0.6438709797125576,-1.1384860371695118,-0.322776928819161,-0.7385151427340715,1.3244789362351248,0.33776729750888346,-0.6424207252917311,1.1234510946496101,-1.0704001268784258,-7.067159076332424,0.2048910240385695,0.3788408564372981,2.3258922055754736,-0.04504463776966944,1.8877040268391097,-4.277829642463064,-0.6342741693799635,0.27915828919610935,2.502156397007046,-0.25668029861800734,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2166751,0.0,1.0,0.0,1.0,3.211319708820895,1.5749102166501159,0.5282596737289029,0.8240100830728716,0.012999440405843174,0.004369747258435414,0.5664091302691647,0.9008836572360805,0.18159401699338593,0.04221801435812776,-0.7807465521444242,-0.576224448464564,-0.21499379142287456,-0.4181033031564986,0.6993641519977328,-1.3228261152910226,0.39083278099800195,0.684126132120678,-1.1426461735530413,-0.2901420433292808,-0.8093965258972114,1.3087061125925215,0.34403420263447176,-0.6025457137137934,1.120329044892151,-1.2266055000958433,-8.140596952715736,1.738095527667651,0.24972328844549807,2.3304990939990984,0.06593450677912165,1.7283896440835076,-3.9104897965367758,-1.4314386969442818,0.2965550686273076,2.451065064534566,-0.06956894438769366,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2333418,0.0,1.0,0.0,1.0,3.213617528036444,1.5899049040384667,0.5294392004955162,0.8246634784479154,0.011147083802416077,-0.0032905860870840503,0.5655042545198843,0.8922940073596886,0.1889281887715843,0.06107128022258331,-0.6843366514636903,-0.6170461717880429,-0.1274156285551736,-0.44182520735793196,0.5570886150519542,-1.2803418645804776,0.39297701876825175,0.7215544382124671,-1.1362882158812406,-0.2651638254570678,-0.8688650633179504,1.2767642175744023,0.34765248623346495,-0.5607183930695746,1.1211321251987574,-1.2750151741637137,-8.405285313561444,3.0855124694060367,0.11753360339048283,2.0399185924763064,0.565628474361583,1.460194697287448,-3.1926109966692886,-2.406483706920603,0.27081127265114285,2.396217388226475,0.10152068614949025,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2500085,0.0,1.0,0.0,1.0,3.216179162031577,1.604872708555608,0.5309235918495954,0.8253068166807271,0.009417402824899798,-0.010537584349890963,0.5645076883271185,0.9021137012247602,0.1536108483954114,0.06522373137691921,-0.6717539952542525,-0.6154323055083993,-0.16893299604238737,-0.4606038939629673,0.4191874145266638,-1.2199754939433234,0.39475057561325827,0.7521235545311277,-1.123791853365757,-0.24146878940671937,-0.9158171052935875,1.2284898285962542,0.35306126311026137,-0.522671641025085,1.1237130745318464,-0.847724402010241,-7.536021063542549,3.8225770971962447,0.18883650730970805,1.851572296619285,0.7773004048666482,1.3822655899537422,-2.3261454071597014,-3.324403564714169,0.34171794813151296,2.371391596266016,0.04262068102564989,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2666752,0.0,1.0,0.0,1.0,3.2197294911722767,1.6197145601552456,0.532473889277211,0.8262474073707332,0.007731138266630656,-0.018050559241807755,0.5629650332172523,0.9081711306094862,0.1116661755624464,0.07457406370296946,-0.6619575898926845,-0.5933084836212303,-0.2793554696033526,-0.4700827439399001,0.305887410532465,-1.1529223731687963,0.3992715816010092,0.7832736382045964,-1.1103781505656587,-0.21908821364090372,-0.9464033986329676,1.165950543790359,0.3590431072857119,-0.481671848434601,1.1225528174076578,-0.1487479162081018,-5.917845451737615,4.202381871514476,0.27654081002356046,1.7768471425160641,0.9464525011034003,1.1660557253013772,-1.4165607537992417,-3.8491602144007944,0.36786843389653134,2.573720548757261,-0.35308075691545804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2833419,0.0,1.0,0.0,1.0,3.2237270941982286,1.6343067360244345,0.5345458796034124,0.8278370757807592,0.005963084396714135,-0.024884731964982018,0.5603846604808792,0.9023822915304709,0.06528290464879255,0.0926906408459826,-0.6219513765898065,-0.4556949632424356,-0.41925796297710405,-0.46556216775309844,0.2219255049457132,-1.0798958180673828,0.4039686210500976,0.8113519110714726,-1.0922433735654768,-0.20260018749295844,-0.9630358915242792,1.1001842315055468,0.365323568764708,-0.43688078448513973,1.1119436924292807,1.0245066844142927,-4.522065631051944,5.01735748525547,0.3362666879356677,1.515716860719714,1.0721806328510814,0.9336904645582039,-0.6785462653147489,-4.035223474858088,0.26542887446714786,2.575609409029952,-0.7428143642889665,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3000086,0.0,1.0,0.0,1.0,3.2287536244044843,1.6483063424746678,0.5369606629368187,0.8300435078431884,0.003592423075755061,-0.030105290196744443,0.5568739005250557,0.893265869425657,0.0369012691726231,0.0957897687116347,-0.6675129835147641,-0.25299899145549226,-0.5699742931189239,-0.43593245282564475,0.15515158802635814,-0.9856767891697816,0.41048049361664396,0.8337976346097109,-1.0746387246585805,-0.1879651359095993,-0.9690216527132103,1.0314428256135244,0.36789075412987515,-0.395818029759642,1.097792289077068,1.454989064177777,-3.5689760240665196,5.027219244391681,0.5238459392646864,1.3458107652608315,0.9825593915855358,0.8485600263538533,-0.1524901434020296,-3.8384251390869957,0.11727166652295955,2.4594444582830413,-0.9973796872805227,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3166753,0.0,1.0,0.0,1.0,3.2336971865664847,1.6621676259806246,0.5393063409374209,0.8330387870043606,-0.0006263114915059152,-0.03454140641494677,0.5521348370851966,0.8792007280747041,0.04726775668562916,0.07913714309951614,-0.7799471908897339,-0.13260274262359376,-0.7047812791886545,-0.41706243528123493,0.10295939954509428,-0.9123215081063771,0.4214301872819831,0.856212359634218,-1.0594913283419995,-0.1743147967104949,-0.9681189064703564,0.9722364709743043,0.3692326321335844,-0.3548991385794078,1.0786976363612841,1.2161059882981076,-2.510280896922479,4.272514273768301,0.7718679256011637,1.2746345634571254,0.8582198115559498,0.844794109402458,0.1859783111677325,-2.833549642184756,0.05152782546956088,2.373607642931054,-1.176965320389603,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.333342,0.0,1.0,1.0,1.0,3.2385189942769412,1.6757839530531682,0.5411968294151611,0.8364382357032188,-0.005607320254875253,-0.039129894236663784,0.5466337779448626,0.8645527760641536,0.07479198914820812,0.032960742339604346,-0.8064264150202674,-0.11534368413760515,-0.7956888333861797,-0.3953955054753086,0.07147539077688239,-0.8432593618765534,0.4362094759278778,0.8762855383672526,-1.0460313403920614,-0.1598052759432434,-0.9628223632757318,0.9369909819707231,0.3696083517473822,-0.316697616754764,1.0585600332663931,2.2002927671258234,-0.86148030480729,3.6121459277784056,0.8238720710090993,1.1801065617394806,0.963312990741116,0.7171684826130418,0.2710621871373309,-0.9691554939146746,-0.07587570944683462,2.193557478604928,-1.0707847938902433,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3500087,0.0,1.0,1.0,1.0,3.242847652184127,1.6894996746392084,0.5419813397746452,0.8401346724820835,-0.010294528181438879,-0.043575746037183075,0.5405265110429337,0.8434650626224447,0.11031769012107798,-0.03832583844831143,-0.7860409804990723,-0.13153084199506435,-0.8838867324924062,-0.343719196357523,0.07424333195283096,-0.7919164030373684,0.4488926445737578,0.8955493236993048,-1.0273808310964296,-0.15040913281216134,-0.9590834821616329,0.9399312232334489,0.3667034367603093,-0.2817804097220783,1.043004738512623,2.686618024652995,0.8592815407541441,2.534389880617173,0.8242210517372899,1.3861262101422285,0.7061133720324889,0.381703101576729,0.32287882790754274,1.1918169303475241,-0.19749631573500728,1.8595142165725698,-0.46669186777095784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3666754,0.0,1.0,1.0,1.0,3.2468700489307527,1.702910378323245,0.5414332828756672,0.8441644412669894,-0.014784505694312418,-0.048209203845769426,0.5337074921305898,0.8120044426795561,0.13305630921979622,-0.11811750415368688,-0.6255565349676493,-0.09317542534118779,-0.9365252189623137,-0.30584139221234047,0.10011816608745658,-0.7587795302299889,0.46368356593385757,0.9224898377804076,-1.0224941809167536,-0.14708181377714566,-0.9520597141535585,0.9767182924367692,0.3630251280564609,-0.2547136855680639,1.0430036065612367,1.9983213872292582,1.935055767312008,1.7818475595674899,0.6626409913889623,1.6173546472107396,0.05827322929151947,-0.0072605688027113854,0.39417468441130954,2.439330497775038,-0.32426147670646804,1.2829368994968338,0.3947521347558527,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3833421,0.0,1.0,1.0,0.0,3.2507615164962584,1.7159384259400807,0.5395010691034018,0.8482480571179175,-0.017497386257516095,-0.050696635220174875,0.5268765759143084,0.8008052506155602,0.12993099924743043,-0.17752177751522485,-0.3442772345675821,0.05365300791065922,-0.8818424009591646,-0.27710835022845526,0.13874531986694905,-0.7325213655952815,0.47098072179612266,0.9494612530966393,-1.0254383862351637,-0.15065115225628964,-0.9459442997362769,1.0212424024479834,0.35589469925266193,-0.23901576087639054,1.0561631693212938,1.3588967768937426,2.6223749675666665,0.16991420477421001,0.27152799525760185,1.6166451429648616,-0.33123560160156634,-0.3770592125062885,0.24687012503880584,2.402349510796717,-0.32704207370490346,0.4578960640247206,1.3155420496634942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4000088,1.0,1.0,1.0,0.0,3.2553606380497535,1.728881886667055,0.5369936332526128,0.851866106395736,-0.019360940193339234,-0.05073568652700035,0.5209368300299305,0.8066174536777022,0.10691256976415092,-0.19691029991847234,-0.06862390477178025,0.2841938231323907,-0.7601590715189592,-0.2605447423894306,0.1875308398313433,-0.7531157120765682,0.4727345172109773,0.9763781169889125,-1.0335353897191792,-0.15965047933130277,-0.94383069352759,1.0567967696199605,0.3521237037968259,-0.23945045290750228,1.0868550959194898,0.4047118855436163,2.7569568081087463,-2.001561476812856,-0.07463466772954262,1.5709808008030506,-0.6705934643686268,-0.5951592191630573,0.2597955293571156,1.9462796904143083,-0.2800526392178025,-0.4907783754277634,2.0340286327714354,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4166755,1.0,0.0,1.0,0.0,3.260461103376501,1.741612024830336,0.5344519344527905,0.8550716792119014,-0.02027369806884761,-0.04750769970212212,0.5159306339473995,0.8419440431329686,0.09735770876603334,-0.18162864827912023,0.15219269467296997,0.5096213769086755,-0.6657474809073124,-0.2636179270628757,0.23064406393436113,-0.7992402149264751,0.4684928945628267,1.0018273845221277,-1.0477915464203489,-0.1704898325723395,-0.9372844314380044,1.0861185218804397,0.34655959260855923,-0.25537507277587435,1.1239642593489172,0.023231552881274143,2.1645682718143298,-2.269012384988824,-0.3734331406150863,1.3964113552885207,-0.9014166386067212,-0.5858376963693441,0.5350665685748551,1.4592339616697743,-0.42456365733424084,-1.2867539868147746,2.150635919019953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4333422,1.0,0.0,1.0,0.0,3.2661193972243256,1.7552998032734013,0.5323930570405939,0.8580429163132678,-0.021034006989771162,-0.04238950566450093,0.5113932480235696,0.8883003534936809,0.10332285956516624,-0.1361886670202248,0.3527640219377485,0.676684453406826,-0.6179483866847783,-0.25977035574461793,0.2596832598630391,-0.8287496095103547,0.4602867209615984,1.022925255259287,-1.0635826711005125,-0.17917844159946067,-0.9259951055706569,1.1054379989578837,0.3379715535814407,-0.2823423382515939,1.1585431032625495,-0.22827774812824547,2.230987704518266,-2.482890848773534,-0.5929406865287252,1.1831862679357539,-1.199170330301077,-0.6396220581030304,0.8736348465217917,0.879990763495895,-0.6614690597019448,-1.9951061522586693,1.7538529979077178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4500089,1.0,0.0,1.0,0.0,3.2718888403869655,1.7693230531099253,0.531175940589618,0.8609337694052132,-0.02054631550541169,-0.03504674317751065,0.5070923184288368,0.9000100997484797,0.09029076858574542,-0.0938581371379814,0.5378678790495854,0.7942276636512642,-0.5907606990976787,-0.27122720055233374,0.3050104694841503,-0.8820034087449828,0.4487281654824901,1.0412670056657374,-1.0877639707084068,-0.19181061048391104,-0.908163211644955,1.1154516059963537,0.3245105798538904,-0.3218787441915735,1.1824261428693743,-0.6024438141085207,2.57267679550236,-3.076729948444768,-0.6436439417207663,0.893270458779518,-2.1233647585198256,-0.7651717782885387,1.1566742855995398,0.3845283144934069,-0.6735552461156639,-2.9623709368092226,1.500592638609458,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4666756,1.0,0.0,1.0,0.0,3.278247756221948,1.7829975617722638,0.5302465781879565,0.8636785973452328,-0.019676437704459385,-0.02665171984243929,0.502953083414819,0.9151603933930154,0.06580107170439081,-0.08354146107771337,0.5265990068902516,0.7542843212926906,-0.566884965829384,-0.2798518563778229,0.34543932455823745,-0.9313074795738435,0.4388318799946434,1.052700996769968,-1.1343616379421573,-0.20468421855386384,-0.8874392189390532,1.1182556350762183,0.31551966714056884,-0.3810882336366304,1.208562957922374,-0.46217280055350257,2.5689226267272156,-2.977863298834482,-0.4864204740643626,0.37258259187721215,-3.7742656146124065,-0.7113083658352093,1.2754681273332777,0.20536359360723128,-0.00024816639289567695,-3.8893605025256517,1.986948311801468,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4833422999999994,1.0,0.0,1.0,0.0,3.285197564797887,1.7969195282105874,0.5290645764648758,0.8662051869101608,-0.01904414656293688,-0.019960296529111184,0.49892632844348167,0.9336991472541059,0.06283762708270207,-0.07101421343547155,0.35571678124874495,0.5851865102394787,-0.5486375687877896,-0.28663299138230386,0.39064139496989925,-0.9812657172303522,0.4325141172523131,1.0536864502338172,-1.213573076146528,-0.2155209367656424,-0.8656475223693039,1.122297072807501,0.3245023076242495,-0.45152435356646203,1.2486578857259774,-0.29112871722078276,2.679559624212777,-2.718825734690494,-0.5628736479618118,-0.6132548247618418,-3.893550941649353,-0.5553341579964102,1.399110838551317,0.2148579165639162,0.9571505247956056,-4.399574350632879,2.498642638479165,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5000089999999995,1.0,0.0,1.0,0.0,3.292169380830889,1.8109418742656507,0.5282569949305744,0.8685573878039571,-0.019234050899112405,-0.015416249815774594,0.49497520606470236,0.9251555846456966,0.05205500885885328,-0.022370796320028342,0.18123582752244888,0.4140907069146788,-0.5488438050229846,-0.28955616636043013,0.4347581573359716,-1.0219351853185756,0.42006938753767314,1.0322591283942517,-1.2641469289005318,-0.22319539417602138,-0.8408020977132867,1.12541757995221,0.3474247484437907,-0.5277410052960164,1.2918512124478554,-0.03643812741530215,2.543164538063957,-2.047836112982669,-0.9912802700264501,-1.4827331132315176,-2.4281351828648012,-0.3680942285699676,1.631496527010859,0.043767769933856844,1.4221640967690874,-4.5949752796783585,2.29651916869584,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5166756999999995,1.0,0.0,1.0,0.0,3.299453802655599,1.8243238318584245,0.5284739928351768,0.8709016073697168,-0.019704385550883562,-0.012645604551415729,0.49089939514775854,0.8923457750027556,0.027864738710748738,0.03402688673268922,0.15399432336087396,0.26867626740350825,-0.6014994535432914,-0.2878475980586891,0.47541371578300035,-1.0495270575188487,0.3994713754994134,1.0042619142772258,-1.2945110774510336,-0.22779076892425656,-0.8112641960358401,1.1237560013898142,0.3719078723274922,-0.6046905025540926,1.3252086777837833,0.16066527230384076,2.294061826682104,-1.3151543029728325,-1.1907103240438008,-1.875197278878074,-1.8572986090012595,-0.29627868165921156,1.8887907213163575,-0.22747356569785296,1.2761462119483615,-4.658578359777953,1.432729793505239,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5333423999999996,1.0,0.0,1.0,0.0,3.306728137894447,1.8368953846403109,0.5294263017103229,0.8735850503256417,-0.019074971799859272,-0.010459506536327063,0.4861850512113646,0.8469000952464047,0.0022017461758362944,0.07880918015747848,0.3158876825155072,0.13550835245746318,-0.7680271613379325,-0.2842006465726173,0.5112270378294969,-1.0657737497612902,0.3803789640221915,0.9697524274184973,-1.3260570063538144,-0.23307136998324054,-0.7778422810833601,1.1178351125973771,0.3899630405851502,-0.6830272611938388,1.339608967746683,0.22752755207400666,1.9678794549958916,-0.6197067862906384,-1.0899110322831445,-2.7151818332584634,-1.7478367034011417,-0.42688819948034396,2.0744104905034493,-0.4592272226303279,0.9309853099063937,-4.693290445934943,0.375013186956779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5500091,1.0,0.0,1.0,0.0,3.314172828799273,1.84841453814593,0.5310875739612889,0.8772365350756366,-0.01607390042276491,-0.008368581679874774,0.47971622663232655,0.8070922543467733,-0.02731824708558822,0.10402955831268504,0.35051217110559596,-0.00940008131080411,-0.9049426952322618,-0.2802633311543854,0.5410098288081604,-1.070183991708989,0.36314093509590645,0.9137556721564881,-1.3527724174201852,-0.24202040403281466,-0.7421170413916924,1.1084483966869885,0.40294077805672596,-0.7611338303046205,1.3377091423498884,0.35444895902890694,1.764268452003028,-0.07547974473752316,-0.7557501984737587,-4.065595792128984,-1.1616602893872423,-0.46459725605192326,2.1736185152747245,-0.5588375111977885,0.8733885987818838,-4.384046343716705,-0.74613185376822,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5666758,1.0,0.0,1.0,0.0,3.321906968396574,1.8591245431139587,0.5329047833152417,0.8809164986672456,-0.013762482677306256,-0.008031159209429532,0.47300340054607476,0.7802138313060296,-0.053463017734935836,0.10201761170596906,0.2771710113512136,-0.14997475086494444,-0.91060339258498,-0.2723856576417231,0.5700361038474946,-1.068289746284524,0.3551872403563863,0.8342322966411451,-1.364779093444075,-0.24855797615812172,-0.7053881856663016,1.0992071583016167,0.41907605210378623,-0.8291624315874853,1.3147378562122853,0.5221530031813557,1.7297542466032332,0.26166369837880477,-0.5126908797762036,-5.291581306775338,-0.20863574559236658,-0.4024048550497793,2.2674684778148517,-0.5168176185007005,0.6391744634619715,-3.7345239704946036,-1.618916190250383,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5833425,1.0,0.0,1.0,0.0,3.329931702955555,1.8691660663439758,0.5345725838321885,0.8844589217213765,-0.010707215872026377,-0.008600408853090196,0.46641591341129174,0.7642466403323382,-0.07304454770116003,0.08732818027027726,0.3807621401219068,-0.2406365475163247,-0.9542883675332581,-0.26285819623814,0.5986684190118846,-1.061461850985449,0.34605120492397434,0.737369275825223,-1.3597269561823138,-0.255433926028131,-0.6665346076332989,1.0912211082824572,0.42424663611708924,-0.8856182116227053,1.2837451614137962,0.5361229165865923,1.5854159384874746,0.5170906992401234,-0.7600191535128752,-6.01233645284945,0.8682468120041502,-0.4816157892280678,2.170913661500239,-0.4553803508110018,0.16531888064827782,-2.960306358173614,-2.39503807237909,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6000092,1.0,0.0,1.0,0.0,3.338229354318841,1.8788042463902324,0.5360133967082683,0.8883560853505575,-0.006138953610092277,-0.00879731571144632,0.45902983138950715,0.7589804629312726,-0.08186764814651926,0.08176994669835941,0.5438324171778358,-0.30312765333290304,-1.0174701721127752,-0.2545148580139756,0.622883407491473,-1.0510533551704733,0.32985321790468025,0.6338206807237332,-1.335837475160816,-0.2646118679067766,-0.6330242522220495,1.0840277829158933,0.42458669247998754,-0.9278395075470296,1.2349030941304442,0.42263687088273444,1.419749092691205,0.7608003705058652,-1.1936005038071411,-6.0129977996294315,1.9080918292222533,-0.6622229242484824,2.1195727920323155,-0.4572898311042893,-0.20616707771838244,-2.0406157165893255,-3.193401278981467,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6166759,1.0,0.0,1.0,0.0,3.346732950011584,1.8882310853069293,0.5376022833486029,0.8922463720471067,-0.0001874905722395898,-0.009042737592574769,0.45145830960664934,0.7530162342583047,-0.08395326442735745,0.08433966873719446,0.6706849083167943,-0.35693830221691353,-0.9933547933934084,-0.24877027236625746,0.6459934834181976,-1.0361017879152288,0.3062644418903694,0.5369356149710554,-1.2961237680021167,-0.27750806765127534,-0.5958820399273689,1.0759780834263255,0.4173743864486713,-0.9536388715500639,1.1772982392209954,0.20763881371254414,1.4130966849768682,0.951780772621894,-1.66193942260517,-5.452612943198174,2.9268964197761105,-0.804124777970112,2.246615198223977,-0.5368368608356981,-0.5715403598769828,-1.1906008782437199,-3.6004953900417216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6333426,1.0,0.0,1.0,0.0,3.355302752335367,1.8973462403163588,0.5392488412836299,0.8957769415454613,0.006671547006342689,-0.009073128590690257,0.4443611591865093,0.7380024713406284,-0.09064790869462253,0.06418964310080601,0.7739848529246377,-0.3767505786818846,-0.9267000383175559,-0.2475935503809699,0.6699867245304809,-1.0193272659643586,0.2744551263552131,0.4520665524429312,-1.238274066041851,-0.29141608078076553,-0.5581369291735704,1.0661331850989126,0.4055353090480641,-0.9675262828618788,1.1148863410960275,-0.010830760391952037,1.466683137036743,0.9651718051674409,-2.0951152345839916,-4.576080141450124,3.773316157340829,-1.0307281010003497,2.2003501128037417,-0.4153151396579288,-0.7010496742297821,-0.5883854188632762,-3.57002629974697,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6500093,1.0,0.0,1.0,0.0,3.3639978638417776,1.9059413081754288,0.5402753818472,0.8989641911652503,0.014299962125327576,-0.008842106611002369,0.4376993388577384,0.7189868700320329,-0.0890757188039129,0.031288770530305085,0.8863976593437526,-0.4199701441681048,-0.8668220144177989,-0.24913129843470655,0.6948830190982982,-1.0039293300648604,0.23642712772988736,0.3843993051840418,-1.170346311203012,-0.3118657397331604,-0.5225368894772366,1.062134217750052,0.3940060172377003,-0.973251758071201,1.0582971245610098,-0.1843545324313415,1.4338731914950926,0.9555615036982315,-1.8405459244896623,-3.66815755989996,3.974737437470114,-1.2293926105219555,1.9439367101502942,-0.0750839937836905,-0.6621655917817133,-0.19384144016673757,-2.729414613216614,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.666676,1.0,0.0,1.0,0.0,3.372416170746003,1.9143353023396648,0.5409188736280751,0.9018215311078387,0.023142645665815496,-0.008705098839644494,0.4314007014784423,0.697419287540466,-0.07400488885901901,-0.004587327040534684,0.9393505040656037,-0.4536228794971236,-0.8774950835120315,-0.25373871375231677,0.7177825931718634,-0.987475152136984,0.21310347283582937,0.3297943892357619,-1.1057825531436847,-0.3323959164243381,-0.49333890923944657,1.0636303803005234,0.38346307851096756,-0.9739876771235327,1.0239056720278328,-0.2760641269931676,1.3815271805216087,0.9158079395241691,-0.8220213174282043,-3.188028648573326,3.6812466699808706,-1.4329657932377782,1.7198610874549258,0.16290259625669465,-0.4762718955786471,0.24903135570070478,-1.5187000842760197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6833427,1.0,0.0,1.0,0.0,3.380508493361982,1.9224820708889667,0.5408674130742734,0.904842371977462,0.03180714557650248,-0.008560925688394241,0.42447060901296024,0.6741202226561559,-0.061546613999776234,-0.04231140751756533,0.9304354564152483,-0.45923990656962793,-0.9454783092968557,-0.2583334544054206,0.7409340172174972,-0.9734023376935255,0.20902636234752606,0.2781314710296877,-1.0476378434538716,-0.35963136170547255,-0.4652080719046666,1.0675643151521148,0.378130255633619,-0.9649506962790871,1.0076736871718035,-0.30708359208811226,1.3995293695680358,0.8119768301034971,-0.4798207982658858,-2.9779749850616617,4.2456550859973525,-1.6419090892476136,1.6199627351857064,0.3311267898608528,-0.15020672122260495,0.4584971955827137,-0.02787767283212973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7000094,1.0,0.0,1.0,1.0,3.3883470636542703,1.9303674336187524,0.5403632642749844,0.9079477461894175,0.040556521903778134,-0.00854348184150093,0.4170288570814369,0.651706673930987,-0.06941941969560683,-0.0661540379945226,0.9580867292432469,-0.41294774272783724,-1.0630570462251907,-0.26397485396082665,0.7644336654594226,-0.9604092036684121,0.1971094142389133,0.23052835786870748,-0.9642604339001005,-0.3871263288598645,-0.43934004340240734,1.0746679620376711,0.378456177789766,-0.9587044067042959,1.0229764144082503,-0.32442334552304364,1.3960154705370063,0.7284012463460314,-1.3010635477777215,-2.1084857254114535,4.888095666652118,-1.7349964710388197,1.53432905971158,0.3920579180937739,0.12906666053756097,0.4528755775652405,1.0285890853373874,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7166761,1.0,0.0,1.0,1.0,3.3963864446113354,1.9375944871388169,0.539587776675066,0.9115082204310451,0.04933484067777948,-0.007419973134635837,0.4082447569542183,0.6487403113004757,-0.0880088654825188,-0.06051503666287235,0.9441554096237805,-0.29472203368987404,-1.1454786360198308,-0.2691475875510784,0.7874679593030954,-0.9491222475885747,0.16565749068403215,0.20784847295025757,-0.8847009953590899,-0.41746469307319795,-0.41406366762567665,1.0806329385591018,0.38243248625598175,-0.949854813501874,1.0419600585889888,-0.2713261781440397,1.305952032951037,0.7297207741982051,-1.4708310313007893,-0.7436814085666706,4.190284156446777,-1.7273566352890435,1.4675140643519948,0.2467391993148311,-0.012473294344534364,0.596321460544611,1.0589665607112928,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7333428,1.0,0.0,1.0,1.0,3.404892785773493,1.944697665121688,0.5392736461851944,0.914933637311963,0.05705320072432316,-0.005645910887421036,0.3995115709118609,0.6869815218999623,-0.095265152940258,-0.05083653005136165,0.8043899355004307,-0.16632801173318995,-1.1607843185334368,-0.2730190779873732,0.8079654869545927,-0.9360851292137536,0.14808161514015156,0.20573892800439122,-0.8245840159995975,-0.4447049985266083,-0.39042281008973656,1.0828926184641121,0.3780404004800619,-0.9388269849313782,1.058275370363064,-0.12806213932825197,1.2078546542680642,0.7621249747936665,-0.24358795517427545,0.35411532908649856,2.296300047658368,-1.5171340474352215,1.406561583172974,0.029475391100663828,-0.37494484877344914,0.6591692247331028,0.9209348750059744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7500095,1.0,0.0,1.0,1.0,3.4142382526452066,1.952363835585966,0.5388676572932778,0.91846249006536,0.06282099812085759,-0.0034758650250765965,0.3904716313643865,0.718362842071435,-0.0970499415845909,-0.040514919553052114,0.5216849890316809,0.016582925666583342,-1.2312626903710078,-0.2734163340661628,0.8277298616356745,-0.9237180309537875,0.15753787593902596,0.21965234086082946,-0.8081575073504744,-0.46803592912997516,-0.36717818774913863,1.0816154535608167,0.36993429963387686,-0.9278824620661555,1.072657949151513,0.12813576069148386,1.0985430140054515,0.72385867496705,1.1429318728201525,1.545294833458765,-0.6367674059505382,-1.2385729640216085,1.2510703875490943,-0.141362775401409,-0.5116027487687697,0.7634426028661693,0.7085473040870329,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7666762,1.0,1.0,0.0,1.0,3.423799983769677,1.9597990190506638,0.5388969540610845,0.9224006522041897,0.0650069663257783,-0.0006685322723403641,0.3807238949777195,0.74190192989701,-0.09594366454481384,-0.03485438030057568,0.1964756345253021,0.20113044913847364,-1.2814159432123189,-0.2687478774219397,0.844583660657642,-0.911956458457607,0.18617942042961483,0.2572488588060056,-0.8458096386491092,-0.48599084656552616,-0.3487203804334076,1.0781805165265468,0.36098694141425297,-0.913378847272999,1.0818936610691188,0.37165333831873604,1.0279289928883675,0.6345064309232936,1.5535658154551224,2.1539582932843753,-2.206287142563118,-0.9188440310789765,0.9924451720746771,-0.17751885869426515,-0.5403684033414768,0.9479165536218048,0.5639410367133589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7833429,1.0,1.0,0.0,1.0,3.433989489565373,1.9676270925598236,0.5385883813651525,0.9263816437022618,0.06458108875226118,0.002278571374048741,0.3710001904306273,0.7849531100026516,-0.07908182635956901,-0.07551015642121302,-0.026059605986268303,0.2747724332461742,-1.2807001274384358,-0.261027864678649,0.8619942299272196,-0.902567774289249,0.20932350669191774,0.29145109423419485,-0.8817005591883879,-0.4986641247555431,-0.3340966158503046,1.0756981464364173,0.3519219834979341,-0.8962851804176585,1.091456021304694,0.48354126830428634,1.1015381634315446,0.3979222266861807,1.3548798186683453,1.7564821976975282,-1.8788337933817216,-0.7293034094484216,0.6360851136456549,0.32103521838898313,-0.4524675758422166,0.9655496316493478,0.6502897257650335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8000096,1.0,1.0,0.0,1.0,3.4444420167286984,1.9762005058561258,0.537224447088197,0.9303355132412786,0.06285252774170755,0.004804750986813605,0.36125103034665457,0.8145507948742543,-0.049661853054183414,-0.10810921127163339,-0.21971893958029187,0.28878457983189376,-1.2472898106796868,-0.2526298029090456,0.8813016728745711,-0.8986923577065858,0.23134217137721425,0.3157983824947364,-0.9084375570174195,-0.5103010088340342,-0.3275175009062115,1.0888817118751941,0.34590465872167403,-0.8811937951813786,1.103570028613935,0.5975011319644554,1.0956284422521283,0.22866139066710697,1.4856042925042166,1.6701561423305882,-1.7733303936635136,-0.5404597793366158,0.05493295456775184,1.2315662521491082,-0.2658017734724025,0.9952290943560156,0.6861054186713443,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8166763,1.0,1.0,0.0,1.0,3.454969097881671,1.9850927398876388,0.5358042821262741,0.9340982740978212,0.059331130174408775,0.006759698613511498,0.3519865591103636,0.8288298097792022,-0.032629924428735635,-0.0984881458377655,-0.39695993060946083,0.2559147686314107,-1.187759633192305,-0.24111112044642505,0.8985152510441867,-0.894945712689586,0.2588437488156778,0.3471230769889573,-0.9408116905325312,-0.5166794867640823,-0.3322655137025159,1.1167504369458043,0.3430619066620691,-0.8631108109238517,1.1143262476674334,0.6947727976561054,1.11450955353817,-0.03692373887633365,1.5075804529114252,2.1305511833846382,-2.0482269622047027,-0.24820263563560935,-0.4421738774039399,1.7792722137745436,-0.08004669768733302,1.1443593177097393,0.5671152667704686,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.833343,0.0,1.0,0.0,1.0,3.465757137699183,1.9939278714746067,0.5346442263973341,0.9376677693986538,0.05502774897437096,0.00764378960186349,0.3430636581660745,0.8395750003167205,-0.036206607685126624,-0.0818925849360525,-0.445250833402706,0.17055042479492158,-1.0899440173747268,-0.22947066333565555,0.9184520656264803,-0.8999231514640462,0.28159495364629195,0.3868168973109699,-0.9767119256393737,-0.5185744465687302,-0.342256659631268,1.1481909042858265,0.3432364301289831,-0.8430484083004328,1.1224739086473017,0.6505273454182978,1.223991949790139,-0.9224898235876174,1.4218506748714907,2.2904144783059954,-1.9200318528909879,0.1699690081990104,-0.5910843074542841,1.6965240085961795,0.04065483030800515,1.2628017442046482,0.458357092315873,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8500097,0.0,1.0,0.0,1.0,3.4769975019807036,2.0024731556979343,0.5336159672288944,0.9407283471901375,0.051254440650832726,0.007878686995874684,0.33517321700533215,0.8460656778264467,-0.03924360107219038,-0.07322596249012828,-0.32002373655221805,0.07446344272466032,-0.9701592082131839,-0.21942683223065876,0.9393150643033213,-0.9256954349751615,0.30623886610143913,0.42347037896012235,-1.0048128802976877,-0.5110138418261814,-0.3519683633566125,1.1733013503339442,0.34441707038265795,-0.8210173352635805,1.1296048479684353,0.3833265204806098,0.6146938515244268,-1.738748862248459,1.2221394418648124,2.2584724105645138,-1.5788851715732874,0.45885302180607135,-1.1717319557161419,1.9250243887589225,-0.021709939948231245,1.404002153097585,0.44199597065172125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8666764,0.0,1.0,0.0,1.0,3.4883231581788574,2.010950527779175,0.5326343544372917,0.9433620420304377,0.04946534170795362,0.007838528546184038,0.3279631002050517,0.843504507646852,-0.027441138267122078,-0.07637889151485462,-0.11003972553027888,-0.023870559088212145,-0.9222265081366532,-0.2166930870978672,0.9389419016568846,-0.957881562788919,0.3223330165177485,0.46209946156128107,-1.0293415366174947,-0.5032793152516597,-0.38131446960393645,1.2123585122460832,0.3425127640167127,-0.7962482429303698,1.1372071371354238,-0.09937169502789309,-0.5117850154753956,-2.3730555009893286,0.8096894268368844,2.3539548807794395,-1.3820731725924862,0.34940788759444513,-2.3447308014094803,2.7288057191448467,-0.2197609928667574,1.4928522060140477,0.47566258308124804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8833431,0.0,1.0,0.0,1.0,3.499507460535009,2.0194040621549108,0.5314891456321379,0.9458643652029142,0.04953325077257303,0.007647852561741427,0.32066894152440717,0.8257633808864586,0.004988061107463471,-0.07510114624065867,-0.01776196007506209,-0.07506946589611285,-0.8851405831892716,-0.22273922868970153,0.9222555296684738,-1.0047974432118392,0.33322856764196374,0.5019356985830957,-1.050882078188982,-0.4993668889458407,-0.4301262130523153,1.264261722892487,0.3370916893030332,-0.7712554955396318,1.1454602991153158,-0.5717168505734032,-0.928155634052833,-2.97035634534772,0.5898713149830196,2.3447078712756326,-1.1700477373766653,0.47297930045770487,-3.2728622421548295,3.038788549995834,-0.39884158914756507,1.526845795105554,0.4049241931266455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9000098,0.0,1.0,0.0,1.0,3.5099681434409953,2.0280224197588073,0.5306361386078885,0.948121258067405,0.0494725556072621,0.007291875439248642,0.3139512299624676,0.7906448181862533,0.03391900878229004,-0.0547320560103078,-0.10187171257786891,-0.0656135250488585,-0.7920447840676439,-0.23575035356477067,0.9080033186447479,-1.0568936389909327,0.34199543300860347,0.5402565469176602,-1.068343205866566,-0.48751330703778284,-0.49041009586658024,1.3136516664985143,0.32921801778902127,-0.7453532813037983,1.1507046372345915,-0.9947283896745612,-0.989459341590271,-3.3575108040310204,0.545857163612652,2.2165441906897083,-1.0183132271927307,1.0064234863535817,-3.8030517860400903,2.5311337099502915,-0.48764321947732825,1.5621595021356764,0.17232738013541973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9166764999999995,0.0,1.0,0.0,1.0,3.519909997959902,2.0361778824931136,0.530239381743652,0.9501057519745864,0.048169081687044035,0.006739956612537078,0.30811259730672147,0.7541401887037174,0.043092729463698354,-0.039177930025568686,-0.23307010668916472,-0.05459372853449078,-0.7156408978544477,-0.25589690799407955,0.8892734856515087,-1.1167146938469268,0.3514238428195297,0.575820652709032,-1.0848259203162882,-0.4658193723058222,-0.556894859457104,1.348633015299744,0.3208368828109076,-0.7191834079911424,1.1512045566083218,-1.6579569417246913,-1.3104208706732468,-3.9891970194476034,0.5512296545833009,2.0204088715826756,-0.9552695330345005,1.6192730429093576,-4.0640138012162,1.5682249482024624,-0.42759936480369853,1.6537545238753093,-0.04311029483567419,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9333431999999995,0.0,1.0,0.0,1.0,3.529435480155632,2.0440276907357857,0.5298980493295186,0.9519897435022694,0.04597934327269952,0.005810959546317256,0.30260148877334625,0.7339234520660898,0.07084770357802528,-0.040542688967521626,-0.37098055738377184,-0.05178727981909459,-0.6670441433510819,-0.2910156954860565,0.8643225355942483,-1.1898671389189874,0.36036979157669047,0.6076036439976742,-1.1001855873190183,-0.43353743098926806,-0.6258774935080403,1.3659259359869262,0.31496467712227366,-0.6902280202576531,1.149267624532716,-2.097291266913193,-2.281654269528409,-4.139396493425314,0.6050414722180941,1.9225789178669526,-0.8247960681248756,2.120668358120447,-4.094887916409221,0.4974314287065265,-0.3787617463236283,1.6636856376548215,-0.1601558581652171,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9500098999999995,0.0,1.0,0.0,1.0,3.5384803353405947,2.0523185849752026,0.52951889956754,0.9537579021815025,0.04247720499131173,0.004567081386752689,0.29752427270740867,0.7127999991401321,0.10312998231017145,-0.05102498989901577,-0.7416634677375118,-0.03435575512151012,-0.6129457738564777,-0.3258067567106038,0.8132181912236104,-1.2546948529208701,0.3715919322295643,0.6399067448098583,-1.112319177573522,-0.3951302856572501,-0.6933913963299392,1.3652140960853902,0.3082114660160036,-0.6637271091569392,1.1458660173257573,-1.8389203492394703,-3.8114493248948405,-3.3921437007002093,0.851320069539803,1.8541563640324532,-0.7386419981553816,2.6049134161161196,-4.2228156891497255,-0.5002857459105853,-0.09927159314441053,1.5115745330632595,-0.22831435089634783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9666765999999996,0.0,1.0,0.0,1.0,3.5469805605999594,2.0604713496624356,0.5288848712219144,0.9555311345198875,0.034305187576980214,0.0020475262510185038,0.29288088484006,0.694951084023171,0.14203811088624602,-0.04717891424267073,-0.9499782689394475,-0.029997269615104905,-0.515012153574126,-0.35231316305539545,0.7372739706677987,-1.3029388217519078,0.38874718398268854,0.6694089797425136,-1.1248070365003309,-0.346706810124503,-0.7666382980007438,1.3492497111041903,0.31165561739935377,-0.6398421017172422,1.1416571309485477,-1.7625770057970085,-5.2301399812732825,-2.144601784051059,0.8795362876497321,1.756835050101864,-0.6691726538745637,2.8124779230815102,-4.176120114455749,-1.5356649949478989,0.17243446956321168,1.5567852922475713,-0.3369593174087465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9833433,0.0,1.0,0.0,1.0,3.5549839410202,2.0693000723803543,0.528640908120046,0.956830744340025,0.02747596834648022,-0.0002501572948946194,0.28934397396604733,0.6955407596364194,0.1665498219946574,-0.04893862165571509,-0.8124752208260726,-0.030483281199243817,-0.393235004697975,-0.3845594410756378,0.6388798431718355,-1.3261817220293577,0.4009098671203079,0.6984680302689238,-1.1346249773141843,-0.3013808340560049,-0.8325956785531384,1.314025160542794,0.31395929316374194,-0.611834162296334,1.1346340176148446,-2.0389605826790467,-6.12265524025339,-0.8752826772539861,0.5225323983280675,1.7297289213667697,-0.5675635622522568,2.600105596941026,-3.716107011965949,-2.495608345161074,0.23570604438552306,1.751415874151446,-0.42223599670377815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.00001,0.0,1.0,0.0,1.0,3.5631840171973344,2.0780082967402125,0.5279268818945488,0.9578082569521232,0.021496947896808248,-0.0021739881610730806,0.2865946578722866,0.6943949405702354,0.16554404195982608,-0.036130402788108175,-0.7207915244560501,-0.07250427241039925,-0.30164303635902556,-0.4202786517420692,0.5331850544823363,-1.3321149693458858,0.40616496542911734,0.7270667257700006,-1.1437258597463102,-0.260036450219429,-0.8905087794734096,1.2660625998915982,0.31951250125927416,-0.5814614558178024,1.127582569576022,-1.9558962233531534,-6.379152201194385,0.46630504782828613,0.3842046035442806,1.7299578920349077,-0.41871128013092557,2.362576307221084,-2.9926808631695576,-3.3070421435718145,0.2533011332370936,1.7865729353190427,-0.4813054330312921,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0166767,0.0,1.0,0.0,1.0,3.5712880822099327,2.0866631471980255,0.5280396459744233,0.9585303132504678,0.016323856699243924,-0.004740669310221291,0.2844832092354727,0.7033224011963253,0.16268858992294694,0.00622084231839254,-0.6983620212427186,-0.16928219198002253,-0.2251859774756369,-0.4497561122471578,0.42624101118854263,-1.3106381893480783,0.41371671285209083,0.7561334086672802,-1.1485820478993005,-0.22262813297688164,-0.9323519068375146,1.2037902019542572,0.32240268115838727,-0.5522816120141703,1.1185904710934393,-1.3103474918410714,-6.009528424904781,1.934507721423163,0.4506001185659021,1.6977636689035651,-0.13494621451309358,2.123677241780324,-2.1119042910412165,-3.97822298734238,0.2467084854020616,1.8744395087941021,-0.6192740472866516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0333434,0.0,1.0,0.0,1.0,3.579874063140679,2.0953256851151316,0.5287200082854514,0.9590501791367889,0.011157440639780417,-0.008125363161769497,0.2828997064147507,0.7218341271767486,0.15530175012121766,0.04405298140691437,-0.7120863687416015,-0.25605178854377764,-0.18839609439189772,-0.46395698882660436,0.3328670396836153,-1.267631249664599,0.421184999421322,0.7836589612510307,-1.148224075893161,-0.18924706724826876,-0.9609057299684028,1.1334549017653197,0.32773613388657524,-0.5189800138953651,1.1069400600481971,-0.4640680063549316,-4.8380644371866675,3.160139199386937,0.38009959672118193,1.5416482310383266,0.20415165601571553,1.7521168496166368,-1.2758408025989352,-4.30012715453081,0.2872649963052619,1.9943208399926542,-0.7644889876193207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0500101,0.0,1.0,0.0,1.0,3.588671142841936,2.1040237643550257,0.5301214058679689,0.9595138690344336,0.006173398849179087,-0.012155993900760732,0.28133122132018273,0.721380562636836,0.1291632961520055,0.07082641484533714,-0.7133456176784833,-0.31308493819061617,-0.2770151449759126,-0.46522507673018926,0.2649718740780246,-1.2053000053592338,0.4263867247494367,0.8075217858117731,-1.1417769790886663,-0.16422412118187044,-0.9748800186468659,1.06045234346142,0.3319782001862291,-0.4858041177263591,1.0931074538735295,0.38204440456342226,-3.6950102170952492,4.420829031928315,0.36336228904328605,1.3555327499650527,0.5664993962366439,1.3170146271110228,-0.38077908396068144,-4.084082444928099,0.3060581626466725,2.105212061468248,-0.856191887347857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0666768,0.0,1.0,0.0,1.0,3.597734705780896,2.1118836020229605,0.5317460382404382,0.9603542823758777,0.0012795200111793332,-0.016456060181354204,0.27829339416191956,0.6859369715488786,0.08861902035778935,0.07840059784191288,-0.7178888650909196,-0.3028985102541908,-0.4401519399134202,-0.45122214987153,0.20969978611309253,-1.1202699872117197,0.43329709994691745,0.8288434766187158,-1.1293407249186465,-0.1453464918769262,-0.9735983914856978,0.9973185479955534,0.33793809304534184,-0.4488061381656194,1.078400273390476,0.7230467802208251,-3.0020094765237664,5.062713892001888,0.4515294917013405,1.1755109395803967,0.7884594920219425,0.982831058455708,0.4665160734226162,-3.2380736446242846,0.2595586025402144,2.036620816235478,-0.7873449347059671,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0833435,0.0,1.0,0.0,1.0,3.6063219461227076,2.1187104558571512,0.533452515814315,0.9614847888139811,-0.003784818308605097,-0.02032977117546263,0.2740791426461678,0.6382822864659073,0.057644861276987425,0.05700054154575453,-0.8062741839212089,-0.2532511654295604,-0.5989834231448339,-0.4411234691863764,0.16490469139326727,-1.036542538111578,0.44143773790811414,0.8467055621651823,-1.115494943457302,-0.13146302037794294,-0.9593294517650405,0.9525163394357008,0.34063017090814307,-0.41791662141045544,1.0668625702270016,1.5819087410389403,-2.26424786833021,5.388209866851133,0.6549991793298621,1.1042258250481511,0.6913519014983733,0.7404360090931855,0.7075739543502093,-1.268243852695441,0.21257791366320766,1.6847964910702504,-0.4926227475285074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1000102,0.0,1.0,1.0,1.0,3.6147060971783502,2.1247257816891385,0.5343966546889583,0.9629399354301874,-0.010275283951796037,-0.024236003728720656,0.26842823140772293,0.6134029822097486,0.048476924375163155,0.013606353630193066,-0.8982915096119382,-0.1765129746848253,-0.7881732121498103,-0.39849175304298257,0.13422470621889432,-0.9406626324360241,0.4551304495911915,0.8656510777353759,-1.1062956154452406,-0.1206652422114194,-0.9500125458357606,0.9550436683561152,0.345024037672643,-0.3926461428101783,1.0619794822980093,3.0452224818004185,-1.107833332599895,5.214971158787653,0.8652471086298087,1.1560049776244967,0.4512185928963467,0.5152279552606065,0.6326684088555888,0.9624958970486871,0.2448525898254129,1.3134638492962398,-0.12664821115507305,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1166769,0.0,1.0,1.0,1.0,3.6229399724896707,2.1306766019814876,0.5346940071992242,0.9647769399690264,-0.017081627325496,-0.027325404931391656,0.26108810075767547,0.6351345917853781,0.06590696970848531,-0.042536705003664424,-0.9568623467992634,-0.06787580687223371,-0.8898837950057296,-0.33961585011153034,0.12797683978438193,-0.8627098184872457,0.470279365878915,0.8852391384863307,-1.100454293612851,-0.11428872085405904,-0.9382404626252936,0.9845996001703835,0.3487919402258295,-0.37413440553632415,1.062640954745285,2.959553713064585,0.4680957029888023,3.5312574933394942,0.9781905243325264,1.314265366837129,0.13403409456578105,0.28892830295561084,0.5139248829517712,1.8427474945342872,0.26885172097871374,1.065858600934094,0.1820772493548207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1333436,0.0,1.0,1.0,1.0,3.631942016586814,2.1372808522234505,0.5338053799549327,0.9665052532853757,-0.024955082607241247,-0.029736335155371524,0.25369388955070443,0.6776798826014008,0.07768764305229103,-0.0980255103171497,-0.9279139157930123,0.0387717911326147,-0.8202182616202365,-0.29983976530391554,0.14982792752490126,-0.8229538139075414,0.4877368656149773,0.9094600109143046,-1.1018278033574416,-0.11103427951767884,-0.932881682142376,1.0164687076904244,0.35398577962871486,-0.35711745172180176,1.0680487360816533,2.141144650236787,1.7904110016972408,0.9299003083874658,1.0143032213915288,1.5497580039511187,-0.25038657098069284,0.044987045563917825,0.1531445756634236,1.7974398197421992,0.4921948228976759,0.5534579352001009,0.8346704129203595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1500103,0.0,1.0,1.0,0.0,3.6415447843359834,2.1439325101320605,0.5322847700773975,0.9678974402716163,-0.031780311845049924,-0.030964804258497153,0.2473979340898331,0.6754735737564898,0.08420340131306003,-0.09565379576688357,-0.7657402778420442,0.16718130205302756,-0.6475835433042918,-0.2682442190273274,0.18765732586835673,-0.831713079547643,0.5040895408788474,0.936897841935235,-1.1088005293379788,-0.11278914966945874,-0.9331356332268744,1.0445143806577781,0.3651984671354069,-0.3556857707991251,1.0904633574873246,1.0592696898484542,2.199450365395991,-1.3185266100114448,0.8737027011161839,1.605891527443314,-0.6149704543751792,0.11629432398652241,0.29518929563205487,1.4365621865876763,0.6934467031725626,-0.3568322208993221,1.6958029603558409,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.166677,0.0,1.0,1.0,0.0,3.650561055276901,2.150418489953664,0.5314093679640881,0.9688747656517924,-0.03765466919903873,-0.030534766030666315,0.2427579914938903,0.6841079214217838,0.08592616726475866,-0.07888030878953636,-0.5684119646713014,0.3488708468910073,-0.5341007971281717,-0.2645307050243211,0.223143086334792,-0.8669047888096969,0.5168603472323635,0.9629898355551836,-1.1223268595013112,-0.1071577942985065,-0.9230420192753545,1.064354209680826,0.37710071596424716,-0.3690118828739272,1.1245756144803787,0.5366014350214481,1.6016711163262625,-1.445587494198911,0.5949771905813345,1.6297809880107605,-1.1642476205467145,0.2937800475890682,0.6800944886005431,1.011572415707356,0.6237450795170156,-1.2044796334068222,2.3567064127298,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1833437,0.0,0.0,1.0,0.0,3.660481095485016,2.1570775114386027,0.530348697715357,0.9698872601276206,-0.04208865423551758,-0.027972499514439225,0.23825361927512248,0.7190556313603772,0.08566735075110121,-0.07404518646971403,-0.3768737680853881,0.43688376643966276,-0.39634131936889544,-0.2503574687531835,0.24104646985730657,-0.8798994257267729,0.5239221535633712,0.9912239835209928,-1.1476088609727106,-0.1029964618311533,-0.9104657716005571,1.0782335286195177,0.38599001136897937,-0.3958351722113281,1.169020395025412,0.27574779250371473,1.5985678184572256,-1.440223299135107,0.13230532085700078,1.6090357121559935,-1.6502303371221378,0.15909080491738445,0.8193531940775336,0.7495411318781054,0.3658147428084105,-1.8203135842276654,2.4957610590892783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2000104,1.0,0.0,1.0,0.0,3.6706413907536337,2.163904864762637,0.5295024377503768,0.9704007765077908,-0.045290932095444054,-0.025243565207264573,0.23586824041958102,0.7143507275344586,0.05984658034337159,-0.06700563725402196,-0.2234250917723572,0.490460246456597,-0.2578107624181763,-0.25533909355767775,0.2764287868545541,-0.9149123281290871,0.5212705334146183,1.0166244665627642,-1.1773346474207382,-0.10185475686187336,-0.8957301915158904,1.0893389640461717,0.389294565112177,-0.4296891237024217,1.2077678161674252,-0.1683223010707136,1.9885606748801394,-2.1622156906007137,-0.4771193971662516,0.9358720050120781,-1.8353529308488679,0.011163777890279555,0.8572969443551686,0.4951645175586187,-0.11886050843039443,-2.432550567450684,2.029302913260283,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2166771,1.0,0.0,1.0,0.0,3.680861510844632,2.1696273493979974,0.5285859292887553,0.9709384404262688,-0.04751795141600761,-0.021115002390794786,0.23361238381102065,0.6892739056200848,0.02981739164799585,-0.0629124380225731,-0.26172581270428275,0.5375575700662321,-0.23183377053541712,-0.255968223343694,0.3073319582573562,-0.9519734262278428,0.5080181418498697,1.0224197794128624,-1.2087874143578683,-0.10262433515722545,-0.8818891496355885,1.0947390455491062,0.38202798649726566,-0.4769203532963887,1.2366639607542824,0.09982502011156485,1.7855784416047786,-2.142864700892739,-0.9971624301920267,-0.12107780599839436,-2.2510170521921515,0.06067830642806897,0.8272052673425528,0.28116514031089007,0.022795759784928083,-3.714667010899322,1.8448310029640747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2333438,1.0,0.0,1.0,0.0,3.69077259796347,2.1750820038796794,0.5277471472884279,0.9712811853390559,-0.0515381216478431,-0.01774244787681001,0.2316071815957126,0.6855876412533355,0.01882233874742406,-0.07024623214234123,-0.31201043851919574,0.5080936517974695,-0.25779844823656467,-0.2520115862322909,0.3359481872799428,-0.9863412943498251,0.48803171926405536,1.0125885316242973,-1.25236869922828,-0.09983214260238396,-0.8681566274574541,1.0987111541342107,0.39005442529139195,-0.5535116050435331,1.269262305921628,0.2965934257911987,1.8197303238839797,-2.078776525076716,-1.3856797677659285,-1.1038555091068805,-2.3349343703952563,0.1505178404562337,0.8707945028607562,0.2743264179202638,0.6974439224000683,-4.759082739952205,2.131015933919948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2500105,1.0,0.0,1.0,0.0,3.701103808249085,2.180292540006171,0.5264323990456551,0.9718183937855094,-0.05445625871983333,-0.014320999506006075,0.228907043053595,0.6893987626767392,-0.021102108944982156,-0.07563000524973751,-0.2035498600851385,0.4611269382368586,-0.32797777849865073,-0.24608175604442567,0.36798975703551046,-1.021266115648835,0.4618287238790209,0.9856245221855992,-1.2866187157000015,-0.09760706377416163,-0.8528626081539298,1.1038832777682095,0.4052761637401961,-0.6355567619003115,1.3076979672860096,0.4123560460207084,1.9135580613992205,-1.9786672393751616,-1.6667161806164617,-1.8186714438812037,-1.8079874141422094,0.13916780997710754,0.9982490631662816,0.24919436031923448,0.8219514503010699,-4.8195550832264455,1.7405111073092732,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2666772,1.0,0.0,1.0,0.0,3.71177982299163,2.1844661087811033,0.5253879240039704,0.9724603059193045,-0.056518690096671195,-0.011351378960111843,0.22582678600377107,0.6823587439813181,-0.09321094387048756,-0.0626524595605288,-0.003385936516139748,0.3943754828435557,-0.38804592598822313,-0.23826635720786424,0.3997335835637876,-1.052297000906813,0.4324744021290946,0.9519660289168276,-1.312635066898848,-0.09519320632529304,-0.8348815921353072,1.107017649424476,0.41745286176485763,-0.7141637624547535,1.3272794588660108,0.4600081095169298,1.8934547799390167,-1.708007040723,-1.7421019129166933,-2.1876616006212193,-1.919933039644767,0.08214049505997933,1.1558480569321157,0.0821744950514368,0.43557714899640404,-4.640086465689133,0.3428616395380337,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2833439,1.0,0.0,1.0,0.0,3.7229834514279183,2.187322677315259,0.5246368723361118,0.9733518384350099,-0.055923484870059735,-0.008316875972972523,0.222237692638366,0.6850437054380132,-0.1653488180809647,-0.049727506911495745,0.2696560476514867,0.32052383472743073,-0.509189594185027,-0.23074812172665404,0.4311050425971297,-1.078199797540071,0.4037585439750036,0.9127023229874518,-1.3506166116836964,-0.09486904179612932,-0.8143342625329888,1.106622433081557,0.4197954310785528,-0.7902266200957136,1.3191267114613867,0.4718417716960426,1.8879973558629128,-1.3210087174393947,-1.6316522443211314,-3.3515134985099104,-1.8641697447485994,-0.05180860823266257,1.360784248134964,-0.07516171498263376,0.0917851593862425,-4.4492111529218565,-1.0420870676582263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3000106,1.0,0.0,1.0,0.0,3.7348033107392875,2.1892593498327813,0.5241634521101157,0.974634852826997,-0.05326590590922771,-0.005634199928003891,0.21729680787747094,0.7138698088370574,-0.21209545320320228,-0.02749531855561214,0.4563828405711734,0.17256125641501832,-0.6602628876455454,-0.22253826669521137,0.4626669546257084,-1.0963307128887074,0.3780858852082406,0.8402486888655973,-1.374774182668451,-0.09692016338695568,-0.7895220264785252,1.1045122539142738,0.420512373196743,-0.862471097499559,1.2925431538049321,0.555793969204392,1.926483055971057,-0.873206845296671,-1.8032581197290416,-5.107161603522538,-0.719003472151796,-0.18114702500779445,1.6566155414195194,-0.13297679414060878,-0.13753630926070742,-3.6839008959639865,-1.9504896176440911,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3166773,1.0,0.0,1.0,0.0,3.747552102564748,2.1909610966586026,0.5241874819040314,0.9761579208205662,-0.049082916492603136,-0.004452225479887591,0.21139242800092362,0.7432186719609674,-0.252674544047669,0.0051457057583806885,0.584102439099565,-0.008519775255374146,-0.815803923449562,-0.21222161903357636,0.4953212728950353,-1.107306750597083,0.34364981976682757,0.7424632623925936,-1.374583442022321,-0.10090728803952413,-0.7591136340446354,1.1021898644117505,0.41521087826744196,-0.9130235622212396,1.2541102608406092,0.6923707960141511,1.915757515502978,-0.28137709566925817,-2.350818298714223,-5.754577249210788,0.2291835550195862,-0.2957399747122784,1.941171609968562,-0.20339778876048178,-0.2987689033924409,-2.6364213503456155,-2.702718276999725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.333344,1.0,0.0,1.0,0.0,3.76082946921525,2.1918814702861935,0.5248583271681303,0.9779724479524143,-0.04368026506786225,-0.004383534006522638,0.2040654554773472,0.750781050857375,-0.29459767332248543,0.030290159209172583,0.7481847363587634,-0.16779730589110192,-0.9265943125878155,-0.19945919400335327,0.5265256661929754,-1.105709968169489,0.29972511852987993,0.6484290635867545,-1.367134715555561,-0.10677818226002994,-0.7248161767347991,1.0977323140624051,0.4105533898324014,-0.9503519849391695,1.2024523643903895,0.7956483219871893,1.8206989182274542,0.29579301844430245,-2.8407049118428374,-5.087751474856332,0.44737503884698515,-0.4332432624219815,2.1412554226162426,-0.29363766861103985,-0.29532229555435763,-1.9268676317045839,-3.162738478890481,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3500106999999995,1.0,0.0,1.0,0.0,3.7743820401158166,2.1920794560949366,0.5258182368655813,0.9798272511718263,-0.03625665176470826,-0.005330769174725992,0.19645761874735537,0.7338481394844372,-0.33037523504734595,0.05512799767143883,0.8285339942653102,-0.30430310797047505,-0.9820139232348642,-0.1856999552574486,0.5560113582158783,-1.0974469635960717,0.24895946665840554,0.5728712073806176,-1.359670910902419,-0.11534875900314101,-0.6877383105403991,1.0924019225488713,0.40536678206081034,-0.9772526117359012,1.1486854340283612,0.8143708360942095,1.6683546625999084,0.7756449447524254,-3.202690736997796,-3.7886396213165456,0.9585958886939441,-0.4969669292770214,2.3082014959541524,-0.40880731035158635,-0.28414552707731416,-1.2842957615205128,-3.32776442216647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3666773999999995,1.0,0.0,1.0,0.0,3.7875915803288702,2.1913016020366713,0.5274035693890975,0.9816586517703988,-0.029073322335028847,-0.007227367232613304,0.18827851310123384,0.6987179369150399,-0.35797359143155033,0.06297537355892137,0.7911782965524911,-0.40579428428947784,-1.0382487733757944,-0.17231344517549055,0.5821375995032831,-1.0798550849680786,0.1929685471172376,0.5221408236335615,-1.3351814553593704,-0.1233437797003926,-0.647875972989561,1.0841053764635316,0.4010818533201225,-0.9931619292762374,1.0915266618005457,0.831835867956314,1.4822266850579406,1.1762112224661734,-3.039330745481794,-2.655830921229822,2.2319393488517925,-0.5209294101314186,2.349494180386671,-0.42391415008515027,-0.16167954816703783,-0.7352412785698178,-3.0026983052930816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3833440999999995,1.0,0.0,1.0,1.0,3.800372063757651,2.1897464292525926,0.5287027390645692,0.9834162376635063,-0.021920542450021337,-0.009987612707659512,0.17975605945517606,0.664077398573152,-0.3610773472451213,0.04286735622416746,0.8101711511190636,-0.5113099413950065,-1.048607657715325,-0.1579720375365136,0.6054190131995887,-1.0582398444331178,0.1476482391869627,0.48434333295089543,-1.2852727838114026,-0.13271310740281564,-0.6094216812278981,1.078271422618423,0.3999774530099392,-1.0017607033709803,1.0485952903387048,0.7474117959277546,1.3516496364321444,1.4124915925005401,-2.6975380662367834,-2.5724582047075812,3.6851311720440503,-0.6255436419211392,2.2505954255275076,-0.25219934914327624,0.15401655493662872,-0.4868211926152392,-1.5548108701928929,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4000107999999996,1.0,0.0,1.0,1.0,3.812503302040945,2.18794738643771,0.5296533516562043,0.9850057208497098,-0.01409591344774979,-0.013570826440796118,0.17140848224965655,0.6127238083383514,-0.36623614236849705,0.02237421433014077,0.8979803044503033,-0.5578778037016562,-1.0475807455401007,-0.14739966881711233,0.6271926774943304,-1.032771937718621,0.1030504317401404,0.4363920453127618,-1.2123435039491572,-0.1441952761340067,-0.5728559754322824,1.075698714678799,0.4062157487524471,-1.0093893348181582,1.039699529140058,0.5999577740115728,1.2264568376269094,1.5126734133571438,-2.4835860459018533,-3.011427848893447,4.166328637312254,-0.724310359331438,2.0696738719885395,-0.1431993671297798,0.4074836274943043,-0.09390690006998208,0.06871131737449984,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4166775,1.0,0.0,1.0,1.0,3.823682657183229,2.185182561573074,0.5302911115183009,0.9864849707069232,-0.005344986384683445,-0.016833385442523104,0.16289711729939205,0.5442916115516067,-0.40440634224897853,0.013279349427217688,0.9970333923341768,-0.4829710530249864,-1.0434196556814563,-0.13797340507227623,0.6463009895509415,-1.0078172964763188,0.06486187208449788,0.3839622038925906,-1.1463948848124184,-0.1568568343345542,-0.5404324141833553,1.073498100834139,0.41356026775865784,-1.004890939633773,1.050885672165276,0.5550354294995251,1.0096803775889043,1.5245786258426837,-1.8110089767847701,-2.942861478034922,4.381934523230102,-0.7562145437416402,1.8454562356200377,-0.1504944037707331,0.4209917627768923,0.5950944005848499,0.9776770905582973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4333442,1.0,0.0,1.0,1.0,3.833987770265539,2.1810198603614332,0.5308827760420585,0.9877903665366611,0.003909796424845538,-0.018903829128928313,0.15458832592906055,0.5487832270958812,-0.44925469069189133,-0.008394918073281453,1.1519409757356267,-0.34015489364432977,-1.1153474518760667,-0.12889845083143286,0.6608487573926524,-0.9819525485519566,0.042683345113382946,0.33829646652083256,-1.066278727712519,-0.1694024780063643,-0.5113406445478654,1.0706822245201477,0.42024883557779436,-0.9895528151257031,1.0722888306704739,0.4874759033458377,0.9218179889923453,1.4595724842497488,-1.3980511458971088,-2.096112143970642,5.367673373995226,-0.8617247467195971,1.63690249116858,0.007157994152973224,0.2856277772835924,0.9430668640576978,1.281325717969923,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4500109,1.0,0.0,1.0,1.0,3.8456738608042977,2.176511322411109,0.5306886198389139,0.9891460506480451,0.01486284549064112,-0.01939372700567713,0.1448898535582315,0.6356653020148452,-0.4611808565233474,-0.016925046781329094,1.4033727836239602,-0.219428851735998,-1.2326123539254692,-0.12172417579568809,0.677028317305219,-0.9591647830298282,0.01826007401785119,0.3140916593527596,-0.9674720811676859,-0.1855810500068572,-0.48586888868423656,1.0737367011164378,0.42308121270996274,-0.9734553146273922,1.0935966148526546,0.2880349668290798,0.940685150321966,1.465244345684991,-1.8949351808880266,-0.8534420480839945,6.230147256082845,-1.1455449328808212,1.5783491963995089,0.10361423300485566,-0.2653575612281111,0.8370552131424065,0.9677069895682855,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4666776,1.0,0.0,1.0,1.0,3.858705508025105,2.1723803759510596,0.5308578705826589,0.9903153216988146,0.027982742217217648,-0.01884241497283829,0.13467551055989904,0.6957277097547101,-0.4758713708101655,0.008802537868620796,1.5018123649284862,-0.042026412484793496,-1.3223748506260673,-0.11929726606813242,0.6922049917823946,-0.9331109726795005,-0.020481287245229997,0.30984834135522954,-0.8586067371666071,-0.20758738547205385,-0.45872889944460205,1.0741360391945918,0.41140356584635324,-0.961650918883942,1.1045457948365494,0.19493416833953278,0.7951303090062264,1.5513918816397243,-2.003424365907654,0.552052087061702,5.0822216090279575,-1.3207379145207845,1.5492385006117115,-0.1223757702204517,-0.7892975891438133,0.9232890942814638,0.5911077990465115,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4833443,1.0,0.0,1.0,1.0,3.8722462781516493,2.167392971114668,0.5312230042022472,0.991394682286177,0.040181305973054846,-0.016078665153054415,0.12354563169892309,0.7163275077725042,-0.486946497308382,0.06367050530125701,1.4045006606258643,0.19642007614714324,-1.3787384897800015,-0.11522635718875911,0.7035327139474471,-0.9074516168823786,-0.048520871740695005,0.33249343239162216,-0.7980643553853134,-0.22960573520674432,-0.43422750204794613,1.0696575006173714,0.39677124045199635,-0.9426789499320705,1.1133002475613916,0.2669997430553502,0.5224097638081537,1.7001041139269595,-0.28577095580884565,1.8060806128449032,-0.12019676397835789,-1.2959277399718763,1.336732116043843,-0.42563751798374466,-0.8868141358609669,1.278350840159057,0.13771072553605004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.500011,1.0,0.0,0.0,1.0,3.8857924319143566,2.1623375169664634,0.5327418745737391,0.9922718095404731,0.0511713602106602,-0.011769054557557636,0.11242614126744328,0.7444508165772271,-0.47178802612245796,0.11148127874503526,1.081254281798478,0.3436198797550674,-1.4538365353497436,-0.1103972568329712,0.7096186854033173,-0.8764407222083276,-0.030007004823588573,0.37005114885543383,-0.8626133039790033,-0.2507850631996324,-0.4141710731276662,1.0599480935526324,0.3818430355300453,-0.9190391389885841,1.1091361615351327,0.46188896591050077,0.29967190417441514,1.8360814254181055,1.4643613455228335,1.8040221907823912,-3.1282241084480105,-1.1574646373778088,0.9704641310679478,-0.2863176175687584,-0.6930493894690517,1.466908396999066,-0.409408984616326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5166777,1.0,1.0,0.0,1.0,3.8999108461829595,2.15726609138834,0.5342282545466902,0.993284210820773,0.05770359561320161,-0.007066862931902531,0.1000341493479297,0.7834375127235342,-0.45462426820582413,0.10432283515324098,0.6740517356975716,0.33919066731106123,-1.5573733223553885,-0.09983002753247802,0.7135217973980545,-0.8462487802963468,0.0002912707341558063,0.3926276256858479,-0.9023387008818543,-0.26818796695031377,-0.4018786329814058,1.060113560943905,0.37366954793306867,-0.8937819055715418,1.0996532541135817,0.6014279533929382,0.44274459433496727,1.1842856454490485,1.6184975681379932,1.4264823943360136,-2.1071309056672622,-0.9806899161073886,0.3818392126237283,0.522386447195327,-0.30454135405775246,1.5507039674400591,-0.4969534266787092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5333444,0.0,1.0,0.0,1.0,3.9143970041807044,2.1523523348425653,0.5351481778602039,0.9942704176181367,0.061931401101725646,-0.003500267028071361,0.08705507646177502,0.8306226388585253,-0.43595944265471154,0.06179257409447923,0.4082073624860082,0.1657835586299794,-1.5525322609152585,-0.09034961829134304,0.7243768680641225,-0.8369644550743163,0.02394302201418241,0.4176006570987939,-0.9328511413099724,-0.2834747924492064,-0.40144307391759443,1.0773610099515731,0.3716916367586966,-0.8673489033603177,1.0925710141822806,0.46418330506504624,0.5950577733776556,0.14824824375889598,1.7123971612707853,1.7420556987420202,-2.084252292644339,-0.8385258029313493,-0.3297658405045966,1.648276687692784,-0.006183773573100022,1.6077700863468485,-0.14045197577067647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5500111,0.0,1.0,0.0,1.0,3.9297078280247253,2.1475919457510875,0.5349826215898347,0.9951440032323341,0.06429232698255406,-0.0021027044602828057,0.0745015983442319,0.8644220559976247,-0.4154366830979946,0.004353790073463693,0.17108729090829675,-0.043112579728328534,-1.519419407605266,-0.08435721975142281,0.7333570961811613,-0.841307162287834,0.057371290269659404,0.45069626511429517,-0.9718139162534851,-0.2961388829497456,-0.4128708496492817,1.1150562270854436,0.3734634217350471,-0.8401894621753078,1.0949715122244275,0.011047595948172785,0.08555081594510336,-0.22707529300662557,1.9555076469565482,2.1484605871028486,-2.283238383441182,-0.6777227454640588,-1.0647598118154449,2.5389826205092945,0.1500207860735886,1.576267179036307,0.3561574326880285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5666778,0.0,1.0,0.0,1.0,3.944948901812424,2.1430187655761035,0.5339210784606169,0.9959755874563133,0.0648549740763695,-0.002351948016672935,0.061813670568345414,0.8563420343242854,-0.3838740437802409,-0.0333509935158136,-0.04194725755716537,-0.1641910741235435,-1.4787584007127719,-0.08998136435656422,0.727228567632347,-0.8445336466462233,0.08912674061324381,0.489216153232928,-1.0089592396405707,-0.3060655958128581,-0.4369351386287634,1.1619939332340576,0.37669233962920196,-0.8148065589746288,1.1044429523490438,-1.000376540168612,-0.2021752446343355,-1.2187002950004724,1.865747080398763,2.37571616287927,-2.098506856343682,-0.8207482067568309,-2.080105531821436,3.28349385177804,0.22393968987811924,1.5345109241021822,0.614414047393861,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5833445,0.0,1.0,0.0,1.0,3.959609914763647,2.138651493820425,0.5325935370780437,0.9967142969220155,0.06381518553921058,-0.003253078581100598,0.04977599708286805,0.8540175025682466,-0.3379564172508796,-0.05706485379071493,-0.2662436596882225,-0.21349339451099975,-1.3564645995392202,-0.11770317111547922,0.7266179078816671,-0.8819305867012027,0.11956298399942353,0.529886962258015,-1.0417642846987316,-0.32349721122485375,-0.4822078393836984,1.2245062410443017,0.3809280929936304,-0.7890389957378401,1.115452021431826,-2.4024922457133835,0.4106381794338279,-3.4487387877317115,1.7904739489286825,2.463805341001119,-1.756694381328134,-1.0205742132913485,-3.1752900683545393,3.878832244606218,0.33958195190955076,1.5767786461130093,0.6861600546106111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6000112,0.0,1.0,0.0,1.0,3.9743972622275296,2.1349565429827666,0.5309704868798958,0.9973829572783881,0.06067638499582668,-0.004650005302000447,0.03903831816493514,0.8731875619544643,-0.2959226579109663,-0.08091425123331311,-0.5430573918011579,-0.20907913630176791,-1.2171199779036297,-0.1700645993798267,0.7409165343226866,-0.9594918361531996,0.14880932494246316,0.5713431621866547,-1.0675158361311339,-0.3400848042941839,-0.5427783525932526,1.2912885999764145,0.3880117606649838,-0.7622471656522855,1.1273149999134011,-3.627568074826004,0.6578008034725088,-5.315927450841172,1.796784987720868,2.4480208474659544,-1.4907118468412293,-0.7688953534205364,-3.9267949256696304,3.7153154156914554,0.5489038003598331,1.5953597965045696,0.6602324832044991,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6166779,0.0,1.0,0.0,1.0,3.989412198327545,2.1314676629741385,0.5291339124929774,0.9980387198431836,0.055019452036523156,-0.00582089975465155,0.029286357189422407,0.8834821966921231,-0.27366284025164783,-0.09123661829244456,-0.8307834379908094,-0.2098951490483736,-1.0895560058001332,-0.23862234878088434,0.7485446451841377,-1.0591285227910718,0.1794559367091183,0.6114878203749367,-1.091454778974229,-0.34912710759856186,-0.6131012653590144,1.3483503359217113,0.39922492293254486,-0.7358602294970347,1.1374598148874748,-4.573912948299259,-0.2449945725181999,-5.97208682793267,1.9114735226376744,2.373739260148855,-1.4166447165692053,-0.3753452702052611,-4.444742903175771,3.1522089873807797,0.8130929543859045,1.640738833550012,0.5725685795805207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6333446,0.0,1.0,0.0,1.0,4.004358852022605,2.127943028507737,0.5273862476073392,0.9986505090382966,0.04705879835484961,-0.007518954705998959,0.020642083593429384,0.8833285099663378,-0.2565218311936802,-0.08994722083614139,-1.0654206091835579,-0.26589008772592826,-0.9390866885287825,-0.3225286692506652,0.7327500322391084,-1.1585617952234104,0.21252523646195381,0.6504679624409005,-1.1147374211264218,-0.35259633832404397,-0.6909367456819718,1.396362443036373,0.4151149133507109,-0.7075557618180295,1.1464006574039904,-5.218708612908536,-2.2340716287209097,-4.976001429122736,2.001884700672751,2.3950692831385485,-1.243818494845097,-0.08221062773897228,-4.563753079605461,2.3634721666246277,1.0989628340065762,1.796734375663184,0.4812487710877295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6500113,0.0,1.0,0.0,1.0,4.01922590605657,2.1244379224474836,0.5258476367878213,0.9991597769698913,0.03748798877778157,-0.0098518801362656,0.013316577662995216,0.8865382270355138,-0.23911486162286838,-0.0896560582679631,-1.1665070966345694,-0.32317851535324893,-0.7988697830565855,-0.4125796504584097,0.6740754419553321,-1.2249955688285916,0.24618556019052337,0.6913236228175071,-1.1329154783902986,-0.3518674673372361,-0.7652266722627351,1.4271328990406766,0.43585709066361966,-0.6759689638593035,1.1535014726736506,-5.516446854051206,-4.423305565682555,-2.8072446916532003,1.935325815434129,2.465948806932153,-0.9792118134220105,0.056477388961291675,-4.5227126243459885,1.36084426188082,1.2615074201406098,1.9885651457580824,0.38889194846802905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.666678,0.0,1.0,0.0,1.0,4.034167809283165,2.1209869671497428,0.5244229708609526,0.9995084212439822,0.027831188207476088,-0.012650639169195177,0.006949975103065158,0.9123266540550306,-0.23365292402174445,-0.07570944349167794,-1.2526597401919926,-0.3913919165800573,-0.7001067462200912,-0.5064105988154957,0.5853062184959855,-1.2521368054281632,0.2770362259981458,0.7326664204018928,-1.147377880187943,-0.35071375492684165,-0.8416941346743464,1.4417240091553511,0.4571652447892259,-0.641270124388417,1.1593637482790546,-5.347630412728079,-5.756220724673139,-0.6361856652868325,1.8757512164435692,2.3694099713313195,-0.4839109333972028,0.1099948254900562,-4.394243860549509,0.2209304877668184,1.33687975558728,2.1404879972891613,0.26330705464439136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6833447,0.0,1.0,0.0,1.0,4.049800717792239,2.1172042297561893,0.5236775823232376,0.9997271363265116,0.016807276628211954,-0.016177153329471814,0.0012116331499812615,0.9488745893669444,-0.2578251528232338,-0.04809321822065697,-1.3027491477544213,-0.42520870660221116,-0.6667454231086501,-0.5908343540580399,0.4822010340515125,-1.2462018000838637,0.30871072578872344,0.7703041131558825,-1.149045875097601,-0.3482009658212459,-0.9117017605639761,1.434497263361603,0.4804198383085127,-0.604619221250465,1.162278392048934,-4.419088973035772,-6.073717692550706,0.8909132976389554,1.9570513505774787,2.242383532170895,-0.010516136835971886,0.14917431248449103,-3.7682344706482094,-1.1160491800454524,1.355366798683326,2.3739698867882586,-0.007789531542824977,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7000114,0.0,1.0,0.0,1.0,4.065857659727172,2.112511020386799,0.5235574814080866,0.9997776524139773,0.006314668856297694,-0.01957916256016317,-0.004628939865063933,0.9780070808160038,-0.2991658343894593,-0.008284583384993303,-1.2615555959072546,-0.40610141479673945,-0.6612798665120851,-0.6537138591892863,0.38284855716311583,-1.2224396361126448,0.34227140148748514,0.8074126876331581,-1.1477284187835513,-0.3457412678990711,-0.9673022015782514,1.404522295417224,0.5023442284364567,-0.5621376365641493,1.159104096708325,-2.9329981786263697,-5.394830347430828,2.157534702077548,1.9367746135089552,2.1092275525497106,0.3006287575208642,0.2807656481442729,-2.78968517186885,-2.502516116630027,1.329583022139225,2.7326976313798106,-0.4822193830000694,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7166781,0.0,1.0,0.0,1.0,4.082295619982275,2.106926871072033,0.5245483242217607,0.9996798029167521,-0.0040285249035452025,-0.022775712516623615,-0.010263018405201491,1.0189432484594514,-0.3387053801468584,0.03212631018573999,-1.189869563591834,-0.32560012150463113,-0.6649526294060266,-0.6886011555454641,0.30237299614846175,-1.174283832845632,0.37327000869066285,0.8406118388560431,-1.139024896471655,-0.33884209216539357,-1.0046914522719492,1.3510798926395278,0.5247393610186883,-0.5135291180246292,1.1462043804676394,-0.8627799427473111,-4.54566212539002,4.003681087335221,1.8309350942839633,1.9507771698581466,0.6614749217804622,0.421735483487764,-1.6054772140749638,-3.880799908810447,1.1631048162559057,2.986817266520735,-1.0291830678061495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7333448,0.0,1.0,0.0,1.0,4.099497693620046,2.1005419816390534,0.5262623334176979,0.9994721337779346,-0.013305977795449562,-0.02485395512057598,-0.016145763257084826,1.0716610341033503,-0.3753089745789312,0.05083981832670704,-1.1895056426672725,-0.1972771840050333,-0.6693029965875645,-0.6824732481328595,0.23132618327264012,-1.088983332956065,0.4033026933592902,0.8724387233469076,-1.1256792106258744,-0.3316833903337801,-1.0208182157458978,1.275162039736882,0.5411144665186413,-0.462576861892307,1.1247979258359155,0.12236309705141744,-3.4748795973974413,4.213467893982456,1.934769787698758,1.8267007791095933,0.8815050741858472,0.6319999420764018,-0.5643230703367367,-4.971697356616339,1.0066231159228836,3.168608723020434,-1.5401077843637252,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7500115,0.0,1.0,0.0,1.0,4.117459464666724,2.093344648529267,0.5283530851529548,0.999146697520297,-0.023612664160879343,-0.025882529269681934,-0.021872667969725486,1.1095916783686033,-0.3989654084757678,0.06070879463864898,-1.2947133419889334,-0.09989230820334838,-0.6499765381556657,-0.6845223774862104,0.18654344457657387,-1.0338346221483572,0.4377624639319406,0.9015019866064148,-1.1096413352317884,-0.31777538529618404,-1.0235022589047118,1.1853563159724927,0.5582935319909922,-0.40790861601669987,1.0948673516483296,0.02566126909377101,-2.115248439085001,3.5389293663935493,2.009679984347374,1.6318751967249887,1.0621170061431937,0.888914067607723,0.17479533640714445,-5.343648446437112,1.2554469567219444,3.180203401082321,-1.7206078154111943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.766678199999999,0.0,1.0,0.0,1.0,4.135699116061163,2.0857970432344057,0.5308446239708776,0.9986761822997613,-0.03461812318710025,-0.026295957292669415,-0.027495292037708764,1.1335009550034514,-0.41531326831136284,0.06577598194811578,-1.3021655776318668,-0.03236172839514194,-0.6637050031780869,-0.6816178707856492,0.16081776095324415,-0.9710187848143222,0.47029216014953495,0.9268346720294204,-1.0902752396133009,-0.3020528621525848,-1.014991692879304,1.097040068612415,0.5829627821058365,-0.3565698698426696,1.067444217281688,1.5091375722449483,-1.125238641307507,3.4299150202717246,2.000780360527901,1.5466940299251124,1.2768727666901931,0.7624641078741792,0.48731200008960496,-4.166518119156389,1.3928475148672508,2.989689158205466,-1.5674440060648192,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7833448999999995,0.0,1.0,1.0,1.0,4.15423706599119,2.077703537457342,0.5335309406624236,0.9980813669139429,-0.045007395965386804,-0.026214933546331583,-0.033476806699140126,1.1288472529870537,-0.41404952135411216,0.03375108689298907,-1.0965080191768577,-0.025716339004840348,-0.7103519700700749,-0.6342176911355406,0.14903541485041422,-0.9195038928116317,0.5044552760015614,0.9530585573835205,-1.0670788245505975,-0.2923598642027709,-1.007258493080925,1.0464721008994051,0.6047218753430682,-0.3082521114305738,1.0426191136165686,2.6370909976077876,0.07284678726148926,2.7202379524901,1.7944956178944107,1.5168575077968096,1.3824939059532706,0.5091798390226978,0.477283387101041,-1.654653330038742,1.1918963094533508,2.7005157208812345,-1.22929704114282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8000115999999995,0.0,1.0,1.0,0.0,4.1721810253765135,2.0697595401907583,0.5352617572820346,0.9974689734389404,-0.05256610602416471,-0.026665577403891152,-0.0397668015540605,1.0822373645093304,-0.38870820812567747,-0.032506763151544105,-0.7029742107454257,-0.0851965129167061,-0.7910946072656903,-0.5937146617259897,0.16324599205174628,-0.8803440050487887,0.5301088003790565,0.9773966900798146,-1.0441920172485981,-0.2850801669065056,-0.9990822148237101,1.0418848473009017,0.6226927385473688,-0.26655249911224704,1.026467567290458,2.4015004768235992,1.1729992788981352,2.3107188124360234,1.3883387179100293,1.472551209902172,1.2509496476684836,0.5494526679954145,0.8731678384921073,0.7863638034170664,0.8675022770939737,2.1253384322286233,-0.36594150018942445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8166782999999995,0.0,1.0,1.0,0.0,4.189135199702935,2.0619824769239057,0.5358560295833493,0.9969177786237156,-0.05640401013400512,-0.02788835314275784,-0.04685904463115312,1.048022859862201,-0.35138157540002735,-0.10331274373542594,-0.30934657455871517,-0.11829677915769125,-0.8795686525442663,-0.5541675151413888,0.1881354690136373,-0.8424797783491768,0.5507333258211435,1.0021436958836736,-1.025380419565005,-0.27404473863941253,-0.9781528402533322,1.0726842801042276,0.6336386757463525,-0.2374073553337242,1.0304210392141544,2.8834186947689227,1.1822689606860468,3.441949312564558,1.1631440439917438,1.5919922814160323,0.8527622145546913,0.6072668150949196,1.3677873635397828,2.0705803153091558,0.5685330134011081,1.227877236232458,1.090686670774315,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.833345,0.0,1.0,1.0,0.0,4.205949559648756,2.0546225047967615,0.53525903863169,0.9964391996461429,-0.057390029889071825,-0.029238471138044987,-0.05440972048628268,1.066267268934559,-0.3372878603205226,-0.19034114697235344,-0.06553697225675588,-0.057673477390907106,-0.8973825594983312,-0.49760051300577934,0.20265503622587855,-0.7656121318333493,0.5688803460550509,1.0304632055931677,-1.0157665532459608,-0.2648378992522206,-0.9534892115198931,1.110904329183228,0.6416438768962733,-0.22562317604601603,1.0628238623620465,2.431580237722249,2.1005944735489637,1.309219123967195,1.059947417763166,1.822205274758008,0.36313543607279475,0.46956647306271276,1.107843105776411,2.0282082696962953,0.35911345380489157,0.18814781649182932,2.5496720912898385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8500117,0.0,1.0,1.0,0.0,4.223479551864884,2.0463996695285758,0.533107025953318,0.9960163148568784,-0.05710080622392058,-0.02965456831105266,-0.06173819762341018,1.1000313023675419,-0.32149359103016095,-0.23005095993090474,0.17676130097001397,0.11075700567784681,-0.8075109472227583,-0.47311467844529803,0.25815542483823434,-0.7988390536023287,0.5860649770764103,1.0628839931892922,-1.013275880820216,-0.2583924915662239,-0.9412246628712447,1.140291357641322,0.6456091481474124,-0.23113574890747546,1.115410278901955,0.9322044957015637,3.404332190185651,-2.309755552500685,0.7386625481708312,1.7353170725784233,-0.4046076228097387,0.23648523304131147,1.0909378814389052,1.69260845935766,-0.1967538368514926,-1.110270673430012,3.205015727023382,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8666784,1.0,0.0,1.0,0.0,4.241317999864185,2.0387718847735727,0.5312584750211778,0.9958340439559417,-0.05393087152364717,-0.028371863051672462,-0.06783107976460974,1.1540016587973545,-0.2843578853993347,-0.20188598008107742,0.5523143149738825,0.34774745867256834,-0.6865268112825813,-0.46652696766876084,0.3161330028542129,-0.8426041375670756,0.5935024802382485,1.0883072237002533,-1.029253500980127,-0.25695504238516137,-0.9171245427427375,1.1673247240023805,0.6350854025509678,-0.262632272511728,1.1696579335972077,0.26551696405576625,3.3439347572264366,-2.86584999929872,-0.253659298555099,1.1543946924673034,-1.2177134907442775,-0.03775281258182154,1.6117937574890315,1.2370857792566705,-1.2029275950817246,-2.5036612322825977,3.003898128781258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8833451,1.0,0.0,1.0,0.0,4.260551939885843,2.031235645454397,0.5298641917891433,0.9958835347375427,-0.047202477826014826,-0.025148048697328517,-0.07318119275100038,1.2220009338798152,-0.2847457921983153,-0.20894354663236214,0.7858704551791874,0.5618848794021454,-0.617193318033345,-0.46426409527564155,0.36962013967476604,-0.8943675779689526,0.5776096502139537,1.1013638932311818,-1.0538664116925913,-0.2596509211691388,-0.8874980968353599,1.1815276327555964,0.6055114814495153,-0.3145912902276442,1.2155404167878723,-0.10879070759304714,3.4582666880509585,-3.488222829800835,-1.3218872818866567,0.8884949890111453,-3.362962253605483,-0.2050934696166675,1.8320223337604093,0.7441890870300916,-1.685056071613536,-3.8116538026322466,2.8107415668136846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9000118,1.0,0.0,1.0,0.0,4.280458351492224,2.0229032610759607,0.5275126600084957,0.995928317493941,-0.03993402212791659,-0.020494878586923917,-0.07817941060204,1.255356240453355,-0.3145275155789299,-0.2352978149430469,0.8374530336159378,0.6534870618724288,-0.5889161392400247,-0.4701533318412429,0.43140878967369073,-0.9588784644419588,0.5494394827162078,1.1179237825669575,-1.14135246696446,-0.2637915050452816,-0.8560570094825682,1.1921310765159894,0.5789167544934452,-0.3896876533763897,1.263349506540435,-0.29602980519165306,3.660670326819805,-3.765838548368413,-1.826857198564626,0.20575589613436213,-4.848746763518869,-0.2813623374267519,1.9444515193770138,0.5154325457041994,-1.5391596186889722,-5.045862328096353,3.0629328514239282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9166785,1.0,0.0,1.0,0.0,4.3004719757720276,2.0138162184962733,0.5248223997312329,0.9958936239842432,-0.032248646902606676,-0.015786707398142967,-0.0831065241121735,1.254708673012857,-0.34029149066852116,-0.2216392512915949,0.8004094466573778,0.6340864556644125,-0.6183486764588244,-0.474131775184017,0.4916427279467813,-1.0198957806371363,0.5167142884713196,1.108222436819387,-1.2154916270596712,-0.2690296845075197,-0.8226829165593581,1.1987087519745727,0.5542060582159083,-0.4827870375550112,1.3176383826975266,-0.11481939481833238,3.5810452529116032,-3.5103280681592652,-2.0078287197250493,-0.49664770508061085,-4.730625587976228,-0.25366355795149065,2.0897410904342855,0.23232195752181214,-1.4870877994434653,-5.708999093331726,3.1330380470953463,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9333452,1.0,0.0,1.0,0.0,4.319987015212453,2.004366018880437,0.5223818246867066,0.9956752376837894,-0.025612271811811083,-0.011401988673403854,-0.08857102940724457,1.2472767872074386,-0.3493104204150271,-0.17561102086070365,0.7491817525351168,0.5470919227095008,-0.6995673021182292,-0.4739806526564803,0.5507772035070944,-1.0758896340691388,0.48251172487012484,1.1013688259544234,-1.2990403019387067,-0.2722469738879018,-0.786398833818686,1.199875157254847,0.5293470620394763,-0.5799880037540535,1.367784316979483,0.1250144836241615,3.4837612946989935,-2.9751414579870867,-2.0069300914233192,-1.226722456584522,-5.091161791435923,-0.19645867158417757,2.3778511993749896,-0.11959153560545435,-1.5687476412450285,-5.717276627019151,2.416429620552239,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9500119,1.0,0.0,1.0,0.0,4.339430711075003,1.9947513765593459,0.5206808635752059,0.9952828247839667,-0.018885318961755552,-0.008107816150924431,-0.09481406401491019,1.2466095415477483,-0.36340522257067354,-0.12136724868035942,0.7545802866380338,0.4158427816985982,-0.8104213598419215,-0.4699646173955794,0.6077683366875007,-1.119067360912803,0.44981648496186954,1.0673316064850724,-1.3851973595183213,-0.2755783199909037,-0.7434210513901118,1.1947223594816219,0.5019143655912313,-0.6733633062740914,1.3981861978112426,0.26267175229869844,3.3332687258576357,-2.2722780287701365,-1.6779059522827948,-3.3370962574449674,-4.6815704068458635,-0.26901697403657265,2.7035457840001196,-0.46293263961048126,-1.5857268669022337,-5.569897443188573,0.9877655469595207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9666786,1.0,0.0,1.0,0.0,4.35854903868021,1.9844907573443007,0.5195958659066977,0.9946850045402803,-0.01233914373615411,-0.005943596618245675,-0.10204979634374976,1.2397563943914331,-0.3969270250093784,-0.07160830908299341,0.6704400907773984,0.24815448475146146,-0.9197578458270873,-0.4652249100684069,0.6618863832535973,-1.1516323865133453,0.4265814146003015,0.9901320615665073,-1.4550929609382626,-0.2812142242902525,-0.6962804607822964,1.184444038405655,0.47648939409427743,-0.7656516231868354,1.4007099010625035,0.4695015307429395,3.1237956120873283,-1.619753476133971,-1.607025337479763,-5.975114698927639,-2.9658848053098312,-0.37546381937377327,2.8815368450180974,-0.7000874690121008,-1.4718211962128938,-5.44405967110665,-0.2919560695062314,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9833453,1.0,0.0,1.0,0.0,4.377226547752177,1.9733549825888916,0.5191962466426265,0.9938848946078485,-0.007270537644815538,-0.005307539636287798,-0.11005355776034947,1.224545569362027,-0.43552704675674636,-0.008654780167783252,0.4632942281300482,0.06715804728873444,-1.129911626229473,-0.4543145350707127,0.7118950653434525,-1.1730592514341671,0.3962488665775216,0.8681607181798379,-1.484060384087636,-0.28809380566761744,-0.6473696311203856,1.171386063842054,0.4528535609293884,-0.8548323249149578,1.3884543093639636,0.9041877606168528,2.8591909397876676,-0.8576583320374411,-1.7439295883607484,-8.206989979574859,-0.27675097775417423,-0.4062797237625204,3.054389328079569,-0.9504356149959141,-1.427269043279387,-4.718521786577732,-1.2880305819831643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.000012,1.0,0.0,1.0,0.0,4.39520181752079,1.9613955562518628,0.5199962310132086,0.9926578337852341,-0.004452320193675014,-0.005785907794768335,-0.12073576578913976,1.2097665942891598,-0.419802059421434,0.04819724537670817,0.23812165724369447,-0.1273153209881639,-1.304404940694397,-0.4350852577686611,0.7571929385259155,-1.1802210547584822,0.36845031205963735,0.7165651817813468,-1.4643180119801336,-0.2947569088343181,-0.5944672795536889,1.1527627878767501,0.4289136641670283,-0.9229359973075456,1.3577754624610259,1.2950604636038083,2.581003491214013,-0.08435042272867294,-1.7830883159412692,-9.192507409037463,2.3575480035518837,-0.39067028054806835,3.3166221840372447,-1.1821492722516216,-1.1851118869295059,-3.5422533501132993,-2.47522813026138,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0166787,1.0,0.0,1.0,0.0,4.413002164066191,1.9501226003022651,0.5214133634303099,0.9912638611281398,-0.0034796936540026817,-0.007969348146514376,-0.1316067583504968,1.2021941954861246,-0.36145568873222217,0.0741665191180627,0.1261020719634222,-0.330557438221805,-1.3218057653159108,-0.4111457666132215,0.7979286871174857,-1.175870937815151,0.3368124705069249,0.5617431917114285,-1.4054752934660397,-0.3011161743972384,-0.5368153372109985,1.1319810092903817,0.4133497523576124,-0.9729076727356244,1.305946540006709,1.3843460386698474,2.348494867024443,0.6504463473509936,-2.142851476002409,-8.82531981733031,4.597308540199664,-0.4368080713049967,3.4452606051522117,-1.0741512330356793,-0.8759110140808178,-2.3618460196967064,-3.531454824361406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0333454,1.0,0.0,1.0,0.0,4.4307006850263155,1.9393334680165202,0.5231957619680512,0.9897169504250662,-0.0029341342473662435,-0.011595405892169347,-0.1425387507301834,1.1862686023550848,-0.3202017442031885,0.09625709678177001,0.05880292253795394,-0.44207994445238213,-1.3170390651643449,-0.3889402975232636,0.8354762573263881,-1.1585394664836925,0.29702178666945867,0.4223872661823486,-1.311074087486242,-0.3093172069983561,-0.4796250296979082,1.1169576751654786,0.3997165719702668,-1.0016643554205038,1.2400600662186574,1.3346084191504397,2.084173164442741,1.2836191815631126,-2.20995105321776,-7.255334550552654,6.033702688264422,-0.46389796445445725,3.4128592594565994,-0.8874600998028838,-0.6558717248754777,-1.1833170374042563,-4.246182465001741,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0500121,1.0,0.0,1.0,0.0,4.447843960938294,1.9287582913392571,0.525588395386669,0.988052999484953,-0.0033085750235946365,-0.015455460858102586,-0.15330183387606464,1.1534429316004542,-0.2736514368959835,0.12781944025573772,0.08213564217858785,-0.44866756295369004,-1.1983045441342055,-0.36665873033431223,0.8674012648771213,-1.1330835461884352,0.26314728806959603,0.3198982230040367,-1.2043514682770464,-0.31657947080558463,-0.4230531343718279,1.1023989467996123,0.39148731780364815,-1.0123516528702354,1.16440684142782,1.1632021384293425,1.737038259283258,1.7684457677837615,-1.8072209850087302,-5.4414362349753,6.9046312063955915,-0.48388600767935935,3.3921654271025004,-1.094248603687105,-0.48229778957933495,-0.15566987315251848,-4.6504392825271434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0666788,1.0,0.0,1.0,0.0,4.464433233372184,1.9190451456269204,0.5286839758385681,0.9865628006333431,-0.002425986283648008,-0.019272948461091247,-0.16222363716383068,1.1247295416109644,-0.21840320443024713,0.14346225452042455,0.2838101888735167,-0.3824206359192692,-1.0087416240898657,-0.35016681536214295,0.8933776484383806,-1.0995911563278493,0.23678096668776866,0.24100569558742296,-1.0809192536309753,-0.32544677284673523,-0.3665526226501297,1.0804826487593349,0.383639946831103,-1.006853361570246,1.085045113438467,0.7012271948348627,1.3910945023759325,2.0986292273869696,-1.344512658532984,-4.2245402364302205,7.248625280699764,-0.6785811770567752,3.2934365436805044,-1.4247847983374564,-0.4171574560582359,0.13479154089930462,-3.5468514453884645,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0833455,1.0,0.0,1.0,1.0,4.48082485490401,1.9099173059172867,0.5318114139953042,0.9852242323867827,0.000647449654592961,-0.022572743558133282,-0.16977415579256602,1.100167912506203,-0.17827034414874543,0.14442500942879494,0.5357272446751205,-0.2853977161652701,-0.8611451736215306,-0.3432844437580038,0.9137711743626192,-1.0631290987002544,0.21833010981765266,0.1790799334870136,-0.9627301423453689,-0.33919888861288894,-0.3132716966867082,1.0549060252027105,0.37758204145787655,-1.0078585925208225,1.046178223458108,0.23593359779534556,1.0407408462347525,2.281369385557912,-0.6011927904027137,-3.4571269455686386,5.6624977929860165,-0.9298429812258657,3.0340872230259412,-1.545021945883456,-0.2530195678011782,0.1965560251692914,-1.8164570939565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1000122,1.0,0.0,1.0,1.0,4.496751250814513,1.901206993070901,0.5350631818571744,0.9840144620928206,0.005886291417575967,-0.025486031927825045,-0.1761571802172654,1.0944114760378416,-0.15733088995460087,0.12928180654173177,0.7322674158130023,-0.2531281882891626,-0.7696650209497998,-0.3423023463733916,0.9280690793622621,-1.0235453580512932,0.21674116692815884,0.1257679002600053,-0.8921689496982552,-0.3564416008771295,-0.2654161796101168,1.0289818142284233,0.3752059443697592,-1.000301480960868,1.0244964225427775,-0.005087355147237685,0.92281202623409,2.3638925923570953,-0.732929023468934,-2.609347613363388,5.605311788892605,-1.0635181556973456,2.7734844609552467,-1.37450613604894,-0.22492757830566687,0.7673790743969795,-0.5359601986060688,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1166789,1.0,0.0,0.0,1.0,4.512952200487521,1.8923294703048419,0.5377611818658943,0.9827801790781566,0.012236505790109703,-0.028807723567986034,-0.18210849129017992,1.098964993733608,-0.13353848251095685,0.07945362156422031,0.836972764814701,-0.23815572006684377,-0.7098464057683095,-0.34345402260206875,0.9445316367578906,-0.9843325213621784,0.1938990935067533,0.09210150575172643,-0.7758860423614962,-0.37464956470401084,-0.22082202975590257,1.0090890623673368,0.37008444051918243,-0.9822792388823183,1.0283128477738925,-0.22032977798851724,1.0060973455380393,2.177968346943698,-1.6616972349495969,-0.08678945936720167,5.2141221072546005,-1.0807716896502535,2.4343994820540322,-0.8534040649528213,-0.06993478015228545,1.419737501168345,0.8756418059511946,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1333456,1.0,0.0,0.0,1.0,4.529141034223511,1.8838782022521505,0.5394636660169043,0.9815760069538467,0.01921340769153704,-0.031790242937657455,-0.18742670031611158,1.105158588306474,-0.11124925193437185,-0.021596023965394992,0.7801634386695944,-0.2306231341718053,-0.6464905301285936,-0.349646686994994,0.9616057246200198,-0.9509462679552801,0.16135114831668995,0.12287491249513463,-0.7183645318482947,-0.39246739591691726,-0.18426936791501694,1.000534955169725,0.372874780369031,-0.952976802939423,1.053684541117271,-0.3443882854040248,1.2160198167720988,1.7103048182518767,-0.623855804563445,2.3603224029039955,1.1072602797315265,-1.0838407704472641,1.6710666440906388,0.4201484753274812,0.20696725369299546,1.585423266077186,1.7133235334345136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1500123,1.0,0.0,0.0,1.0,4.545818415157501,1.8753033110976383,0.5388929841742629,0.9803994276814021,0.02462052427140568,-0.034805154259899954,-0.19235226336990424,1.1400199651570593,-0.10934595454038265,-0.16867862769692094,0.47981068277302985,-0.21061719817030866,-0.6592065521342279,-0.35493365507475527,0.9850657117182817,-0.9273222467334613,0.17310385843091816,0.17077907653668647,-0.7389772925530933,-0.4107776626416377,-0.16511969688177167,1.0230940395548178,0.37698336277343253,-0.929431690984861,1.0854237464432785,-0.2954940166247874,1.6248156897888921,1.0298424337034915,1.2652729970591212,3.577545655586134,-2.8450450968438012,-0.8781737751977517,0.4973620297868286,2.2819932376724172,0.3354026445726021,1.1026206597010693,2.018206145262998,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.166679,1.0,0.0,0.0,1.0,4.563306207687973,1.866305974353734,0.5358701758622137,0.9791548731011971,0.02676992692816131,-0.036479367742662965,-0.1980110128844737,1.1710080259823235,-0.10748822359233356,-0.25202443199007585,0.07033042815083856,-0.022669696605806415,-0.6584017944676102,-0.3594965072487547,1.0157663559340289,-0.9166181181756682,0.20352699923686046,0.24212667285104947,-0.8131995580794279,-0.421739913635094,-0.16769060043132067,1.0766015485583547,0.38405489088162736,-0.9162227074413434,1.1209582138397807,-0.1799784583219964,1.8581002205878168,-0.0143251873479318,1.0347449240398485,3.661574077875943,-3.4887351385396226,-0.1018557505406347,-0.7139800443861755,2.88019130921647,0.3992905540627487,0.9661146532637965,2.037985203403155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1833457,0.0,1.0,0.0,1.0,4.58099416148358,1.8571132960981749,0.5326616282471386,0.9781878547252655,0.026110527677459965,-0.035098783095961095,-0.20306362706691292,1.1854118580243973,-0.10054030432604644,-0.2581681291089251,-0.23558047698568518,0.25946214555561636,-0.6101506214731411,-0.3609329490173857,1.0470025096112237,-0.9277997539334049,0.20759542488190805,0.2928317899041564,-0.85526869642009,-0.41417286111670887,-0.1889190792933138,1.119100608541454,0.39029307452822776,-0.8972278048017576,1.1533567224223973,-0.0837649371712946,1.6841232518980933,-1.447755638970006,0.6556010901838922,3.0910190274463902,-2.766900842318835,0.8588259575690155,-2.1982055342392486,2.425568495501135,0.2675259693176626,1.2456359386255338,1.7084705847819608,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.200012399999999,0.0,1.0,0.0,1.0,4.598820897247935,1.8477824759359067,0.5293727844783294,0.9773366570062443,0.024177364608358905,-0.031179600022965055,-0.20798160124121867,1.193676416306218,-0.07387929388445291,-0.2539042987684509,-0.4126195319322891,0.45813685145757843,-0.6205136646436649,-0.36228867740546034,1.0719039099388488,-0.964876735991711,0.22538041261639621,0.34516084650053097,-0.9054297706167785,-0.393112324461063,-0.24096426478633123,1.1574539934462922,0.39297244102728074,-0.874701426444763,1.1779073472305517,-0.29205134155382595,1.111259267659593,-2.883208595423436,1.3604801685055743,3.3698079458962353,-3.5347492503270543,1.3652517049343285,-3.9820791462181493,2.435294614339539,0.21715223844359471,1.4819757990157596,1.2443320144949326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2166790999999995,0.0,1.0,0.0,1.0,4.616867301848822,1.8389210113594652,0.5261010026253367,0.9764319448880234,0.02130505052430096,-0.02595155492767014,-0.21319772189492356,1.202357918258596,-0.030531939761295313,-0.21524281759741976,-0.5248727425967938,0.4933571220768253,-0.6147969396419085,-0.370668013205936,1.084044559283828,-1.0239068993280924,0.25294485453077176,0.405158946087894,-0.9730939070809418,-0.3686643799354509,-0.32165531630586186,1.2002772580390797,0.3975314969531635,-0.8478285127028456,1.1948345391943627,-1.0268442791067627,0.4623526879916103,-4.4598883612574864,1.4430603733610112,3.4818366563507133,-3.7016684054798925,1.2834795543901965,-5.349496882014258,2.938421211350745,0.25118884934046704,1.7771326389701356,0.7559659345529974,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2333457999999995,0.0,1.0,0.0,1.0,4.635208367231367,1.8303463831612987,0.5238276732734479,0.9755541691217867,0.017654865967478374,-0.021062362563167264,-0.2180338177898749,1.2168843439935924,0.0059931896033579846,-0.17909517790404622,-0.7061110120224741,0.42091215681221594,-0.5991513229015647,-0.3965168884986377,1.0873156970287483,-1.1135399786928513,0.27348252126578815,0.46122230050133184,-1.028818964244002,-0.3503295870827528,-0.4192811841532653,1.255401563052731,0.40134541941788626,-0.8154635533369159,1.2031062621133806,-1.434403957093979,-0.010506921370167102,-5.5901667154085235,1.2830037376529337,3.4151262044191353,-3.199255058290657,1.2025984634550266,-5.917783003103668,3.373602982121212,0.34475426923390856,2.0124959039797736,0.407059755115639,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2500124999999995,0.0,1.0,0.0,1.0,4.653913714570627,1.821966546624311,0.5215035339500732,0.9746015641795536,0.011562170308079902,-0.01635415409437257,-0.22304853498822194,1.2340768201047907,0.034682926597291386,-0.1641870840914068,-0.9047895925675145,0.29235548532707234,-0.573348622790286,-0.41848157406933245,1.0836943278710276,-1.210246162519491,0.29571173131945205,0.5189967139102788,-1.0797359556409676,-0.32857768431371914,-0.5189151442615176,1.312730915683319,0.40902332891124504,-0.7807451817371263,1.2084032248355343,-1.8576418232690515,-0.548836541284453,-6.364730665264911,1.2545088216360605,3.5129496802965607,-2.7157409520531273,1.5118805805265938,-5.86542091445552,2.8567992216206672,0.4947890033419412,2.2634315606044098,0.2510507884327885,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2666792,0.0,1.0,0.0,1.0,4.672934144550966,1.8135704380454565,0.5194927814611863,0.9736788974202205,0.004197754448295111,-0.012829862711119114,-0.22752401675196696,1.2269653572036863,0.06497616904695974,-0.12014355320944439,-0.9761281691815116,0.1302660746293332,-0.46939468250283867,-0.4584384064503943,1.0690211090634971,-1.3256980918503927,0.3152995656209116,0.5783208573745292,-1.1193438436951697,-0.29993346693982764,-0.6147956056631769,1.3506283942267014,0.4178384191818845,-0.7400156837546649,1.211474638464526,-2.1281308969219896,-2.8659549773526694,-5.6680057512700825,1.1205920628326032,3.4021862745299756,-1.9844640060938763,1.6691422886751748,-5.867270970045197,1.6382829487627604,0.5476790943147203,2.473170163591971,0.020101259836508543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2833459,0.0,1.0,0.0,1.0,4.691631843226544,1.8057919405268748,0.5184742583551568,0.9729243345078421,-0.0036852593732985134,-0.010495088525193503,-0.23085604021266687,1.2083672499147555,0.09309072067339608,-0.06717626202334019,-1.0030104292321371,-0.036394032305774315,-0.31606317823908087,-0.4894194125087919,0.9881623042289401,-1.399180065428877,0.33306487478667635,0.6324031498736963,-1.1458848881416972,-0.2729394967483941,-0.7144912344144222,1.3673404565276075,0.42727933523367534,-0.6983060114060496,1.2090732681701686,-1.5648790998696251,-6.664151809229549,-2.6533300595321387,0.9749112885948886,3.1617965950431928,-1.2396751547747065,1.6132953694096963,-5.69584633459248,0.39867026108903836,0.5690873943470806,2.684626275940366,-0.25177549385357867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3000126,0.0,1.0,0.0,1.0,4.710347036063546,1.798225081304463,0.5181380145313815,0.9723991294782012,-0.012152604383396347,-0.009567303492485225,-0.2328104677642737,1.1996381761456345,0.1023758297588791,-0.021583994226200994,-0.9668416735641041,-0.1992400859780228,-0.21043689878947364,-0.5106011474379885,0.8468822711457249,-1.4141426040568013,0.34779667356816046,0.683714287995742,-1.160666431499337,-0.24615684707314647,-0.8046575298726819,1.3639174295076868,0.4368080369326135,-0.6505279622482343,1.2030821052177072,-1.1764803463934965,-9.240007366693948,0.3013961984704307,0.7484651369607912,3.009423559534073,-0.6235941142229937,1.465272086609543,-4.929328215573663,-0.8598158661889912,0.5560524424325103,3.0458910650003057,-0.5231387595874547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3166793,0.0,1.0,0.0,1.0,4.728832983909762,1.7907172817074097,0.5186599920977852,0.9718879843032402,-0.020096386011395934,-0.01001305403106493,-0.23437068926219548,1.1969714518195667,0.11318165358763987,0.03480206456715228,-0.8395576366331274,-0.37267879968339596,-0.08788463825827224,-0.5286355024872649,0.6801614426719841,-1.3891335053867828,0.3580137625830452,0.7327174691530693,-1.166671400188738,-0.22409699617660353,-0.8788025035554253,1.3386798703335834,0.4458144537182552,-0.5967761061799685,1.1916352746413361,-1.0178791461033208,-10.240641149762387,2.664413307214312,0.39972108447780613,2.6720889593844857,0.07885485757584201,1.0622482156746529,-4.055464722278556,-1.9924678105833986,0.5351372929136436,3.330981175503845,-0.8333797191095427,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.333346,0.0,1.0,0.0,1.0,4.747563463380758,1.7834705011912748,0.5203196619759347,0.9717210024819039,-0.027196803366594018,-0.01234165810962272,-0.23423558802476582,1.2188856553455096,0.08998030024490017,0.07535469956623075,-0.7572942696944185,-0.5046585302275898,0.051316883106049795,-0.5445305201667089,0.5055268834442354,-1.3253286495221037,0.36112073636549297,0.7727840981144888,-1.1580379309898183,-0.210748502400777,-0.9398399576462819,1.2975017029903861,0.45464598237222115,-0.5394950343326944,1.1753027256887412,-0.3025556162873507,-10.100207296618242,4.423248090722206,0.32375622522653347,2.518468593692238,0.6998812450534022,0.6386434955493634,-3.257478863432155,-2.827832257564195,0.5544286971446971,3.531052489302191,-1.1340698583834856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3500127,0.0,1.0,0.0,1.0,4.76633096022285,1.775062087656216,0.5225183205064758,0.9716401998612068,-0.03434301881402685,-0.015201885705524725,-0.23346259174310965,1.2556818431584182,0.03798945765895201,0.09198311313337462,-0.6025524324747071,-0.5605149988844388,0.10580342847366479,-0.5387207098672177,0.34348719277088957,-1.2416916074795032,0.3688056583410113,0.8166665901740502,-1.1433419786948749,-0.20280883708205838,-0.9873853495017547,1.244418606559293,0.4642954472516582,-0.4790741211330628,1.153832870423896,0.5943284512989836,-8.765816375277492,5.203165359470881,0.30287867981653194,2.4847384489401345,1.110545715051426,0.19695825587580362,-2.330906042445025,-3.4331716156566965,0.5058654826931528,3.675963934556932,-1.2255321078956862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3666794,0.0,1.0,0.0,1.0,4.785371961580755,1.7658764524520543,0.5252092826546353,0.9716591132876569,-0.03916295548492825,-0.01900937436685294,-0.23234344012455116,1.268278183506283,-0.009887071180954665,0.10668764638529109,-0.4092093043975309,-0.543420351746585,0.1352958718059106,-0.5247195321681793,0.21333241988056062,-1.151889457328717,0.37121671255128935,0.8556088787283899,-1.1210196664517231,-0.2041832140743665,-1.017536981121519,1.1830624202570552,0.4715081988530251,-0.4169626581165344,1.134451573723411,1.1616169451392029,-6.058184507604931,5.133181267558016,0.17060411873608158,2.174975579397574,1.4700818926575603,-0.16934065171462495,-1.2994874391564086,-3.930480444864678,0.6887010406382521,3.6769398786364715,-1.2059710238019712,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3833461,0.0,1.0,0.0,1.0,4.803796066265945,1.756045770760337,0.5284143651011456,0.9717302249821425,-0.043118499193495356,-0.022327519810821417,-0.23104684967026232,1.262211133952401,-0.057124522674162015,0.1035068760603396,-0.3186518070340264,-0.4452357004950921,0.08384718758070586,-0.5000000675881145,0.14154730530509135,-1.0705852230154849,0.3744924736724886,0.8891659211523413,-1.0943391509341633,-0.20845353676192266,-1.030701684106131,1.1134023296984408,0.48725219451966933,-0.35650921338252184,1.1136337558990954,1.79262976770655,-3.659399155955084,5.355297541955421,0.24271628544035412,1.8951988515715528,1.6517242981021314,-0.3675229864660246,-0.42097126934775997,-4.049392718085278,0.8993666084744677,3.543637505377042,-1.262013620658348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4000128,0.0,1.0,0.0,1.0,4.821972121352293,1.7456960006843378,0.5314471743757178,0.971593678023452,-0.04606705789699398,-0.02493589991832553,-0.23078507728369083,1.2582963487060517,-0.10176172866093414,0.07788726871661637,-0.31648066790456897,-0.3306457940292683,-0.019602968833838136,-0.46496508706930983,0.09135220405544743,-0.9733791822437002,0.37930727158038685,0.9187823001273651,-1.0659620797333655,-0.21643400479143307,-1.0315693848311955,1.0480823930280314,0.5014871457599479,-0.2988411716947993,1.0923843689005581,0.9015563289207414,-2.5928567853131423,4.918434064574426,0.4268432634728637,1.7295519459911326,1.7078908065614318,-0.47380759633134156,0.24500542472171397,-3.5536360009186545,0.8467016493377783,3.3402701694456516,-1.3579461878338293,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4166795,0.0,1.0,1.0,0.0,4.839619663655013,1.7345782571416009,0.5341851856060372,0.9712739331662453,-0.04950531139015541,-0.026481800590990947,-0.23124637323295436,1.2460052583533974,-0.12770802219385596,0.07114733180643451,-0.31271759692215384,-0.21466838459078558,-0.09165566785186383,-0.4699481298536679,0.05511857293753425,-0.9066370929673997,0.38872061091113497,0.9468177679888421,-1.0374093435227285,-0.2242471548934738,-1.0225348202817122,0.9949475594254189,0.5154756392777052,-0.24516665171632215,1.0683687924415552,1.1490680435044904,-2.109633644094764,5.155312451547724,0.5377486366685476,1.5224316759405716,1.708497690367749,-0.4539638290377271,0.4913925170681136,-2.2730779937190135,0.6446721646061792,3.092058958835468,-1.5141479551267272,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4333462,0.0,1.0,1.0,0.0,4.857014340503661,1.723624029605791,0.5372485682597347,0.9708908128314945,-0.05191517217356117,-0.027283742360249278,-0.23223144029267245,1.2433193720002593,-0.11644183620102261,0.05714007242958538,-0.24934246122737574,-0.1399150827869447,-0.16495846603039915,-0.42666274234795726,0.021030941943379036,-0.8015350901712793,0.3972322619859142,0.9695301241541625,-1.0090120428212612,-0.23156616269027924,-1.0151896015027573,0.972312975032198,0.5229762608916315,-0.1957723335963531,1.0419126694531369,2.9343500266851357,-0.8191166871301544,4.846873639313751,0.48129298220303196,1.3462876794769822,1.6816909346539592,-0.2683462054901393,0.6004196923391457,-0.528042556231584,0.3396080818842313,2.815747266469101,-1.3830823449618042,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4500129,0.0,1.0,1.0,0.0,4.874715480639382,1.7127810860276593,0.5396138406498038,0.9703558901339224,-0.0540058413925657,-0.027925522795447747,-0.23390806047352258,1.226298897812796,-0.07492063450499459,-0.008601855706256267,-0.23794120880190162,-0.13297187762703908,-0.21096436575343255,-0.3721362666741616,0.02781462875874996,-0.7450743151986987,0.4047637424041015,0.9916941137239201,-0.9813528669215342,-0.2331920462995588,-1.0025207905090945,0.977346105681529,0.5267959313143851,-0.15130822178420103,1.0222659554040054,2.4953450339613306,1.1676344037393898,2.909022063626348,0.4252675772374848,1.3875542936549312,1.4977890617456833,-0.1092843292665587,0.9520545212634602,1.4173790106228406,0.1704836541154881,2.3212552482170508,-0.6682079889890845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4666796,0.0,1.0,1.0,0.0,4.892221415376482,1.7029481049519712,0.5404411525336968,0.9697919909580592,-0.056183672271158606,-0.02869647619209829,-0.2356340414666078,1.2070085938035922,-0.01397021570349144,-0.1313467734638491,-0.2788007414520912,-0.10918553353565005,-0.1882252865165099,-0.34348440819291065,0.05995216657698561,-0.7045674941155968,0.4114078762450022,1.0157820264462798,-0.9590856409104677,-0.23520898095145315,-0.9834543873236739,1.0195590365448934,0.5286590607277247,-0.11839700390543487,1.0196390252729681,1.8168794191219961,2.423071756575987,1.9788455356195194,0.4913730482603348,1.6619384944600937,0.9135190800380828,-0.04231269128358219,1.018536243164585,2.8122395395586586,0.30273480440234046,1.244494963892094,1.0172500837312257,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4833463,0.0,1.0,1.0,0.0,4.910328527445045,1.6935753900787076,0.5386195732388679,0.969302787084455,-0.05884995265834808,-0.028769919486350833,-0.23698329425334352,1.234536735455407,0.013895433760125808,-0.2579832797347603,-0.2370048233810674,0.02121210559288636,-0.11821302713786708,-0.31157349824480046,0.10858384884939996,-0.679112665421679,0.42114287677098255,1.0470921743351562,-0.9509021700189928,-0.23460247216319097,-0.9685695145011921,1.0710876111494536,0.53688711164345,-0.1098249733548003,1.0561743593450519,0.6869875158230475,3.9912988867597865,-1.5438758706221831,0.5338172031083573,2.0297394222131104,0.07305296544567776,0.093139152980848,0.735904396627332,2.8488391721024913,0.3233564234104067,-0.32985051776852814,2.8632069672482525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.500013,1.0,0.0,1.0,0.0,4.929136516262861,1.6834914375363015,0.5353119498799365,0.9691050251812222,-0.0598703995546393,-0.02753420402715679,-0.23768225224921927,1.2607002583596056,0.008449911115928743,-0.2600337786823222,0.02880059987457012,0.3048887059737334,-0.0503507871391356,-0.3205847785329747,0.19299572888890426,-0.7560301260613943,0.4292018186030943,1.0834401425026783,-0.9566505371920807,-0.23210433630948135,-0.9589241917091363,1.1145205322042546,0.5394376297318332,-0.12939204315442032,1.115079448395041,-0.4514563452537348,4.259057270691375,-3.9990234947077874,0.17714339392174078,1.9784871552306815,-0.6168596641394715,0.10077674132962247,0.9933147700219522,2.1834072687998365,-0.577002770671242,-2.069096784591125,3.1818637302025015,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5166797,1.0,0.0,1.0,0.0,4.947886761024689,1.6734832116694973,0.5334367117234583,0.9692621927674248,-0.05715128172335735,-0.024011874862058278,-0.2380923403527923,1.3029726360646845,0.0015271202065095801,-0.2033414115818483,0.4565929224537757,0.6179279941910807,0.010162940109569798,-0.3266220731836813,0.2505527084762639,-0.8124137151801716,0.4270476683779335,1.1130418780753226,-0.9714641999476195,-0.23124324073375413,-0.9354589559461424,1.143867999003266,0.5176536474875573,-0.1787950041142901,1.162236695809384,-0.4573352426676132,3.4855146346243946,-3.5504567620800107,-0.5021939238694707,1.3403432608739752,-1.5895115013866432,-0.2145236253165374,1.5207705617130984,1.3381429141966208,-1.5402914127800371,-3.6358612579764857,2.4904446447331434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5333464,1.0,0.0,1.0,0.0,4.967749414685513,1.6627808280768375,0.531784601718139,0.9697992110169128,-0.05004232118565043,-0.01935689308049397,-0.23792975243040954,1.3671349812837836,-0.03200985569309567,-0.204974211469559,0.7908561252047681,0.7755932854451708,0.029995631664173055,-0.3358293171109113,0.30917978241069305,-0.8743789214945121,0.4124619876611837,1.1281183405546948,-1.0096343598724022,-0.23925513812160762,-0.908231738267329,1.1591253852203363,0.4880944799530711,-0.2505876608110537,1.1980944359157888,-0.9758461339034585,3.8193273396000746,-4.1085251900599555,-0.8501276370616836,0.3905651191860392,-3.762084101257463,-0.5645075344937491,1.7145254298313852,0.8009004124620627,-1.6945093004670613,-5.123118942780378,2.5248660143181696,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5500131,1.0,0.0,1.0,0.0,4.987863585089619,1.6508739451991155,0.5295334495133791,0.9702763006478597,-0.04130317808385285,-0.014584488307494065,-0.238002606250617,1.402832123076843,-0.09426859887274897,-0.21891340569064707,0.910709217461233,0.7851486532798724,-0.05188410572306568,-0.35915034270353885,0.377863874418089,-0.9493648287505161,0.3987100238007016,1.1260607414191985,-1.096867254128475,-0.25006019618404807,-0.8783079939834009,1.170564732812029,0.46116989117136853,-0.34956597708156556,1.2463990646110572,-1.0830259620609237,4.056542704347649,-4.283840364385856,-0.39509626275963416,-0.5588453858410174,-5.254229282495809,-0.617333276905576,1.919968932464627,0.584563579831847,-1.207770286748029,-5.9873184125494525,3.094363269804821,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5666798,1.0,0.0,1.0,0.0,5.0078010745848704,1.6378291026606022,0.5269883002828375,0.9704081119238945,-0.03219321335319909,-0.01029899836227799,-0.23909333733718205,1.415884641480226,-0.1538124324379897,-0.21650412635573757,0.872473759962551,0.6941623439940885,-0.17489865975973418,-0.3719302547146729,0.444398142991795,-1.0171738858967316,0.3992920858961117,1.1094901237703019,-1.184775686237548,-0.25983295517401195,-0.8442326458539126,1.1786108768523031,0.44783538987678434,-0.45016534038392964,1.3012400845335008,-0.608213400207327,4.017615747711225,-3.8606970096326436,0.25073610462708956,-0.7578525771746496,-5.806788342700088,-0.5061802238193037,2.174503435659937,0.411736953690795,-0.8397630715530076,-6.046743655661934,3.064077582108299,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5833465,1.0,0.0,1.0,0.0,5.027304414776769,1.623987738686541,0.5242981539371863,0.970178816406735,-0.024401659557804815,-0.006918367927041804,-0.24105965940338908,1.4149566956726907,-0.20267215823732487,-0.18172868714346663,0.857799702516689,0.545994814998541,-0.33109266639666773,-0.37942416325800976,0.5117846671828463,-1.0780549864514049,0.4070679106706782,1.100798938323205,-1.290427252671034,-0.26693290405670644,-0.8058244011611739,1.1842893253841857,0.4331777328020635,-0.5511245020532071,1.348535188286506,-0.28585180070266086,3.9507344503097146,-3.145880130481141,0.6259754264738072,-0.9847927804554351,-6.653946203222483,-0.4629491270170801,2.5496591689399004,0.12738798921160666,-1.0498043345906987,-6.184915422163523,2.2187777695428097,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6000132,1.0,0.0,1.0,0.0,5.046328170126877,1.6095142516860965,0.5224238256316013,0.9694818560535131,-0.01609959152411484,-0.005039824435245187,-0.24458195784941678,1.4171475714640067,-0.24708386534474558,-0.11486065785322874,0.9278074177000342,0.3722773024818167,-0.4947182480471709,-0.38145866712821497,0.5760895547177488,-1.1220367666381117,0.4201579751769337,1.0766636321022687,-1.4065743366080443,-0.2752646236045231,-0.7592438369119713,1.1828571516518893,0.41284184207013874,-0.6563296001170752,1.375199491436779,-0.08134918276055318,3.714930403214053,-2.183784517969511,0.8860436164728281,-2.947512637201524,-6.152787187458058,-0.618783688102277,2.882790439637666,-0.2785508631312979,-1.2406191093640895,-6.365476093842626,1.0404169943667716,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.616679899999999,1.0,0.0,1.0,0.0,5.064988787062036,1.5942178461724261,0.5215420690730304,0.9684370683602121,-0.007859052253932429,-0.00480908912829697,-0.24908784110290053,1.411655555968668,-0.26847771033501433,-0.05313657268328757,0.9383487896872279,0.17058028335368897,-0.654108185543791,-0.3821358081066404,0.6356159282853416,-1.1508479493026897,0.4366027569560136,1.0025483205823118,-1.4955205691054485,-0.2875590682456949,-0.7097311943205558,1.175004278043085,0.39182367978198657,-0.7633074628797009,1.3832158241265313,0.007716289143653005,3.4738498798576227,-1.4233499737396398,1.0527458802239325,-6.34429718766678,-3.6225434431303882,-0.7441965942465819,3.154711428466324,-0.6179467563254575,-1.1324197871441977,-5.850418958835753,-0.33019116007021215,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.633346599999999,1.0,0.0,1.0,0.0,5.083233499906973,1.5789470412106097,0.52139022054788,0.9668947933407042,-0.00020174679551459093,-0.006251974706734282,-0.25509866859929703,1.3843317938816457,-0.2784307612481557,-0.005388592726575202,0.8126572923476572,-0.017044462956067763,-0.8835956264488875,-0.3812014569756739,0.6918847823029949,-1.1694818606527646,0.45524957470079014,0.8651866362268968,-1.5273260262152868,-0.3000712263591821,-0.6540865789823319,1.1622588852445903,0.37509444033734635,-0.8513439554395309,1.3641930974216947,0.28374230533892236,3.236794217081739,-0.7170359334711006,1.238788729459747,-9.016222148507586,-0.7770142526079822,-0.7692085030185986,3.4406671700351144,-0.8954321660726741,-0.8319778830218731,-4.835634866673415,-1.6179854795760238,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6500132999999995,1.0,0.0,1.0,0.0,5.100547654248074,1.5633808058461671,0.5218991164328377,0.964675727867049,0.005254448806699397,-0.008510954852022825,-0.2632502506730505,1.3480086431028098,-0.2636538622514075,0.03367237273315299,0.5837187467788958,-0.1941883513007945,-1.0451596605186466,-0.37267771234585595,0.7435092846410141,-1.1747491948874553,0.4778957971905871,0.702006981217249,-1.5214210959933314,-0.31319940296021503,-0.5950420592749073,1.145156479478518,0.36409102821606526,-0.9244956141444725,1.329282866941632,0.6046360473523066,2.9431423981065388,0.061285347893704795,0.9314370437901628,-9.879297684394357,1.7003053566504576,-0.7146441685438516,3.6337981896796934,-1.1314187844628916,-0.42640963798036535,-3.840794954914031,-2.63225627130984,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6666799999999995,1.0,0.0,1.0,0.0,5.117448388290767,1.5485448410444296,0.522997466258527,0.9622303546313412,0.008471592351952958,-0.01182201987155804,-0.27184778203108834,1.3150654021765804,-0.2128235246947472,0.06367237498236623,0.42829413401641403,-0.35109988950833204,-1.0518488019335552,-0.36104688175486055,0.7899897251160394,-1.1674390116372846,0.48629753825626515,0.535876054793906,-1.4706490676399144,-0.3238927462869217,-0.5329597304064628,1.124544850334575,0.36088075731069164,-0.9793707099896622,1.2764510462276153,0.6953985834534115,2.6492564433289485,0.753063901423083,-0.1891212172635038,-9.462074160483011,4.3259495991534855,-0.7729548549027164,3.624509898752953,-1.0479429753860476,-0.05101421915181776,-2.730753626738873,-3.558683345752909,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6833466999999995,1.0,0.0,1.0,0.0,5.134123983354003,1.5343734321684352,0.5246547787791476,0.9597815932920809,0.01073128001011974,-0.015926077905603186,-0.2800901512899083,1.2991276950604873,-0.16154193860463784,0.09546613251737127,0.374298900067174,-0.40400358064234393,-0.9648911548093193,-0.34949771320417,0.8318180093690752,-1.1496470146357591,0.47159174400705584,0.38660387839620464,-1.3772224876249086,-0.33896461632062924,-0.4742248210158156,1.1102249771027848,0.36239055084339006,-1.01552091708601,1.2106598515043119,0.578131694072925,2.287966662402819,1.3953607125784617,-1.4907075009777673,-7.610651730478365,6.2892115068781616,-0.8183410024950127,3.5420967713569764,-1.0006490080120802,0.07703439173667596,-1.4817158911550043,-4.244084055709456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7000134,1.0,0.0,1.0,0.0,5.150926586440549,1.5206716347077478,0.5270819076968091,0.9575613446625705,0.012826175448180198,-0.019860446250234084,-0.28725828640114826,1.2852623880859861,-0.12081000047523793,0.12129818834139383,0.39433685339100905,-0.32565038090483533,-0.8249714777238594,-0.3417757867436501,0.8662554330605775,-1.1209268948606217,0.43660718884317284,0.2821871564011785,-1.261008264796542,-0.351170834259489,-0.4148896018881122,1.091189816690905,0.36344857550420695,-1.0287613384758885,1.1349812947650297,0.3471056918293883,1.871486094961109,1.8273514608239148,-2.0067217442902443,-5.705801807752239,6.8384677450125295,-0.7940973120486368,3.4782407906018955,-1.3266240393412647,0.048139251259955315,-0.2403004054997841,-4.591385451640047,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7166801,1.0,0.0,1.0,0.0,5.167464982751188,1.5073683660852664,0.5298624852814128,0.9556507153179493,0.015740833989584722,-0.02284378802887991,-0.29319293614631287,1.247205835751564,-0.081284443629279,0.14074232266611886,0.5148501621873681,-0.18266601293401027,-0.6525809518712989,-0.33792750033614427,0.8942010039668519,-1.0887351774515313,0.4047008854159314,0.19641010441767615,-1.149273106893308,-0.36543457966207127,-0.35828322944636637,1.0660040873498067,0.36399519576133865,-1.0235309466226965,1.0576133636906135,0.07465640963369276,1.5060733527361359,1.96592315773753,-1.4006985321537475,-4.421648714139792,5.482792601701098,-0.8768701337678707,3.2311271790482317,-1.5688724214168903,-0.06495083958288764,0.3730097270839359,-3.823140317700997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7333468,1.0,0.0,0.0,1.0,5.183544767906326,1.4950240946149866,0.5330797238926116,0.9541738509657265,0.02038164505512375,-0.025130242573423122,-0.29749843963672035,1.2059256331469737,-0.042680417687349204,0.15394208089185177,0.7902849193926532,-0.1164941351965591,-0.48403603675693607,-0.3392872347787664,0.9164579785566722,-1.0553959918744935,0.3899171443914791,0.13479857115327112,-1.0782481458869986,-0.3803998971764269,-0.30718514717802586,1.0388939647188473,0.3612835431880547,-1.0163276560391088,1.0075430292989753,-0.23748571589862083,1.1992438030952726,2.146092943361231,-1.9378983373635028,-3.354962860747992,5.951732390171154,-0.995895948728387,2.9721083755857407,-1.6199334967215386,-0.4147893212959235,0.5427165234714258,-2.1223193059596746,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7500135,1.0,0.0,0.0,1.0,5.199381848575443,1.4832132530979294,0.5363468345924454,0.9529185643191912,0.027925744826388058,-0.028468879611824656,-0.300592557202254,1.20063786203287,-0.03172160788555556,0.1147309604026934,1.1661811726276137,-0.20250026635248047,-0.40521357416014137,-0.34584370669847936,0.9341758773529478,-1.017198602933294,0.3401041449772588,0.08457778539521903,-0.9508816304387768,-0.3986311776794141,-0.25921275211961664,1.012006196130189,0.3501688573988531,-1.005440359659214,0.9868692453373373,-0.7411669723311791,1.1272508509654822,2.434453727764663,-4.681194199371894,-1.435854786413103,7.092880329962841,-1.2807031909547157,2.7064186872413427,-1.1940652524591895,-0.713025622785498,0.9771826217775187,0.0020953858484556217,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7666802,1.0,0.0,0.0,1.0,5.215393128573606,1.471030271511012,0.5383170992247989,0.9514716391773366,0.03807163044210469,-0.034008864909750164,-0.3034726806554792,1.2064256463654615,-0.04122964770945359,-0.003658275400830302,1.2814910838385707,-0.34359623301448305,-0.38873365044011626,-0.3639928499342705,0.954033082072245,-0.9742473719854229,0.23387702566613605,0.0869366492158486,-0.8418183286962152,-0.42309008892179684,-0.2169710105087353,0.9990917100325242,0.3375159748934966,-0.98375483683435,1.0076128756336162,-1.0234801430478764,1.3773792181849172,2.0779100027321955,-4.948683917367026,0.7433104023654233,5.718894628409409,-1.514433882432264,2.0544004357482577,0.17879392460477553,-0.3326316315776725,1.413065459573413,1.9606740286714963,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7833469,1.0,0.0,0.0,1.0,5.231316581549694,1.4587748419829336,0.5377708892814926,0.9499505328137678,0.04672769516094753,-0.04014856760031421,-0.30626557141054433,1.2337721855743429,-0.06532177562495245,-0.1625495233949478,0.9327623793644919,-0.34567665162154043,-0.3369776219596776,-0.37995977969875144,0.9800886097843929,-0.9479347976482206,0.1751476844860968,0.10935484836142663,-0.7602514282321546,-0.4491124080560817,-0.19073260063464567,1.0179660055366098,0.33908111417082193,-0.9583380834690697,1.0522251770046558,-0.8083149280293912,1.7975663362793706,1.2029280173793062,-2.3473341761591953,2.071547429632022,2.521205889351423,-1.2315351635987193,0.9528778953193552,2.1238909247429727,0.029995155036507272,1.1336778810490933,2.6870320822067977,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8000136,1.0,0.0,0.0,1.0,5.247980863043533,1.4455342698953662,0.534652946037584,0.9488309229624637,0.051305346648600814,-0.04397524508870576,-0.3084701263572448,1.2655221042051492,-0.07090348373767275,-0.2540652346015103,0.489914256694278,-0.12459144550959486,-0.3224339076944397,-0.3909367347562454,1.0139520797859798,-0.9341496912109115,0.15563239663855113,0.15598836830674465,-0.7577779643041085,-0.4641413431440984,-0.1852083504728971,1.0698882157833516,0.3385158153943905,-0.9459654985541882,1.0971807908426483,-0.558987958081595,2.0783204007368994,0.24638954821561532,0.14448661453274242,3.5066233731429897,-2.0574438207503034,-0.3472387617129528,-0.13233673947582905,2.9102668248033567,-0.00739399530336882,0.9014282191946568,2.5572112107898133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8166803,0.0,0.0,0.0,1.0,5.264911567320179,1.432584610994476,0.5312701895896395,0.947797394332794,0.05408144423850899,-0.044356221563589544,-0.3111074127912177,1.269829709023476,-0.05113420219892295,-0.24758902301573946,0.05761703622687152,0.21756658240173032,-0.33503866667402993,-0.3985927489006685,1.0493660950303163,-0.9397217962817302,0.17996391460296252,0.22624252790775115,-0.8288330260867528,-0.46068705659576425,-0.19514383410628927,1.11497509371451,0.3388346471677766,-0.9282904160673665,1.137465721178397,-0.23729735498259932,1.8689373413634485,-0.8879822001800394,0.8146628137322692,3.8002026695324247,-3.670369357984864,0.9191124898183316,-1.4176090374105033,2.2285303082743786,0.051797446654480626,1.245419464512107,2.0195471056439076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.833347,0.0,1.0,0.0,1.0,5.281923055453233,1.4196228342146726,0.5283935713566051,0.9472031690551977,0.05360295144345882,-0.04052682531534245,-0.31351308833635705,1.2788162338768483,-0.02029797140927858,-0.2126926098955337,-0.3334473598145251,0.49130324914840595,-0.3149894215282912,-0.3988466624088224,1.0762501157605842,-0.9637491570823928,0.18278787807381436,0.28266204397133676,-0.8801238542615611,-0.433504198875988,-0.23246207956051637,1.1441727079611848,0.340242400402703,-0.9044514333758203,1.164499162333919,-0.08898078280205546,1.1580169881627438,-1.8928923610526829,0.4024564251051577,3.4295149074157605,-3.217082817799918,1.7931538573394956,-3.1689942312851147,1.6974825624211063,0.15114811202820777,1.5912944292769344,1.260547932390675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8500137,0.0,1.0,0.0,1.0,5.299402818462023,1.4070822248999566,0.5259985098650994,0.9467712046394913,0.0516023670321161,-0.034572138303862646,-0.3158579570554904,1.2924430994225764,0.018526946596589267,-0.17506430702123316,-0.6779945644517804,0.6061987252850415,-0.36625792282527553,-0.4015587809261225,1.0879667385035403,-1.0028183345096437,0.19337915560356278,0.34055992012260367,-0.9360693344856046,-0.4009151418075239,-0.3007771864154085,1.1715579589607177,0.3438729276452577,-0.8752471623385067,1.1794840696279483,-0.4364835746959009,0.4992688084695375,-3.4615234356297364,1.20361135401634,3.5103946092561995,-3.6222565384063614,1.79786870716256,-4.755991436046566,2.1735165638630107,0.3655309580780906,1.9119759881780871,0.6113552263747147,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8666804,0.0,1.0,0.0,1.0,5.317244825197994,1.3946362721470986,0.5240928480942041,0.9461891968771982,0.04630366179166016,-0.02707047811299376,-0.3191381579070424,1.3215222321113993,0.06244990745990642,-0.15207430050406623,-0.9905250382959512,0.5926674195643992,-0.4048337823300844,-0.4133961439975907,1.0928924426608226,-1.079133502371613,0.22290833678178262,0.39967543163951735,-1.0008659803588758,-0.37357512211265553,-0.390995444494831,1.216623404991056,0.3524267900407032,-0.8407187729714849,1.1848777106367578,-0.8823788492040023,0.2801657901708018,-5.093466663327184,1.5888583645725416,3.5629817474130867,-3.579794096238601,1.5511645040327222,-5.621387874262118,2.997409346229205,0.5544989958814273,2.1871047922966094,0.21687397270265024,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8833471,0.0,1.0,0.0,1.0,5.336077465851366,1.3823734705806519,0.522131610942797,0.9456453246147365,0.03931805990438245,-0.01963823346210612,-0.32221630931120315,1.3507279205673384,0.10001856576275392,-0.13664748412292707,-1.187222615797488,0.5013436744910242,-0.36666403526040664,-0.4309714680581792,1.0973056168536197,-1.172600896184994,0.24634120701320514,0.45932621590182304,-1.0553960430131644,-0.34920955492879957,-0.4881571569833374,1.2714718036623143,0.36235626447457164,-0.802343523454967,1.1867132165096348,-1.265051482010097,-0.08102344033705101,-6.071787032593389,1.286632062306519,3.6018178878690135,-3.011696832949156,1.5746786186471706,-5.777316193995781,2.996164896258011,0.6402709719287883,2.396735883171904,-0.008599189479023148,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9000138,0.0,1.0,0.0,1.0,5.355196463361729,1.3700411226919942,0.5203770885690916,0.9451564886736408,0.030405790432086882,-0.01254467434325107,-0.3249574294764404,1.3467864135859284,0.11382234495509458,-0.09228885821669566,-1.2904869032292392,0.3574126176584584,-0.2804959823620141,-0.4555646110680261,1.0901916559146916,-1.2815268082438616,0.26579615796747075,0.5197362680230103,-1.1012560755703031,-0.32108572984584194,-0.5835730361157699,1.3164957679439828,0.3737691984563943,-0.7608274170833625,1.1845910704141778,-1.4254791062533487,-1.7753572395233308,-5.837115497602799,1.1177623083414008,3.546695952706027,-2.3725751363981185,1.6235333290696377,-5.936441919857124,2.1561398129344265,0.7115333724090575,2.6384879586807366,-0.29582660834265834,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9166805,0.0,1.0,0.0,1.0,5.373936595103763,1.3579002763583319,0.5194883949427088,0.9448665177413353,0.020987650083804186,-0.00686672645994869,-0.3267103155136777,1.3116404791357137,0.12712668555323559,-0.017007526644961975,-1.281016118573096,0.17512915332440693,-0.1457245706073847,-0.4784875332985646,1.0381269238456927,-1.3671718019127872,0.2836000251420724,0.5775496507717541,-1.1344820390647774,-0.2950916690575897,-0.6860389500747028,1.3433432745027827,0.3860740909904317,-0.7143937489330785,1.1768523098431056,-1.312520531960308,-5.171279475261099,-3.4595371371467256,0.9987756586040919,3.346225396510161,-1.540265729025799,1.4180189815698294,-6.062177549693503,0.9742459010535578,0.7502820479024047,2.9351894059656094,-0.6864304981466837,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9333472,0.0,1.0,0.0,1.0,5.392210319105464,1.346384252477606,0.5199655585798875,0.9448418559158054,0.011207241714066883,-0.0027490671984054405,-0.327323551966976,1.2749780025190338,0.14156350333325718,0.053280636936076035,-1.2927388532517297,-0.030367224804150106,0.0008957762512284834,-0.4993153829680718,0.9178153286540233,-1.3968449434512282,0.2990887465059844,0.6312773376550421,-1.1525983692222117,-0.2738183359255822,-0.7856460252507234,1.3489706962621615,0.3987786500719443,-0.6629875745385485,1.161710008047255,-0.9379632581364412,-8.611932588839204,-0.06806691559513046,0.8282247389379097,3.1146986799498637,-0.7202717445731264,1.176169261133313,-5.529478235425555,-0.2203192256054732,0.8672011572682242,3.1762956675850895,-1.017748693702446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9500139,0.0,1.0,0.0,1.0,5.4102246885831535,1.3352822354478586,0.5212813440208174,0.9451138643083032,0.0004690951580246686,-0.0002802258909642792,-0.326740699814714,1.262642118698435,0.14161866170251214,0.08996540091719608,-1.171477070462401,-0.2747455462350946,0.16079624671069068,-0.5097530377673298,0.75106193008888,-1.369440703637086,0.3112075716549853,0.6813731477499949,-1.1584911452353313,-0.25588594860852854,-0.870355259887437,1.3359992856279852,0.41498085404611634,-0.6085170149271977,1.1429272855364445,-0.9955943567439439,-10.214557052271921,2.0936396253854253,0.5031847935579675,2.8506306971331807,-0.005738011277720356,0.7731508284640946,-4.698570568729906,-1.297611158887934,0.9556986669878035,3.161417028405806,-0.8490036001905199,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9666806,0.0,1.0,0.0,1.0,5.428224868515026,1.3241005689793948,0.5229788515002112,0.9457496351910966,-0.008737033244514183,-0.0006823965675771746,-0.32477811829142184,1.2581894122056467,0.10949576537444627,0.10818963540997094,-0.9522261220503945,-0.4790160264903366,0.29619958623434006,-0.5325019278991604,0.5773294126078224,-1.3270568163624057,0.31586160650356954,0.7262985509348613,-1.1527896366473365,-0.24804659010005714,-0.9422653574464248,1.3057169044584864,0.43063533601811554,-0.5576067961638864,1.1334098314406644,-1.1092278261123936,-10.168918623759447,3.2324125626412106,0.20289279116557205,2.6679137665117993,0.6149689043918333,0.23762138325897827,-3.817802715023342,-2.256598292819449,1.0343398334115763,3.092915376774293,-0.42070335998344743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9833473,0.0,1.0,0.0,1.0,5.445574737713937,1.3124589459435003,0.5251205682138423,0.946580866050759,-0.017133612322968235,-0.0026238372994973327,-0.3220003398029064,1.2475594144735849,0.06148454198888653,0.12202411653695477,-0.8053850852258647,-0.5893180360055041,0.3772730892767423,-0.5467273725862647,0.41209729803565687,-1.2616934027215414,0.3179706782200238,0.7703037844946393,-1.1379921407576765,-0.2479652199918037,-0.9976156049083961,1.2607791920941174,0.4494589174491578,-0.5054196295070295,1.1289038121567723,-0.48397821881405917,-8.87110411281393,4.171113561683483,0.08387921691034915,2.4866138360397017,1.1778192006227703,-0.19183960404052325,-2.838944336579847,-3.0566082789971367,1.182118502433407,3.203890690393059,-0.3958102016219549,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.000014,0.0,1.0,0.0,1.0,5.462460420363098,1.3005159980262075,0.5276462953900053,0.9475247641851015,-0.02462034967100165,-0.005542454006703582,-0.31868470443626407,1.2652909343416154,0.004641915723405443,0.12630266909736412,-0.6680558952383059,-0.6482254261744064,0.38755169959419705,-0.548634567458177,0.2816253507737506,-1.1880194195653855,0.31865758599252897,0.8091858445771071,-1.1135289181052974,-0.2544412563573815,-1.0368970245953755,1.2038297580513633,0.4700393649071293,-0.45081022622473843,1.1202161316659192,0.49447695126063135,-6.740135645269356,4.861086278542018,0.1699724989409172,2.3401740326533678,1.5014411387317836,-0.4976092727595797,-1.7832893572261512,-3.620094784450202,1.1373287730569284,3.4272662957954187,-0.646910218798522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0166807,0.0,1.0,0.0,1.0,5.479297054146325,1.2873335328767685,0.5304234627348138,0.9483130931076734,-0.031159034904842172,-0.009152535660051723,-0.3156701174887284,1.2972090402929894,-0.058217480044251535,0.11076719746413331,-0.5834756544751076,-0.6446236269383319,0.31530201645594885,-0.5302447745791136,0.18742566051763532,-1.099656869364389,0.32363643951622095,0.8483097415946871,-1.0879440027038745,-0.2645522289244079,-1.0570587023685583,1.140109124606125,0.4873699523729736,-0.39117719116276245,1.1073400950694736,1.5331374972656502,-4.7892353299801655,5.4114392564857825,0.3947562017549347,2.2267994371469744,1.672430383331604,-0.655384574609721,-0.732014667234463,-3.8867713374808535,1.0484142450420573,3.612811992214685,-0.9322415363040435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0333474,0.0,1.0,0.0,1.0,5.49592154831942,1.273341753076963,0.5330354542068005,0.9487877826190485,-0.037279667288841176,-0.012501695811755491,-0.3134576168503373,1.2998835100326311,-0.10522324553172557,0.07239916888184296,-0.6814938768082931,-0.552391431352873,0.18469342685916115,-0.49752988200682213,0.12198385382538976,-1.0076377502532423,0.3318161523681069,0.883412640935302,-1.0577811271655517,-0.2762874525366772,-1.0612975623041687,1.074270454350579,0.5049865763028142,-0.33038291896344946,1.089141351639682,0.9719974415269931,-3.29734869216248,4.710932150114882,0.6602419547383848,2.016999404225771,1.7343495392296255,-0.5885904780873856,0.11897740765430652,-3.7436630786413634,1.0759474013187855,3.5498118191218992,-1.113594927283892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.050014099999999,0.0,1.0,0.0,1.0,5.51200791902632,1.2589822886020843,0.5350905073565723,0.9487311755445792,-0.04485860411757713,-0.014224379178962897,-0.31256124075674574,1.2778007858524898,-0.11747702689073591,0.05124638320243349,-0.8439409415300466,-0.4109303740807931,0.07470017730532723,-0.4978447950617177,0.07751381762230651,-0.9426254836317495,0.3456445486902974,0.9155431895355064,-1.0301322357729177,-0.28417195076668594,-1.0530927808482542,1.015320105740541,0.5232349374800932,-0.27284989387124453,1.0702201899203487,1.2746513635476804,-2.5088528122919422,4.999585339049366,0.879534408263852,1.7769467930928007,1.6460035973389575,-0.2533616545429793,0.8953716265409024,-3.2826210564507923,1.215622254952993,3.4418158947541233,-1.3245052238051092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.066680799999999,0.0,1.0,0.0,1.0,5.527849842889164,1.2451606450782482,0.5373786136849067,0.9484440636071736,-0.05278263657928989,-0.01455168321983346,-0.31217959574501314,1.2707742171855831,-0.10034071152314394,0.06024438261186608,-0.8571301058903209,-0.33840101311886894,0.03687905906807021,-0.4550414182451419,0.03835525949213753,-0.8409845723125742,0.3611340246125292,0.9426443191681816,-1.0029142308540133,-0.28473285791222014,-1.0314517817280302,0.9648495336274822,0.5455073991760643,-0.21565549301725237,1.0449910892124967,3.04595450833297,-1.104426951582228,4.855603659229774,0.9063357557597815,1.4636129861840401,1.9256609165612322,0.07290954995260523,1.241344180714732,-2.026029245733196,1.0790267008534369,3.2993331658600393,-1.4420560230259225,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0833474999999995,0.0,1.0,1.0,0.0,5.544117857252099,1.2315086745986992,0.5399563097925207,0.9480912911690118,-0.06017724443169378,-0.015082283991604708,-0.31188800485379486,1.276617868320925,-0.06875853846743518,0.012489488052132427,-0.7323171267626608,-0.37930725478438376,-0.020613024193045497,-0.3963127750536515,0.040699512274435475,-0.7807717046171797,0.3758558009713405,0.9643303866491735,-0.9659434101768155,-0.28174162757429577,-1.0117145587348177,0.9477856624808181,0.5592025661103212,-0.1628719017203655,1.0221515596824164,2.52307841858431,0.8470314477251526,3.065951969365808,0.792784405742634,1.4736309917535693,1.8978067612635796,0.11233306934452769,0.894905627590838,0.14289989044290982,0.7963566731052979,2.896889280171843,-0.8130538782599959,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1000141999999995,0.0,1.0,1.0,0.0,5.560749793657809,1.218293551951926,0.5408460392301155,0.9475166073380759,-0.06632062731508993,-0.01676467727767523,-0.31230241562762673,1.2342859076212949,-0.011053077037671222,-0.12455196746283302,-0.5734267219838493,-0.4358341614545289,-0.0692926886434142,-0.37093863608710365,0.06658969755173913,-0.738785968936916,0.3875602243229107,0.9917654504687,-0.9396538789581099,-0.28098841477853126,-1.0016215344812938,0.9696128728355718,0.5720526747033524,-0.11909232388557227,1.017889239066905,1.5617310771194584,1.9443142021188846,2.4423470067496647,0.5748157340929957,1.7006191268502509,1.3402271925590215,-0.08179360724554648,0.6230029168711207,2.560744670387377,0.8619226207719416,1.7940853257349212,1.1157702515943329,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1166808999999995,0.0,1.0,1.0,0.0,5.576953151013311,1.2063922132261644,0.5388972809811485,0.9469808254873034,-0.0714826494821237,-0.019057031947700757,-0.3126569630053768,1.2057741971063705,0.037469402361932636,-0.2645533157933822,-0.4907166877452565,-0.3501740374767044,-0.04091699976499175,-0.3442549683675977,0.10551011529934509,-0.6993599749023904,0.395016363762156,1.0210178042521236,-0.9212690810763686,-0.28446808660205447,-0.9909477533055859,1.0331439888767087,0.5879333775975606,-0.10306893792351308,1.059343975786911,1.1439076000675308,2.7676642193469805,1.1167050681347608,0.5740294542170433,1.9832224742863953,0.5973911404755583,-0.032364428956614316,0.5231057160127949,3.752477830905981,0.8467555084299817,0.008182860036540186,3.4556376044719492,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1333476,0.0,1.0,1.0,0.0,5.593722268492561,1.1942956761058066,0.5352171454281078,0.9466114163198687,-0.07587779962928064,-0.019781795399041582,-0.3126948457955479,1.25261257497668,0.04508596096288786,-0.3254105563695783,-0.28242999170781924,-0.03150772794224792,0.032961471749531436,-0.3328083064910126,0.15884535604091976,-0.7015623922187527,0.4066945777321091,1.0578729984930781,-0.919740801116182,-0.28206723123471367,-0.9841846424071529,1.0946957173642933,0.6002779147680524,-0.11881956133883026,1.1330773895918103,-0.05632221286327261,4.036971435324459,-2.5444781174937807,0.512746765114837,2.2852692765398355,-0.387752758843125,0.03468316828539985,0.5220548025291409,3.273238576960227,0.26564516016507694,-1.34352356105747,3.8446813953124064,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1500143,1.0,0.0,1.0,0.0,5.611294810913457,1.1812985039675319,0.5315314227470335,0.9467904829931352,-0.07611433045909685,-0.018038331046685528,-0.312200270059844,1.305327965443121,0.035067318505393796,-0.28541567917372124,0.21331199199514064,0.41857352769895934,0.13844597408116394,-0.34613237921785434,0.2400760989415894,-0.7841760817840576,0.4121079567824349,1.0971935991547366,-0.93419419888799,-0.2833119786803299,-0.9735458917509611,1.1422521596579547,0.5967882339794072,-0.14785314619366616,1.1875002786094175,-0.7071082477822616,4.17389527484488,-4.386052041747737,-0.14395694899118103,2.0314039154906363,-1.2550525657531242,-0.22887802470667606,0.9502679189226135,2.2441443456363257,-0.9060818077873082,-2.751292353182294,2.705229023487884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.166681,1.0,0.0,1.0,0.0,5.629290075181571,1.1681415890325297,0.5292184935944717,0.9477024687915185,-0.07037321114713821,-0.014107283201514512,-0.31098010605177556,1.3554383077378962,0.007301318013890223,-0.24027085887107638,0.7091317629528262,0.7986208901383529,0.21763497333302537,-0.35637862855763786,0.29797547679543407,-0.8477644193471467,0.40189600316860646,1.1255865977696937,-0.9615759703114571,-0.2896965139834712,-0.9525089817585378,1.1695006784951272,0.5700751274363549,-0.21052948986439693,1.2232518707233413,-1.091334296367654,3.767810535549245,-4.203768141565183,-0.8748516175447829,1.1915951261595943,-2.551727242615321,-0.5318149774415746,1.3935757750782012,1.2908318270303898,-1.6852200024449815,-4.62676573409528,2.325094534967875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1833477,1.0,0.0,1.0,0.0,5.647726880242279,1.1538121433296975,0.526760229800457,0.9489016923478366,-0.06082388680609147,-0.008840136760143915,-0.3095284882450617,1.4094316017289297,-0.039511113473594706,-0.2622447915926369,0.9846380880655843,0.990318071981029,0.23826383697235712,-0.3825102618523959,0.3656700346472666,-0.9243019667541065,0.3829461778741676,1.1369135161330648,-1.0192519437569836,-0.3010391800493809,-0.9270932730099694,1.1852799732810895,0.5406141215499076,-0.3020789791145578,1.2650035847813157,-1.581142773277405,4.106377368621486,-4.697205780750476,-1.0033378551405074,0.022709762568492112,-4.326503651715054,-0.6468405515325302,1.5810124794032363,0.8819688195644195,-1.5108979447183588,-6.009668784223756,2.797124668921051,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2000144,1.0,0.0,1.0,0.0,5.666303980372231,1.13848243255179,0.5232450468378778,0.9500573627089394,-0.04972730581394307,-0.0032807000043832356,-0.308070510803132,1.4410524828221964,-0.08346802629887451,-0.26670311028131294,1.0712154577181106,1.0264454542448362,0.19428525979449227,-0.4090834930764029,0.4348549961746415,-1.0043382585192147,0.3684513411080659,1.1263435913692943,-1.1057930471355357,-0.3112579088239256,-0.899808460377598,1.1988996979451958,0.51971176188588,-0.4108521833164411,1.3164895461623543,-1.4549284861334109,4.108994086546419,-4.566030651906983,-0.5002361276919423,-0.7570896398866722,-5.072972354483474,-0.5357480625309375,1.81568810373965,0.618419582731803,-1.3562020777712076,-6.7336222294055075,2.987697726064222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2166811,1.0,0.0,1.0,0.0,5.68479670197839,1.1226111239899732,0.5199427216717032,0.950844083020623,-0.038606545973476424,0.002081490186073971,-0.3072470208012988,1.4694506045122708,-0.1286647966825435,-0.21111047706788588,1.1043746100053826,0.9321318926885545,0.0737787279522445,-0.43100797505207533,0.502636778131753,-1.0765032928863827,0.36627160693536104,1.1116771443308664,-1.188351360437923,-0.31889748451694966,-0.8665702151727741,1.2058940006001218,0.49540729521072885,-0.5265335023362233,1.3645937081633048,-1.1858328154794346,4.087394120209161,-3.8941886845246763,-0.10950428149582077,-0.8056140348287091,-5.432894231454665,-0.4530188821740449,2.2339103880723825,0.18820131521867986,-1.5039019889261505,-6.893023726743442,2.4992382945316285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2333478,1.0,0.0,1.0,0.0,5.703337484429111,1.1058811368760944,0.5175175486488969,0.9511148286449096,-0.02745584929677439,0.005896997228980598,-0.3075580993809766,1.4857772496455515,-0.16872545330487398,-0.12167366872645016,1.2743716982723143,0.7297312290934148,-0.10938708749626128,-0.4486113326479051,0.5711017393412215,-1.1341448076159495,0.3648011910912531,1.099489736500735,-1.2868898837103067,-0.32635856843098593,-0.825344631847826,1.2051730876659061,0.46958159532820903,-0.6406201004094709,1.3997976559292948,-1.0027988983466125,4.023870558224459,-3.041212699058896,0.15296512544309274,-1.6093342631019392,-5.710690579768529,-0.5350031451050691,2.782835910760589,-0.3272563361222976,-1.5947140806186653,-6.530287239841778,1.3617308357435711,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2500145,1.0,0.0,1.0,0.0,5.721547154847289,1.0888712691522981,0.516488325507738,0.9507696744679287,-0.014682697899936342,0.007085264099291871,-0.30946929335100676,1.4514978757726558,-0.18297537652848606,-0.02404218869213971,1.347562950587129,0.4914060442524092,-0.2751715742056879,-0.4644346718502223,0.6367660649972722,-1.1778772522691925,0.3713704546478058,1.0580325616051842,-1.3787080938095793,-0.33673095835399497,-0.7738088326250271,1.1949854342456228,0.44225005287583463,-0.7442101790167652,1.4099848268034796,-0.8069740534957908,3.734110133425107,-2.1246552897660793,0.5637837314883318,-3.906724952136131,-4.733378786641262,-0.6160020293555108,3.1996218597412374,-0.8396708349351448,-1.7035503709410302,-5.987160235297878,-0.02885392451547122,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2666812,1.0,0.0,1.0,0.0,5.738842526525173,1.0724518415968731,0.5167014298852571,0.9499791859708651,-0.003605043798012425,0.006681408404502224,-0.3122209292521552,1.3844040202173806,-0.1674828108683819,0.04702161011451006,1.2821278932545694,0.2588643440469672,-0.39421165742306286,-0.4755105215627017,0.695572326062734,-1.2049667922518381,0.38359401972644624,0.9692653109812005,-1.4446694921569345,-0.3468920104763049,-0.7186903565483275,1.177184003856679,0.4127964693934833,-0.8401925073967492,1.3988358565218508,-0.6253508490087226,3.3239308039771687,-1.1657411892570233,1.0886746021327571,-6.595941113969563,-2.8233490202097444,-0.7138510373007326,3.398002079972206,-1.1997635812069998,-1.7209103107788457,-5.318949971605365,-1.1913747739865963,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2833479,1.0,0.0,1.0,0.0,5.755404909871069,1.0570044052200829,0.5176351420618384,0.9487605980960229,0.00691527851626931,0.004501150827740476,-0.3158880277325262,1.3076114472965488,-0.12856562975467656,0.08974528983760104,1.1705754928316114,0.03249645133572843,-0.4751737557643136,-0.48527974184056966,0.7475639800585647,-1.2167353696271725,0.40765968063053787,0.8381674180767912,-1.4728199160398388,-0.3605260405207552,-0.6605418700924816,1.1549932348878174,0.38488626112251906,-0.9215088660002755,1.3702722549122748,-0.4034577485533498,2.9910301262909536,-0.45801942973997173,1.5698029601343684,-8.73116930870769,-0.42336161130873246,-0.8359856916284834,3.456453783169763,-1.361451116225523,-1.5517112142012237,-4.331469283270167,-2.298774495461941,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3000146,1.0,0.0,1.0,0.0,5.771172639332991,1.042850625974569,0.519085783652435,0.9473511563344925,0.015036146160580098,0.001100100752333371,-0.3198413523587474,1.237718776167274,-0.08432063939601186,0.12414262841859303,0.9389957511993431,-0.20337045011542937,-0.49681054987308876,-0.4889591400783299,0.7952735296744409,-1.2202341371111325,0.4359208897177892,0.6782257519463236,-1.458781574091333,-0.3747582559296338,-0.6034750000124165,1.1318022092190871,0.36107265880602823,-0.984575105603707,1.3222098867548198,-0.11076130986524764,2.61909991976228,0.29536483319522067,1.4589992996082999,-9.728630278914356,1.98749966716909,-0.8015781410252011,3.4489285342827127,-1.4198873184385539,-1.350993550238032,-3.112004155220123,-3.3603427422945455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3166813,1.0,0.0,1.0,0.0,5.786486489285955,1.0296484640168166,0.5212104370678784,0.9458859800381244,0.020642845077648332,-0.003579901701029651,-0.3238221271288115,1.1909119671523563,-0.03849207748090422,0.1575386101667411,0.7190758310788071,-0.42069431090172954,-0.4225797318091129,-0.4889717928868319,0.8348674853239687,-1.206889855496343,0.45629308788410117,0.5138790935376274,-1.4065697946342246,-0.38724536532680465,-0.5455773556878222,1.1076635629473777,0.33985305271501465,-1.02524254530789,1.2582606061462738,0.040923338030399756,2.1764903686048274,1.2173128453355069,0.6080614575971982,-9.368342486826354,4.23588844869439,-0.7394869049462124,3.409779127851048,-1.2402591686598166,-1.275039119920233,-1.7068458389693388,-4.30993250724598,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.333348,1.0,0.0,1.0,0.0,5.801651833907576,1.017320595551227,0.5240175137659192,0.9448016214281434,0.0241169639362552,-0.009265411528708313,-0.32662274927881596,1.1526247700521703,0.022296110490563126,0.1914896231435528,0.5898982291147673,-0.5433318944999801,-0.23551420013494037,-0.4875950260824274,0.867823353727293,-1.179656961112426,0.45618964550845964,0.36594704449594606,-1.3175850100756235,-0.3994078687269679,-0.4898154684321064,1.090460154246482,0.31857126980607914,-1.0414700806924075,1.1785451825177866,-0.02382665676337713,1.757701736410765,1.8779174321474834,-0.6283012759384361,-7.570391821377858,5.908678118797666,-0.7384541954378468,3.2880848256785313,-1.0728553872097404,-1.3832431333371809,-0.19630042245364604,-5.154155870452347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3500147,1.0,0.0,1.0,0.0,5.816949177128672,1.0062499138751526,0.5276906605116987,0.9442853940141145,0.02699904677837974,-0.015256778483668293,-0.3276635116014105,1.1149459569651343,0.08223653256687574,0.22511923827684516,0.5271250990270996,-0.5547920840262628,-0.032724317394817314,-0.48976601636738826,0.8934576603844433,-1.144292482563598,0.4353496701327349,0.2615321947989107,-1.2096134634290945,-0.41186055440501257,-0.4359743089595494,1.0719016451833605,0.29374485605423306,-1.0317859058097063,1.0864550668541375,-0.18897617070853212,1.3391641336685773,2.2524863689165833,-1.618655182265971,-5.470997063508035,7.440987481619737,-0.6785011095720409,3.218983765650009,-1.2260077934055629,-1.4612149845494122,0.9018841688000194,-4.944019739326744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3666814,1.0,0.0,1.0,1.0,5.8321642328098475,0.9961327418289972,0.5320875364121608,0.9442480949822295,0.029382869294812226,-0.020864550493363474,-0.32725655478102245,1.0763677328196288,0.126816998316359,0.22932214385188493,0.6269460233228903,-0.5378865182671246,0.10785988662320305,-0.49389424437112317,0.9124622474605212,-1.1045739319827819,0.4022343648559151,0.18358011097920734,-1.0695515979558001,-0.42202461761277654,-0.3825157949781884,1.049593146065777,0.26986400624009976,-1.011407214940129,1.0137441949389125,-0.3882685642194001,1.066176304243433,2.4275859677014626,-1.7297585352609564,-3.9944547758401243,7.3227331971240766,-0.7566803163312739,3.0997478597031343,-1.2704163178899703,-1.3514298048324813,0.9857800365622159,-2.9339102182033026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3833481,1.0,0.0,1.0,1.0,5.847271024164322,0.9870266022295386,0.5363309084175909,0.9443714033745702,0.033889350429195816,-0.027195037883685567,-0.32599784405780496,1.0456654223167636,0.14936539606085097,0.18316321138519245,0.816266586967893,-0.544301110926331,0.22051209986194173,-0.5027083277259392,0.9289969416043113,-1.0633727884678181,0.37769093697346734,0.12838343597392152,-0.9655218686760788,-0.43708328206140945,-0.33264917365292096,1.029554349892607,0.24869710579783003,-0.9989265055389633,0.9886578639866795,-0.5726151230470967,0.9529815313854786,2.4997158457715347,-0.877978276642046,-2.9203654007460687,5.793187885446307,-0.905777868814649,2.8078675743800607,-0.9469254877226814,-1.262219853745274,1.0001976352633968,-0.5321208046853386,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4000148,1.0,0.0,0.0,1.0,5.862167661389068,0.978233627296908,0.5395970808051727,0.9447312186359157,0.03916680582940064,-0.03399454885536519,-0.3237178655927719,1.038001963238732,0.1461016965033033,0.07576330742605902,0.8389593226114958,-0.5181023614633411,0.3610709908469806,-0.5129814533137013,0.9442283620388059,-1.021249903809341,0.37296836376929515,0.08623440292997835,-0.8764449488950642,-0.45221727362512276,-0.2889200219743481,1.0180289000133218,0.22778992696726705,-0.9780672270848401,0.9960067993080143,-0.6941208981670329,1.0055605950657605,2.3060959368829983,-1.9763898094313475,-1.073842357374139,5.528737236301888,-0.846643454794313,2.2527624823079693,-0.1596822321240405,-0.7748234965586555,1.368482633169164,1.3633720884194824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4166815,1.0,0.0,0.0,1.0,5.8772790347641575,0.9694743114055059,0.5406553899282558,0.9454809195415209,0.0440887834852269,-0.04012269103513109,-0.32017523267394105,1.071700000228545,0.1154761860816349,-0.056187854618134005,0.6219600670071542,-0.416773289331268,0.47265774596661403,-0.5258457372729002,0.9625156951438764,-0.9865027701653224,0.31181114489976847,0.0925886191386264,-0.7812302588835335,-0.4653047869974502,-0.2575569407251565,1.0242315981763235,0.22286960425764174,-0.9533103265344823,1.0341036911588015,-0.6773044301919053,1.3182350216066632,1.719314238144655,-2.8798833862188173,1.4815733865494485,4.241122256048032,-0.6262235333903498,1.3124223304099116,1.304801965355289,-0.005137071745271716,1.2937700482344507,2.2992933566101454,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4333482,1.0,0.0,0.0,1.0,5.892963704720603,0.9596319861902973,0.5398590649453407,0.946532488323897,0.04641778960460214,-0.044240915840937076,-0.31617143881310633,1.1471748851433587,0.08151957353742179,-0.16160309977837212,0.24802907632872406,-0.22751233570060356,0.4970613080053745,-0.5355583128070601,0.9881696173080294,-0.96393931458357,0.27697205890310883,0.13562028125318573,-0.7350739242853127,-0.47309143315303664,-0.24517252346586232,1.0615223858452958,0.2276186908999532,-0.9349414725590218,1.072650064481243,-0.5405755531964651,1.7015380340041582,1.0205395618944,-0.6402334178444793,3.3294112214983227,-0.31944761934650484,-0.17237497431985876,0.13012172092641544,2.795790136837749,0.33280682980400894,0.9710478345982039,2.1906654108630783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4500149,1.0,0.0,0.0,1.0,5.909947970990757,0.9489148010460835,0.5377078786306589,0.9477502038593686,0.04642492984471614,-0.0454131927908941,-0.31233302562165227,1.1951796652584625,0.08075072712889064,-0.2014791336023889,-0.1646674893830374,0.07124415523627467,0.5200515105389593,-0.5438649584178192,1.0192337430465506,-0.9524847167328716,0.2904699882893913,0.20356921514931858,-0.7918785341582583,-0.4710506309664438,-0.2532195413528279,1.117424789123591,0.2339631874382307,-0.9209420006446866,1.1071260175652649,-0.33062240614548316,1.8318810722911596,0.20807076027116359,0.1623259866958279,3.601588115146567,-2.8342684414309387,0.7648504815867163,-1.1449766966532051,3.089774885517412,0.4481645617640902,1.1549714541821052,1.8593761726463351,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.466681599999999,0.0,0.0,0.0,1.0,5.927221049112943,0.9384333925571341,0.5357870137856287,0.9494116295965561,0.04377709590747699,-0.0426710856280456,-0.3080264630060918,1.2034516225577168,0.09475779684236563,-0.2015541279797258,-0.42424330850668956,0.34097266688244654,0.5214878021327006,-0.54657908172007,1.0492324418431396,-0.9570036087031472,0.28238293594803554,0.2556734585306123,-0.8295497279509068,-0.447596366110114,-0.2833384896860823,1.164515088014202,0.24255753950306033,-0.896442347088188,1.1346293941945322,-0.19206757430473573,1.6559992984720802,-0.7651424713093652,-0.468466218024084,3.1375151653949804,-2.3609349563696735,1.5597356100084379,-2.61983444066389,2.700985046949415,0.42846368647219163,1.5325646499245988,1.4044054958269203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.483348299999999,0.0,0.0,0.0,1.0,5.9448659289883645,0.9282310523935571,0.5335536596417112,0.950974211108197,0.04108230044546585,-0.03822152376522298,-0.30413715576745215,1.2178904590405788,0.1090224891929008,-0.20660771552889562,-0.5743169283619028,0.5096344575069222,0.4925909311750831,-0.5502672236991487,1.0744338300622398,-0.9779895167860152,0.2748544164575073,0.3081532631634956,-0.8705765234329111,-0.4190593399837885,-0.34054753069725363,1.2074578040875745,0.24824533888488284,-0.86985641014289,1.153939627719862,0.06775190242137463,1.1529424118950542,-1.7577978627331539,0.25951207402615756,3.405945964405399,-3.1526384586246916,1.6204100398866537,-4.1180813946643875,2.4444409963479097,0.4306131100311317,1.713328278653963,0.9293384242947228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.500014999999999,0.0,1.0,0.0,1.0,5.9629520605746995,0.9181502931344501,0.5312485851821701,0.9526132632109301,0.03693628141342714,-0.032025187430992606,-0.30023002721243786,1.2239307873701957,0.12185500348798711,-0.18420694536740412,-0.8137388072967153,0.6220488122345407,0.46674504068716155,-0.5443206804558973,1.0876639324358022,-1.0155969879807765,0.29103335571637906,0.36920521774052323,-0.934637886747627,-0.3935825900865562,-0.42060814404698815,1.2459966175218653,0.25691133854497206,-0.839331290244504,1.165607403626918,0.6891751305601307,0.04196597883650604,-2.8684232298291152,0.607120394031717,3.5269487554211048,-3.5183835790101448,1.3814590678424745,-5.279870297887747,2.5027277039249918,0.5713977574108595,1.9262962950651323,0.40711731032945137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5166816999999995,0.0,1.0,0.0,1.0,5.981049773431551,0.9084304838766982,0.5293911551907949,0.9541294457494245,0.031017549456052014,-0.024569904348787783,-0.2967679770122254,1.2163714424300198,0.13324260612464045,-0.15116899276653908,-1.0668946326972384,0.590428240609844,0.43696681470005966,-0.5272946734021356,1.0758326988211886,-1.073603815675201,0.29509180339992414,0.42571845680744946,-0.9878562106254879,-0.3730106122917682,-0.5165435592848651,1.2908822277335879,0.267291968891762,-0.8056464052209659,1.1675102318719977,1.1370457095921154,-0.8238043005533497,-3.387794892222396,0.38195349282778157,3.3206123174457285,-2.9533795646651586,1.1785073997009443,-5.7609818479790045,2.649198044738156,0.7639976938469781,2.0703590843211623,0.01769591323003662,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5333483999999995,0.0,1.0,0.0,1.0,5.999144547150975,0.8990023277232303,0.5277076145807567,0.9555612083557116,0.02271262545315527,-0.017594482792788687,-0.29338941341849994,1.198451939950866,0.14530059822879093,-0.12739176053567686,-1.2919074295258524,0.4351417025741672,0.416117076236687,-0.5064190809997795,1.0602037341637371,-1.1285237102411825,0.30376516427420464,0.47989251636286867,-1.0330840691284366,-0.35429893152936476,-0.6126412563784115,1.3343033956263401,0.2823779792730509,-0.770319182743193,1.16619726858098,1.0767232452522313,-1.2923508364591882,-4.172977985484951,0.6201375677089582,3.2294842884183517,-2.4548356853756914,1.1980103460401557,-5.641626588775038,2.1012716801898996,0.9542903230919693,2.251579612824468,-0.14277222409031723,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5500150999999995,0.0,1.0,0.0,1.0,6.0170073965855275,0.8901443608754929,0.5262228731783929,0.9567760579809884,0.012449095685630051,-0.01149043666150694,-0.2903318183670167,1.173517578713173,0.17639449751858932,-0.09017057963015149,-1.4104147156583489,0.26115798799299794,0.44603112133995604,-0.4914038267788449,1.0327542514491599,-1.212703360056565,0.3157630969993939,0.5333681483870137,-1.06968423046039,-0.33307685422307326,-0.7045981550191389,1.3609247571580299,0.29910170994751584,-0.7305936013548427,1.1627511482175055,1.0471562687114664,-3.0514777839243044,-4.431352977970504,0.7451638492733714,3.1714678839859842,-1.9359374421853746,1.0920010788165555,-5.588534205125307,0.8885394528894923,1.118800739599387,2.42504801585236,-0.3076940655083754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5666818,0.0,1.0,0.0,1.0,6.035009708597708,0.8821972156987226,0.5254602731597441,0.9580634804668791,0.0014096127700288011,-0.006692401719411321,-0.28647441796215345,1.1577547805958848,0.20063540288406806,-0.038449665916093084,-1.3697333692034594,0.05850764520671481,0.5441379269755323,-0.4715138022323127,0.9584876046010747,-1.2762357715970645,0.32860400892757363,0.5856083239269271,-1.0976154462637786,-0.317898822768741,-0.7989261024515354,1.3639214366252868,0.3196714118464131,-0.6894840872115799,1.1559407792177632,1.660918234129302,-5.82077678439205,-2.52250399144674,0.6748045645232957,3.027710452123655,-1.3221013698349442,0.8272018892660309,-5.241986008887393,-0.21816755401202761,1.220167120666686,2.6110009073785307,-0.48043131702585773,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5833485,0.0,1.0,0.0,1.0,6.0529500072349665,0.8745483806792818,0.5254487575582839,0.959427517764725,-0.00919066524980842,-0.004018416391561546,-0.281776901391488,1.1526850377780422,0.20064614962501298,0.007691765886812381,-1.1694643530366182,-0.1556318027117603,0.6959829651004328,-0.43603977491331924,0.8387279705843059,-1.2967869946050559,0.33825662747047475,0.6342920319718324,-1.113754364261646,-0.30550340276741295,-0.879331371447786,1.3536524908131253,0.33977402864754674,-0.6435600637088312,1.1467367389545557,1.9154732769037326,-7.6608778169290455,-0.8132351894518569,0.30066149772612166,2.851053796617373,-0.5785462173385031,0.4882261360357135,-4.385118230663256,-1.2065935415743105,1.2334555955443391,2.7870717227043134,-0.5931845847108775,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6000152,0.0,1.0,0.0,1.0,6.070946048716478,0.8670553326323863,0.5261090886737761,0.9611579370169797,-0.018052449393250045,-0.003555566372755036,-0.2753849798517285,1.1611345880249984,0.18797493766327178,0.03419682318509034,-0.9149032299932613,-0.35106748542018373,0.8778490703914822,-0.40766456530396983,0.7031244999782521,-1.303343665461139,0.33862607889587754,0.6806436405510926,-1.1169003587448099,-0.30162458568580813,-0.945097002481526,1.3237015714665736,0.3607866805949308,-0.596581510649988,1.1361679201817616,1.487977964232402,-8.307562731159429,0.4802230312691071,-0.212547339373725,2.6173516338605807,-0.026088778422043032,-0.054619721642423,-3.5068107421257273,-2.1526454271714273,1.2232018254828652,2.81419836209583,-0.6096316969743184,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6166819,0.0,1.0,0.0,1.0,6.089104465087755,0.859417231845071,0.5270320843878255,0.9631660122946513,-0.025495528791756063,-0.005157423431069724,-0.2676464304929194,1.1620310047418063,0.17150411062356974,0.047484660131480075,-0.6528658189594627,-0.5295903732006232,1.0370231296142094,-0.3864404102403749,0.5618086590414763,-1.2807795282145502,0.3311717019881946,0.7215372609239606,-1.1146239919482994,-0.3073240637968085,-0.9962252966393597,1.2818974997310493,0.3805475043770973,-0.5497532640257461,1.126415641746632,1.2614163965151406,-7.980909304498586,1.7966244149970585,-0.5150821139000822,2.4692379722043807,0.48917846258148245,-0.6029683118627562,-2.6027003506003425,-2.810913764650623,1.2003097084935268,2.8552833884330946,-0.3389937137589003,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6333486,0.0,1.0,0.0,1.0,6.107083810623716,0.85206741967305,0.5283382398193003,0.9654618817630843,-0.030970826271681053,-0.008677886263248228,-0.25855145923497636,1.1504012033647764,0.15029004460477785,0.05194397118489257,-0.4246880642261895,-0.6546904188357177,1.1465126874367468,-0.36561726799237204,0.43709365776767894,-1.243456065186276,0.32145664076040054,0.7629517375737701,-1.1005943773801963,-0.32172356961245413,-1.0318538543482274,1.2300042585839686,0.4007970842320289,-0.5014052073499923,1.1248681071235507,1.3162257184086574,-6.834506248091238,2.824048757614982,-0.6484328870600538,2.4380987304023933,0.9866832590582618,-0.995211165876397,-1.6414931717154173,-3.326671247567125,1.2298353608942196,3.0718635468811955,-0.11662371390704274,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6500153,0.0,1.0,0.0,1.0,6.124821052741339,0.8447350756149095,0.5297395404562807,0.9677916948400607,-0.03530784790577951,-0.013256428476823364,-0.24891134642459417,1.127240907460373,0.11356235364632022,0.03650677929310665,-0.2957611506191166,-0.6859206761189336,1.1880541729700735,-0.34256613187837176,0.33399132847135177,-1.186644381357467,0.309557229190667,0.8028073811439558,-1.0817344842008068,-0.3404978356734328,-1.0509418451294184,1.1710082363673953,0.42154209839592865,-0.44735760767213645,1.122528176841483,1.3958320997501066,-5.59306265669099,3.957242550330551,-0.7680577185477444,2.15170591227453,1.2714266603729123,-1.1851494017050639,-0.7157238050722495,-3.6850591427066495,1.1318718683604208,3.2649494894044353,-0.28448897393383543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.666682,0.0,1.0,0.0,1.0,6.141806827710502,0.8373976052198495,0.5309425357641753,0.970066968902701,-0.03885053423482627,-0.017806703466707246,-0.23904734498681116,1.0975617052574016,0.0795784338477214,0.020046808263906528,-0.2708498396286052,-0.6385386227878426,1.2142960181680196,-0.31908943827856184,0.2506578630071355,-1.1115477163590877,0.29585466560496115,0.8346754114299819,-1.0582134039393218,-0.3612286286792497,-1.0557113622322227,1.1071687081564707,0.4385262219688342,-0.3925733400398785,1.1153851223598246,1.2366536061590494,-4.415965427380319,4.236558491888713,-0.5856619505482542,1.96350530771808,1.3506312923685804,-1.1553784154355062,0.09408052614719442,-3.8511019008619707,1.1022535613529751,3.335511966636661,-0.6159453427210932,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6833487,0.0,1.0,0.0,1.0,6.158425301256731,0.8302154558560622,0.5321714476661453,0.9722633582219599,-0.04259853113740383,-0.021716027809434234,-0.22894921170441357,1.0737266459095864,0.0539494050755141,0.02079180956941851,-0.39971887358437197,-0.571016686398182,1.230369781778973,-0.3013442625628297,0.18679218649431267,-1.0454254825239437,0.29003512512826185,0.8682576889682456,-1.036713351079768,-0.3790105265465107,-1.0478058213191435,1.0426379162652029,0.4582839572579319,-0.33617365308345,1.1019966243544237,0.368607976792468,-3.6616200211903456,4.547938160431917,-0.1044161701808815,1.9369043333557072,1.386008959019957,-0.8724251202345462,0.7807813425457318,-3.7847269824172605,1.3769023533430973,3.190302228876178,-0.7990456697234948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7000154,0.0,1.0,0.0,1.0,6.174600054505211,0.823197328671449,0.5337108390605783,0.9742647541109852,-0.04796113638699682,-0.024677615695444428,-0.21885824996357198,1.05103147174944,0.0229707109516315,0.018576895573860892,-0.632287685342259,-0.5413573018881733,1.216174794944071,-0.3068024811449478,0.12860361819278923,-0.9599494744821464,0.29237411963785376,0.899239018335461,-1.012013012904726,-0.39030952418207593,-1.0296852654286088,0.9810108897607632,0.48442305887376097,-0.2862297197238573,1.0887502134326634,1.3028134752307368,-3.0202847681707214,5.52088335697418,0.19548895092872373,1.6406775645325953,1.646701803493454,-0.5485772891780727,0.8122822507853291,-2.6584535855409976,1.8239524746724611,2.925442124852503,-0.8280002183884894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7166821,0.0,1.0,1.0,1.0,6.190372424140757,0.8161112591046993,0.5351439153038037,0.9759605707731446,-0.05534259272260449,-0.027250220555984733,-0.20903489471030454,1.0195275549591196,0.017958950850501032,0.013316448061768519,-0.8324847783362532,-0.5184215973033426,1.1981949781705463,-0.25791705986757346,0.08611582620297074,-0.8613956692325806,0.29655143652514937,0.9229470504978364,-0.9818231811831992,-0.39729647275759905,-1.0207296921408158,0.9540226195169306,0.5190824946771789,-0.23865872055889156,1.0743965618747928,2.747735531379709,-1.6823946239521625,5.220290001527441,0.5128114378633928,1.4076870082023394,1.8196222428776498,-0.21044047870265528,0.5953411201292905,-0.9332694322376401,2.0894914000751954,2.6883445924202163,-0.7774869625498494,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7333488,0.0,1.0,1.0,0.0,6.205796692375967,0.8100292201600103,0.5366874292401803,0.977427066590332,-0.06385857495349405,-0.029116698087399823,-0.19927526136983262,0.9890836456464895,0.04140096779941399,-0.008670462095200001,-0.9038698432923917,-0.47092666572220004,1.145101745011338,-0.2152111135832554,0.07252368523474222,-0.7859394597452316,0.3094678684207294,0.9461620124546729,-0.9513588168339882,-0.397324220834863,-1.0098405217348911,0.9499018464682131,0.5540729115090275,-0.19661805408687727,1.0628339295152043,1.6665487311556553,-0.18825117077940334,3.645142811963548,0.7661610442081986,1.3420244098472225,1.7902142349816645,0.12160654450877449,0.6966840307979432,0.5656466974493731,2.0473757046470196,2.3476127841326004,-0.5260888564208287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7500155,0.0,1.0,1.0,0.0,6.221219387083839,0.8046101945663771,0.5374171772640136,0.9785823071999362,-0.07218809103149043,-0.030706836998396467,-0.1903224571878813,0.9780742795114853,0.07645012760137782,-0.08799972418654142,-0.7390060372980963,-0.4444593888545578,1.1133847996743764,-0.20236532439246954,0.07984077462691258,-0.7398906658242749,0.32209018907615894,0.9676812869610378,-0.9221492540028614,-0.39324291316687027,-0.9975068446686156,0.9728775471416895,0.5873284879904599,-0.16040480458028594,1.0568602315881748,0.6032269743946116,0.9929679080171825,2.6062336177856484,0.5012402038952533,1.3179971670395338,1.5657713589715412,0.13781958564824856,0.7405642562402277,2.1469779007782104,1.9159473892393672,1.7776835726550158,0.2881832186305595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7666822,0.0,1.0,1.0,0.0,6.2370320729813225,0.7999180094480954,0.5363151609312017,0.9798580790671119,-0.07788938119950156,-0.03265513408365891,-0.18095588247207275,0.9953767626740917,0.0841910112244143,-0.17711750184510533,-0.41244484829455874,-0.3004884561425689,1.1680580205992672,-0.19510350755497005,0.10562268169984217,-0.6990648320701355,0.3261759086332514,0.9900953392224685,-0.8991663338168462,-0.3927302254586157,-0.9851549971559331,1.0214679196260135,0.617937952213499,-0.13736181648613857,1.0724400560151042,-0.02493649167334456,1.7244233876236508,2.075115994850228,0.2337738417684974,1.4689571130287695,1.003659438003018,0.08325511279721144,0.6137725721192524,2.775861750266733,1.7412078057648783,0.693339940281762,1.6666229068970517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7833489,0.0,1.0,1.0,0.0,6.253375875228816,0.7946304401880068,0.534260870016348,0.9814143668854994,-0.08048417586855607,-0.032821669086938315,-0.17108733425897207,1.0235963110145854,0.049329234638849084,-0.23106961950193783,-0.1562279202607369,0.024198441810178398,1.2184930829568,-0.2031965424440138,0.13732166917592678,-0.6707199943215343,0.32988266605336497,1.016646621992471,-0.8886938724921316,-0.3904677371899557,-0.9770477180131357,1.0654064572080306,0.6453688642631429,-0.13729342701489786,1.112414439592937,-1.5309430743193322,2.772984326976774,-1.559702349849496,0.21642652032719586,1.6618552127281465,0.1621642049676628,0.04698556518476888,0.5006339460208663,2.3764606399584856,1.2065844850919205,-0.7391824874495665,2.6548460407736174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8000156,0.0,1.0,1.0,0.0,6.269926026924378,0.7888637349046566,0.5316256819081265,0.9831321332746955,-0.08107041008874394,-0.03015899325056517,-0.16114972000255418,1.05663250786012,0.025868778668615477,-0.2304358719768956,0.23185024093555195,0.42729003567156043,1.2662779217353735,-0.24613504542848608,0.19805567746468977,-0.7510550143786087,0.33339014040592596,1.045490623770421,-0.8937608495069771,-0.3911640368200857,-0.9684671655796412,1.1006834327220056,0.658157515488862,-0.16200128201328995,1.1609351010306275,-2.134812239424006,2.8936461262909656,-3.8450257760672435,-0.30000536807859685,1.640482992963743,-0.3347122078444633,-0.11091401271216991,0.6571592428471579,1.7627689979505226,-0.17418072282734468,-2.026712183674387,2.3004911755943276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8166823,1.0,0.0,1.0,0.0,6.287235868584098,0.7831494737873773,0.5295744526589852,0.9853125310878161,-0.07619911720789277,-0.024675924004460666,-0.15081117131229171,1.0982581886919371,0.02177036414334904,-0.18764367535487111,0.6369821672453087,0.8060379233312935,1.2541207073808385,-0.27435709274562997,0.23377673296203405,-0.7988877765254941,0.31988246711705387,1.0713294977901286,-0.8998509684010942,-0.39416487834129554,-0.9551423661076143,1.1241655413243146,0.6395628285568499,-0.20485063491818967,1.189097632145493,-1.8941419449674313,2.6816414264904247,-3.7445426002560382,-0.9539855536177599,1.4876838704278474,-0.8386548571106858,-0.16213066141939952,0.9090094656756805,1.0545485735606839,-1.458898394772559,-3.2925599957623564,1.5745881491596097,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.833349,1.0,0.0,1.0,0.0,6.305203659395875,0.7778200574227824,0.5279691253154125,0.9874036114381177,-0.06912731532449731,-0.01690326562538501,-0.1413145498743419,1.1381493706022183,-0.011434418980508065,-0.17267680912064237,0.8329885216228228,1.003300833364348,1.1750332932660903,-0.30927323653686345,0.2874439037904657,-0.8758733506899833,0.3015905583529637,1.0950801852969405,-0.9217160673209904,-0.3965684030094431,-0.9381667894564875,1.1358351221439333,0.6095274717365504,-0.2717535013760349,1.2134214776418244,-1.9758170045551258,3.118055470607142,-4.32659068041121,-0.9853249055280989,1.429455259636774,-2.4034106506517112,-0.18647932025255345,1.0861939140473247,0.609159069866525,-1.8321139110861875,-4.596110748514433,1.744338422357548,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8500157,1.0,0.0,1.0,0.0,6.323609756460073,0.7714751692125015,0.5259346844105254,0.9893110238836627,-0.06046706281456947,-0.00875374516497272,-0.1324039436060145,1.17431982662337,-0.08070112759833575,-0.1838084640510331,0.9378500604140365,1.008885589529572,1.110627792778233,-0.3402177912852678,0.33771212318597016,-0.9431077543119132,0.28703823791112354,1.118978101741705,-0.979964816983528,-0.400380868115002,-0.9189358298931092,1.1444708842638034,0.5784922427130496,-0.35805463294272066,1.247242362513306,-1.8528669560452853,3.1934472162628875,-4.005519890788771,-0.08396729145759785,1.0003908215768682,-4.508289920544433,-0.19456131003760108,1.2246012930983354,0.51397752937701,-1.8126210932597697,-5.382898190188333,2.2761827668795505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8666824,1.0,0.0,1.0,0.0,6.3422697158559,0.7642833395549692,0.5235082819668303,0.990952754750538,-0.05159821430455676,-0.0012136474568471831,-0.12389023041689619,1.1980508619064638,-0.13643818683625464,-0.16337746251329655,0.9168848393842148,0.9139176770553035,1.0428613387213799,-0.37103559192950336,0.39389235722904303,-1.0093909474176017,0.29879164303989103,1.1284266127088909,-1.0719926985584662,-0.4030537929814505,-0.8973466647131234,1.152967740721669,0.5491066477864852,-0.45118379990885865,1.2892943882833272,-1.7221396944364198,3.326146387377357,-3.766885875244472,0.8251599419757528,0.24038852252996157,-5.275433825539239,-0.08138313147872973,1.4484655228325254,0.3856070725569024,-2.1380963987078463,-5.4280931943224155,2.1657630271174613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8833491,1.0,0.0,1.0,0.0,6.361145042094955,0.7567318807592945,0.5215881194266719,0.9922892023216692,-0.043455458007064574,0.005342617674027483,-0.11595351897036568,1.1823706127540652,-0.14642124024538333,-0.08464837394005936,0.8965733165660031,0.7581262517080154,0.9609780159128755,-0.39762256257579476,0.44858389117497455,-1.0686708679457873,0.3145436243209781,1.1269910685186053,-1.1558129628637577,-0.4030936445898351,-0.8706535492343235,1.1573244790561716,0.5072222202163614,-0.5389914346263475,1.3194346078014232,-1.5590800549424801,3.155394483423124,-3.0920883517398305,0.20588781842577739,-0.5620616919916837,-4.809276596205218,0.06307809048325407,1.7676692093413637,0.013609273785548505,-2.5344077117479427,-5.329151385555505,1.2857163061101797,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.900015799999999,1.0,0.0,1.0,0.0,6.379440849680693,0.7502246130516345,0.5211037454001647,0.993403784470951,-0.035212183878619234,0.010293485722790421,-0.10864192218920543,1.139812118703657,-0.12791294400194472,-0.0007267098364273777,0.89285111213443,0.5685676129879932,0.8646429337791354,-0.42300503103292303,0.4990723837027794,-1.1124607652814862,0.30565458404660484,1.1096911855050553,-1.2323022390504133,-0.400951185760136,-0.838424239890464,1.1534213840884722,0.46462622176770635,-0.6288225347041345,1.3321516842014203,-1.3685276346916073,2.977284178646934,-2.2570582506778982,0.04992768578540881,-1.3626325689233145,-4.791541485878783,0.11086326359956705,2.0540516622207883,-0.3801880340298454,-2.507779377380957,-5.344673732868201,0.19983941562302088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.916682499999999,1.0,0.0,1.0,0.0,6.397315989091221,0.7443491621000375,0.5213854641798962,0.9942967636701233,-0.02748813715688135,0.013649931668679555,-0.10213729698892517,1.0928803451476203,-0.11406610407685913,0.037481115412826935,0.9043424624318217,0.3706031350949005,0.7459041078193851,-0.443240241634024,0.5478268956154843,-1.143906293438934,0.31620788384233744,1.081569892045657,-1.3155313318291495,-0.3993981950789653,-0.8021850235568531,1.1446515192426412,0.42362940711837105,-0.7171475820335363,1.3260959349781516,-1.0844504904873404,2.8646458609114758,-1.62100808650429,1.1073791472971533,-2.434839586760626,-4.70189021452387,0.018854873032730184,2.243007499257905,-0.5401585164131258,-2.5960175596263895,-4.946258547453306,-0.7746588184872366,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.933349199999999,1.0,0.0,1.0,0.0,6.414368143297875,0.739145787144048,0.5217849155696063,0.9950100169050491,-0.01941765844768883,0.015247671129162256,-0.09667227795060956,1.0343831669964805,-0.10726095813107833,0.055354097131264934,0.9104828290531094,0.09722026543271772,0.6491032581388098,-0.45915345301253374,0.594560770042886,-1.1664944762321683,0.34256729611511977,1.0285297036237286,-1.3890322263272232,-0.4003226887353868,-0.7636571737147005,1.1354160641974669,0.37809213004565606,-0.7936981493698145,1.3063296719412578,-0.8547903375110975,2.738144116392908,-0.9739783746719176,2.0071856854831727,-4.014685568103869,-3.403281333756096,-0.12556960298780465,2.37422804064814,-0.47804268891333795,-2.657872172891413,-4.246242581396025,-1.4630089974270553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9500158999999995,1.0,0.0,1.0,0.0,6.430512208503616,0.7342555960354044,0.5224602820917238,0.995619063794017,-0.01205298701767527,0.014005201882365564,-0.09165838550897108,0.9853509379035817,-0.11627865560678297,0.08298959353051158,0.8408337498448407,-0.21768819352062882,0.5887453681137089,-0.4717333098704164,0.6390985487048556,-1.1763723041932228,0.38311420717082223,0.9477467721298234,-1.428974269839775,-0.403583856883199,-0.7230439305867123,1.1287167310760173,0.3350334908305124,-0.8586892844962426,1.2773288708633166,-0.6299773468265337,2.5097666969745664,-0.2492261573118352,2.7103777974242322,-5.799626249958214,-1.662926291230986,-0.17094461421251167,2.449871445102534,-0.37931700465227947,-2.3699958653047544,-3.6187453788168225,-2.023204802613414,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9666825999999995,1.0,0.0,1.0,0.0,6.446025626025747,0.7293895988449363,0.5238089253410689,0.9961308531441184,-0.0056483338026092735,0.01046766115013825,-0.08707380667956995,0.9329553327313951,-0.10892235941679385,0.11288036263506557,0.7832457087456727,-0.4388236432376942,0.6086746979525222,-0.4801527399052413,0.678219827259818,-1.1748020314243066,0.43291340338778067,0.8352084419833715,-1.4444632135633422,-0.4060208539387781,-0.6819946288865197,1.1227721387545906,0.29909210986910656,-0.9143232365800672,1.2388893769738238,-0.501866589457211,2.1538760933715366,0.36028796120549755,2.9253522388242192,-7.695694438603156,0.48990505237920196,-0.16119702002937805,2.5035442651038067,-0.3857202433917964,-2.086906782906328,-3.0073611847653257,-2.587075194563896,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9833492999999995,1.0,0.0,1.0,0.0,6.4605851556899845,0.7253171476300355,0.5256514292973777,0.9966444541124694,0.00042290099731176386,0.0056335747287195965,-0.08165730878115186,0.8793638582112322,-0.06508976571091096,0.13312411927666212,0.7426411265664639,-0.6220864489956066,0.6870076241373522,-0.4884622296434294,0.7108945620756464,-1.1643626814671755,0.48062614348844546,0.6912231111300889,-1.412644068766798,-0.40895710163064625,-0.6395922881803011,1.1158593639149412,0.2654697922731826,-0.9589348578124991,1.1910928585728404,-0.5278566082916233,1.814564805695159,1.0659356574709824,2.692307225150685,-8.394529556022299,2.1733862157656265,-0.1864472562457864,2.5739195967994237,-0.3842331531292652,-1.9480863817964296,-2.1834767402253745,-3.0214070712749086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.000016,1.0,0.0,1.0,0.0,6.474641414716378,0.7224701417571359,0.5279151077968,0.9971090224286483,0.005912018843595604,-0.0008872051020256641,-0.0757486520783403,0.8492077453195692,0.011836344188079204,0.14031308010863294,0.6767649533493952,-0.7574738047619315,0.7955133194860332,-0.4977479953720693,0.738705441753977,-1.1392707717795634,0.5226571570466185,0.5553902304806578,-1.3720168614787402,-0.4122357749101214,-0.5961971373985658,1.1099643413680715,0.23415576727013346,-0.9871059401526957,1.1381756065041888,-0.5863238479566149,1.6723371641449052,1.5097342505899964,2.053638477895477,-7.800123971658183,3.046567102390111,-0.17116369136456128,2.6393840097729893,-0.37940668302269553,-1.762158187100807,-1.2078256572206716,-3.2456427954717175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0166827,1.0,0.0,1.0,0.0,6.488614381141354,0.7213762935566908,0.5303576413771295,0.9975619236749143,0.01069568679474827,-0.007898497933250138,-0.0685085720796441,0.8385801946995077,0.06639850453284406,0.13723433934590776,0.6421965735823132,-0.7656034396201292,0.930459754695757,-0.5080063969969064,0.7666392457029542,-1.1140381057985589,0.5490808963275265,0.43121845873321807,-1.3110916289159875,-0.4146625694203777,-0.5516126452289342,1.1032124491870725,0.2067310685592766,-0.9991957935748986,1.0829045490142635,-0.6533547840758899,1.5948953356597997,1.614830194213281,0.9399048972356094,-6.61667123701442,4.102660382763306,-0.15200125770914116,2.6914490209258735,-0.5010242724474693,-1.4770991760401315,-0.29680640862309315,-3.203362034422144,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0333494,1.0,0.0,1.0,0.0,6.502551622219053,0.7207440939851593,0.5329371307072729,0.9979513518408107,0.01558291920103806,-0.014518686012254376,-0.060328100788520904,0.8327987282797786,0.06365095896516462,0.1311768641951955,0.5939466664530816,-0.6655691909186012,1.0391508630648252,-0.5195265317315846,0.7918687259356594,-1.0854429909837744,0.553987382948132,0.33483408146876137,-1.2352612418759379,-0.4173024936338433,-0.5064819906044353,1.093263498884871,0.18491902959551734,-0.9969995068938927,1.0313966584659817,-0.6510372336187474,1.3928619365740564,1.7067293464893978,-0.3579624829863848,-4.820598020274764,5.168742249783489,-0.050991976461797234,2.656912280891131,-0.7252045588143626,-1.1035243760994298,0.473543127677228,-2.8207268830973002,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0500161,1.0,0.0,1.0,0.0,6.516280210131611,0.7199980692987614,0.5355481839642396,0.9982953165306017,0.019637283818868742,-0.01984664643629793,-0.05125376769092811,0.8096437883111424,0.03876002448301381,0.1236530313116731,0.5382385637371001,-0.506927747284499,1.1682311095952254,-0.5297076815200136,0.8130680697795518,-1.0571470138002892,0.5371487896971482,0.2705315366841913,-1.1387998760070546,-0.4163623053685694,-0.46304872540507774,1.0790389155462898,0.16994684912100386,-0.9834109910827825,0.9888801315292279,-0.6458046547301489,1.1550271348895762,1.6745252837374052,-1.2839480197406814,-3.419605347704399,6.157967740695677,0.1069806726438394,2.415128638687536,-0.7453258166757125,-0.7350716901905106,1.0059317697519206,-2.0687251312609454,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0666828,1.0,0.0,1.0,1.0,6.529336330895444,0.7190922810504979,0.538120862792755,0.9985996670977595,0.023699129674438595,-0.023800098098214317,-0.04087311409023596,0.7986467032431299,0.019195530332820364,0.10862447236196822,0.5000950354940881,-0.3116213114645669,1.2918649004124159,-0.5410533966095665,0.8303697074337876,-1.029625369890842,0.511189030026908,0.22084700857159156,-1.0299952399882326,-0.41373646408033715,-0.4259775416396082,1.0684192553072929,0.16041659091772098,-0.963468380840044,0.9624390161756081,-0.6619887861899584,1.001382331081989,1.622788736951792,-0.5327729369521682,-2.477013519211411,4.2302023454768,0.2585912802430203,2.0556244306921703,-0.579813133723944,-0.47137608006187753,1.0589938132216459,-0.6488520497562902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0833495,1.0,0.0,1.0,1.0,6.542655097330309,0.7182675289618125,0.5404062129266806,0.9988536160775138,0.02721309751178755,-0.025892838323419824,-0.029672578186701576,0.8064859217214101,0.00657149106376833,0.060288753584889256,0.5424358809528554,-0.19112569342867136,1.3539609251305225,-0.5517740185255979,0.8464475475744402,-1.0030539477159803,0.5193896562805468,0.18796425424290963,-0.9977928491443382,-0.4077425787877167,-0.39452777400704336,1.0597117724346161,0.15423428169386927,-0.9481111267091401,0.9672516866138816,-0.6828937697510609,1.0398071130558597,1.388827642806806,-0.24789638497666489,-1.6329878106586548,2.9986407198497806,0.2552464124812845,1.7111162948667056,-0.2731754970921854,-0.2837493734354679,0.9193851487040303,0.8475699369415391,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.1000162,1.0,0.0,0.0,1.0,6.556041343015606,0.7175730311986237,0.5414842049509125,0.9989327747393238,0.0320480594835239,-0.0278500640226914,-0.01818261171745843,0.8119555172803101,0.005539692570538331,-0.03207205799021797,0.7419398994258184,-0.16395470590734687,1.3325530898993345,-0.5638165677941865,0.8650300138561238,-0.9833310225421056,0.5029258006679268,0.16641397268378236,-0.9300403494171919,-0.4052282333145335,-0.36894021773629837,1.0593133871925202,0.15095825955324715,-0.9328221479242331,0.9906914039116552,-0.8630566241104861,1.2852466524929984,0.965420035372268,-2.5199344902598932,-0.10190957384952762,3.6644003046652656,-0.0578315313657471,1.1585782507584188,0.6076077237911977,-0.13903835221624972,0.8208008436627885,1.8045701691702403,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.116682899999999,1.0,0.0,0.0,1.0,6.569727562477872,0.7174875550945433,0.5408273923641509,0.9987806458726582,0.03889486417590774,-0.029533092139881437,-0.0072254715825870175,0.8540628380066914,0.0018654363641632168,-0.12628243748606438,0.7981971779107953,-0.06688379274373239,1.316831014223355,-0.5805426301997224,0.8892891883406503,-0.9708732155089024,0.43539167194291767,0.1845672616539538,-0.875645928028809,-0.4096703003553437,-0.3559084217432127,1.0799654037348376,0.14959966068410413,-0.9207510438669909,1.027404145890901,-0.9412684932362801,1.591707265441712,0.5159185266889879,-3.2039927641586963,1.5403643407914367,2.6267012752297862,-0.19938269642909576,0.5433116127009906,1.5541903691223893,-0.15318455745868226,0.6660186531696063,2.143134043992149,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.133349599999999,1.0,0.0,0.0,1.0,6.584708979434827,0.7174839689243965,0.5389632113911474,0.9985452963103592,0.04466405646257347,-0.02992748787707683,0.004093744756647048,0.8931561421291165,-0.009682705925683795,-0.17097795298083698,0.5559747722577749,0.16595477396739702,1.342148542310057,-0.5951922469866288,0.9180870288179985,-0.9661337039245709,0.3961258282631193,0.21775955340111963,-0.8424834651294474,-0.4118743364876831,-0.35082979442549117,1.1111198364426245,0.14585209742565391,-0.9106214817506694,1.0621293482536631,-0.7929961073551357,1.6405850400436217,0.26035582277253605,-2.0703537332593793,1.887643299332107,1.7671603355491545,0.060156226806566127,-0.14782804705212366,2.0601564151759715,-0.07939305879616138,0.7252427234738016,1.892928133414597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.150016299999999,1.0,0.0,0.0,1.0,6.599787216059302,0.7178396691519263,0.5369226465798851,0.9983674559877729,0.04743813363869995,-0.027767202492773403,0.01552510119466865,0.9040294961285162,-0.011220930611252265,-0.14593156577037952,0.2510435326333197,0.44713358426764527,1.3230097049260907,-0.6069758866446341,0.9439754657144404,-0.9621946707260963,0.36637974281068947,0.24748883080791065,-0.8167404656998148,-0.4076650887847097,-0.36083603316681995,1.1486374215844644,0.14695322009802816,-0.8965762380683493,1.090501876533263,-0.6079699361386991,1.424365058985501,0.23047600111905642,-0.992096512637817,2.6039492396615285,-1.1695612530809747,0.49144749785007963,-1.0998190209303014,2.130499165733975,0.189840513554456,1.0387785549888804,1.3333428530995433,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.166682999999999,1.0,0.0,0.0,1.0,6.615057476842591,0.7184315205738844,0.5358082537973214,0.9982127734971168,0.04808834512561128,-0.023491878115083274,0.02658762029403996,0.9335675802447823,-0.0070696333686102175,-0.09506978194890478,-0.11695584679815589,0.6268651743291143,1.293603394779971,-0.6154579520559145,0.9655659590751858,-0.9584511551888689,0.3630558783687579,0.30455803498645323,-0.8814689182028967,-0.3954927204628473,-0.3874905017777693,1.1821366173337013,0.15218012720017002,-0.875995460665803,1.1065741989131714,-0.36063055343878053,1.2191972471377774,0.1604757373235551,-0.5602371962514643,2.2328778082830056,-2.2380443776395675,1.0640703538337393,-2.1467771067784387,1.801478972345974,0.5206986820305014,1.3654790673685329,0.6670466348347999,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.183349699999999,1.0,1.0,0.0,1.0,6.630981417307559,0.7194951276731522,0.5352885203774188,0.9981247594472995,0.04469898088651782,-0.018471324542318077,0.03752033922594159,0.9709553148804277,0.008724899054880969,-0.06786907294202983,-0.45600159435208876,0.7142673673120296,1.2786256721499587,-0.6189969291346303,0.9846154552321827,-0.9568454687835953,0.3477051322531609,0.3219182399425314,-0.8913420941574256,-0.37219600605222813,-0.43239541317790836,1.2086868407612616,0.16430987754562368,-0.851060178124127,1.1127368088308653,-0.07585337114080204,1.0752354490516236,-0.2302495461974672,-0.5796478040467676,1.7574619458721044,-1.4529385378570314,1.2478743408539033,-3.133181466502077,1.3495834564089553,0.8160492225548701,1.6153356544301738,0.19391500743036297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.200016399999999,0.0,1.0,0.0,1.0,6.647363074459147,0.721296082885226,0.5348840550262592,0.9979646203656315,0.039654796556325055,-0.012866264257549305,0.04825528833829949,0.9960913915397072,0.03869765165028442,-0.06773233045336995,-0.6168159305202476,0.6913886267875445,1.2349831505445452,-0.6179864028174993,1.0014072123926032,-0.9661261554120876,0.3437342462573454,0.36314021701298643,-0.9299002996607003,-0.3538968259094278,-0.4919300928732696,1.2271228225195636,0.17938182235528052,-0.8221508311624203,1.1130380454218507,0.2501365303964997,0.8558751608043412,-1.1778083308663223,-0.09396614655410969,2.6186306285291794,-2.4882273340529553,0.7352490500069331,-3.9799218457774654,1.365733973663108,0.9435167136090559,1.782708548840581,0.008339556645185287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2166831,0.0,1.0,0.0,1.0,6.663942689903361,0.7241205362194386,0.5341188459454884,0.9976924368376883,0.033627114774113294,-0.00829772108857257,0.05839663049851727,0.9978617002584582,0.05454538560583887,-0.06951413386713187,-0.6901560603372054,0.5509092091996407,1.181160009693303,-0.6106590281123117,1.0131446843173382,-0.9961058249996948,0.34457292110361415,0.4092061021355459,-0.9742831711743464,-0.34768765536872703,-0.5650597400319469,1.2542113975989635,0.19576049756703978,-0.7916364409822044,1.113014794608342,0.7143703746853688,0.3216524542892615,-2.1341332952762277,-0.0711929101630471,2.679973446390755,-2.3622828833283105,0.11063787221198326,-4.610233645687877,2.0204031205672863,0.9546061723289495,1.8855436146517723,-0.03830686240974878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2333498,0.0,1.0,0.0,1.0,6.680210147266892,0.7271127423729107,0.5333740685595164,0.9972857132677119,0.02749121870152152,-0.005043112772395712,0.0681175896518756,0.983036551339569,0.029722619888507718,-0.05401060151220645,-0.714331635217582,0.3873603757311625,1.134379892434798,-0.594174009369962,1.0121289823124089,-1.0372640741968482,0.3413611445057165,0.452472843890908,-1.0086432199238362,-0.35020888945983686,-0.6456048550784419,1.2944697278986812,0.21120209173999033,-0.7592992516377869,1.1117611474544016,1.2694860059118827,-0.47846716437984077,-2.854131596592011,-0.13569249938027178,2.5845169714873886,-1.9191115906301928,-0.1399133736374975,-4.597403656051215,2.1683614915629423,0.987998650836272,2.008160031136262,-0.09977413716399178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2500165,0.0,1.0,0.0,1.0,6.696281369252952,0.7296435013382373,0.5328272801744763,0.9967706070209627,0.0212314374336219,-0.0031940591820776103,0.07737816894644955,0.9658774184041994,0.0011995682174487377,-0.03744228785544235,-0.7630544601500513,0.22669532382237648,1.1156826134489644,-0.5683427432828485,0.9971957469401992,-1.091243735161535,0.3400498287447718,0.49535684015292364,-1.0382536854694588,-0.3523514438175352,-0.7183068350605645,1.3264902585418277,0.22869385179482557,-0.7246976394003269,1.1096889833845998,1.7562033351301884,-0.9329570905312378,-3.232677821028158,-0.0391721612545067,2.5162630509426216,-1.5061976608145815,-0.16788591089606086,-4.228192397749623,1.3834144442172234,1.11289721788757,2.1238921577504644,-0.15122183208893397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2666832,0.0,1.0,0.0,1.0,6.7120176023354166,0.7321677304258342,0.5324396069649299,0.9961257063647772,0.01447550099606904,-0.0026600789650557677,0.08670040928442223,0.9440188048317426,-0.0015508019996012534,-0.02888840685562761,-0.7725411414214066,0.07973518569942775,1.0803501078468902,-0.5356337811187334,0.9810303504308949,-1.1450202170763082,0.3400554031857555,0.5363484466731988,-1.058849909030833,-0.3558050976820996,-0.7865448835495892,1.3405836349335516,0.24829873986272386,-0.6885027047866276,1.1067204096366483,1.6314476961028652,-1.43080132665287,-3.7026655554728034,0.038454756868326355,2.448607852476263,-1.0819514201565494,-0.40330294635856406,-4.1121945050476185,0.3525416480230638,1.199999655538854,2.1206627958379456,-0.16690416379271827,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2833499,0.0,1.0,0.0,1.0,6.727286821651992,0.7350537232001528,0.5321090293726163,0.9954084186928172,0.008253000826009606,-0.003247063232857504,0.0953070015958587,0.9192785701978619,0.013600304426717114,-0.013248146682111293,-0.6860784437641242,-0.03140214321773732,1.0457421652146963,-0.5139610446495733,0.9495022739983484,-1.214666167188332,0.34133165653736647,0.5769772651426559,-1.0743188049381052,-0.36579490224968375,-0.8553802593751187,1.3382416703120397,0.2686939203127644,-0.6540087381615424,1.1041255001312316,1.4145584909610742,-2.9410292255887707,-3.8937807451527315,0.04992263190933201,2.311735201604838,-0.7615590328369242,-0.5600801826289856,-3.8222562381593463,-0.6627924280897125,1.2120859866358986,2.1055900756506496,-0.23540527895912586,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3000166,0.0,1.0,0.0,1.0,6.7420190741800194,0.7384327687760562,0.5322515274939182,0.9945614522659317,0.003091740215742511,-0.004404814692957586,0.104012289738472,0.9077620741389347,0.02408413008366661,0.004284668015916997,-0.5093100660602456,-0.14890041697832612,1.1095822865021279,-0.4884817371161315,0.8829958468426542,-1.2748131681667823,0.34171949424424203,0.6134064408423735,-1.0842352608959993,-0.37447447444174464,-0.9139536796386499,1.318490509811066,0.2887016868896529,-0.6183162285589342,1.0988735513109922,1.30203237019653,-4.427786893699083,-3.2308532815353463,-0.17277691535553347,2.2431637303366436,-0.4677023599764411,-0.7530122391314489,-3.1297550155912117,-1.5187582797383647,1.1630334448280784,2.159922440710388,-0.2896543838051646,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3166833,0.0,1.0,0.0,1.0,6.756722454305615,0.7420976500653387,0.5325406253909558,0.9934973638030206,-4.309029683813636e-06,-0.006632233065582808,0.11366178593724804,0.8918964167166679,-0.00502529673625321,0.011169873716057115,-0.37132448295258,-0.30394888793720537,1.1438990179454203,-0.47055987884086425,0.8019090823559194,-1.3223614919630624,0.33557241450705433,0.6517495390314594,-1.0899089147841439,-0.390895360421548,-0.9597056352118268,1.2876162930702089,0.30746177934259666,-0.5820111794763667,1.0944703346941005,1.2140943170618128,-5.688870134943494,-1.700788278748498,-0.3364638828576155,2.1999388181106556,-0.01674853627833184,-1.0855069937207524,-2.5100359028241566,-2.0802940673716233,1.1973582014642654,2.156064394514901,-0.02342571719188448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.33335,0.0,1.0,0.0,1.0,6.771011160872461,0.7449833995038324,0.5330158369251022,0.992361763385214,-0.0025940585723733915,-0.010137222513202263,0.12291720038639645,0.8860847559522864,-0.02131794786591007,0.014679740283705344,-0.2486247629800103,-0.48227998645960257,1.19116817371306,-0.4480118456077833,0.6933664630865287,-1.3315062241776174,0.330504009051396,0.6867378814419832,-1.0847935465551795,-0.41065811326623597,-0.9976217104018487,1.2491472355457407,0.32861370676234186,-0.5464472716708112,1.0980926925095482,1.12306903560901,-6.853141440491485,0.33544350983230237,-0.49810371478540705,2.2011474043040136,0.2806354247175928,-1.3204763407835285,-1.937926815168789,-2.4667405239017963,1.2539366056505814,2.2562575363568307,0.2274542527813503,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3500167,0.0,1.0,0.0,1.0,6.785523258460624,0.7486169425631547,0.5336106941801414,0.990949260568908,-0.003320679436809739,-0.01504588815972836,0.1333497555884431,0.9050269056488419,-0.0013362921712413434,0.0039565987731574395,-0.1463482241519315,-0.6022852066011136,1.3018783340399183,-0.4331241694492949,0.5734705774634405,-1.3111800192724183,0.31896892414062644,0.7251212659180868,-1.0805543819178625,-0.43491132647942166,-1.0243033249125741,1.2053914444907807,0.34925974979338975,-0.5068024445139699,1.1020521582837624,0.9677927078140866,-6.940639257852807,1.5987346250784455,-0.677456180229167,2.2031955366594436,0.3807766980133408,-1.4102921977781084,-1.2689689981201304,-2.7128559739312816,1.2644045600282687,2.4049302112264073,0.26078038679840143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3666834,0.0,1.0,0.0,1.0,6.800099953320449,0.7529166658171662,0.5340209970750942,0.9893002437660358,-0.003998134139696274,-0.020336310701064876,0.14441425509600186,0.8953306554417525,-0.008786122320008277,0.0077147757464814115,-0.22721746350171246,-0.6247902571925064,1.2543258686384207,-0.4157520241611332,0.46201135844881797,-1.2782149634260276,0.3079220912133451,0.7601778795436671,-1.0721009645696216,-0.45766794721165277,-1.0399207616037862,1.1587185222242997,0.37076060972358815,-0.46628277096791687,1.106785389454854,1.2215734374790848,-6.426637882250435,2.49426379867872,-0.49810754120228645,1.9184014455022136,0.7967624211527666,-1.1781246025655379,-0.5578960870020035,-3.0138098201872796,1.3791033663448453,2.462838526017278,0.1365651478182844,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3833501,0.0,1.0,0.0,1.0,6.814171141536078,0.7568693603763033,0.535038069113796,0.9877166020591289,-0.005978341339075245,-0.025826564999576005,0.1539907854123893,0.8634337940105715,-0.03459697717512766,0.010822587922172486,-0.3914713293473473,-0.6121912826609391,1.1357841921956302,-0.39240497342842956,0.3592488862792339,-1.228037726365541,0.30236530622671415,0.7890681086615903,-1.0539955814286088,-0.47418222510657976,-1.0428998983390467,1.10493091623055,0.395229953945109,-0.4247076627908256,1.1066043389820484,1.5297420140012856,-5.47004337023081,3.0561053448218636,-0.13036977048649157,1.7078928766880084,1.0040996382261629,-0.8129962398632794,0.030140092617665423,-3.185307139247149,1.5833797118941237,2.4185256984860035,-0.0463016369716529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4000168,0.0,1.0,0.0,1.0,6.827809143653536,0.7605836789712207,0.5358194209380291,0.9860850506735298,-0.009356990298521542,-0.031320229069397486,0.16299620493059389,0.8440190009251798,-0.047573895146704626,-0.011154255574712217,-0.4853596927169389,-0.6178546129398359,1.1145898546630948,-0.36476052171162276,0.2796762147715663,-1.1763445815249425,0.30357642350581066,0.8171077559594592,-1.0386309096887736,-0.4847678760735114,-1.0389160898405245,1.0525414052289188,0.42354003901203974,-0.3856650864500035,1.1052419984690232,1.7119283475033669,-4.121139458495162,3.584185019602815,0.1330676095244874,1.6258456369648224,1.0007920326761275,-0.434365219033261,0.48381337190588286,-2.8572369594817766,1.7535662752570997,2.3596335345765778,-0.08755549225019653,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4166835,0.0,1.0,0.0,1.0,6.841287987961144,0.7644253830848874,0.5363644973057514,0.9842867248152541,-0.012856358867412866,-0.03712574636681898,0.17215120198778466,0.8202005731272304,-0.06162425757096521,-0.0285641631404528,-0.6759469105430393,-0.6112108042944725,1.119681102677587,-0.33534058104976083,0.22187729625343128,-1.1085646534331126,0.3068009020820377,0.8432630716167935,-1.0206357802866024,-0.48866109469870306,-1.0267727536879592,1.0096894937653602,0.453682280024764,-0.3460530543293707,1.1036858167366757,1.5274152441909925,-3.3415009015466524,4.052902125003531,0.3988305758460152,1.5866479393896844,0.9897433521924817,-0.015692269570385657,0.8247341440103069,-2.1706691283276927,2.0026485975781805,2.3430936479014277,-0.17383599633921407,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4333502,0.0,1.0,0.0,1.0,6.854221322743991,0.7679314778035151,0.5368255870830646,0.9823376114718427,-0.019381799238253106,-0.04307473700724333,0.18105725607619202,0.7985562459042448,-0.07628413107666895,-0.04801333403857875,-0.8980193739731674,-0.5968666399201489,1.0901996054950767,-0.31384657841090674,0.16829262861995112,-1.0412475738313498,0.3168708026227162,0.8699961263823113,-1.0056393986328007,-0.4852909527720089,-1.0114248967245714,0.9801856229067205,0.49029512577455225,-0.3075618086470461,1.0994474536686496,0.5196095044358637,-2.9235530705462427,3.8695985367046726,0.6425231082193519,1.545398412818359,0.993777202428981,0.36713251671662483,1.0848425694295598,-1.4916939862652676,2.213536657993527,2.31895981920684,-0.19212000003638627,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4500169,0.0,1.0,1.0,1.0,6.867109551702126,0.7715283978328518,0.5369735354873298,0.9802762549100552,-0.026535574126608605,-0.04926343228328386,0.18954535500760267,0.7906635798332894,-0.07986555362817208,-0.07120019002802613,-1.0914952913267555,-0.5743621630363245,1.0910144749006625,-0.3180202295945984,0.12442533233168515,-0.9795777775697211,0.32821838185755664,0.894776455070633,-0.9875098072871562,-0.4764233196659811,-0.9906112623841359,0.9599662614435855,0.5274669828603255,-0.26875423909182145,1.0972818039274628,0.7275745827232662,-2.2397365758267194,4.0663732990078225,0.9052094168536329,1.4709510831141983,0.9944446691886226,0.6087939234342513,0.9086401872895883,0.0447354733949151,2.4390166132850197,2.303526268200018,-0.16217036720055575,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4666836,0.0,1.0,1.0,1.0,6.879790579192942,0.7752481493825046,0.5369357085759255,0.9779150598361238,-0.03629619044172148,-0.055443764762193995,0.1982188468691186,0.7716264311207983,-0.06396862277703352,-0.08235631154513032,-1.1482209299765909,-0.4664137910011404,1.1067401417960723,-0.289594043815159,0.09363459344328875,-0.9057015261062025,0.3470445101984651,0.9190279272161901,-0.9724911766968687,-0.4649977814046056,-0.9811368299055726,0.9816768083355826,0.5715958421518271,-0.2307774461386276,1.0940417639506066,1.596592694072966,-1.2384785347464402,3.783068595657866,1.0172531209086861,1.3792324802056504,0.8525576240296716,0.7019933473179714,0.6322084144905848,1.5919996331908328,2.410132930471364,2.1929584987376796,-0.24844059943703153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4833503,0.0,1.0,1.0,0.0,6.89180642248678,0.7795098161650863,0.5368697062882406,0.9755171583213826,-0.04474619614627036,-0.059979074110733416,0.2068007795435821,0.7608224081719566,-0.049160113253548826,-0.11181884404301896,-0.9028742889885715,-0.28563637670909936,1.0852247311086116,-0.2648003666859866,0.08314263194156817,-0.8534752388432192,0.36212688703805423,0.94075096302632,-0.9590911629823256,-0.45302349462249225,-0.9695376064205554,1.0130330220165888,0.6078049078848996,-0.19565547626999888,1.0890004340501884,0.9806895670047306,-0.10630906457807154,2.506555255091416,0.820893352032455,1.3802997545389983,0.6263957679421075,0.678638298935209,0.6656845461830911,2.008658315931737,1.8885006032321214,1.943573936592683,-0.1891748699459744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.500017,0.0,1.0,1.0,0.0,6.9039572419291995,0.7838918516149862,0.5359322567566903,0.9732422687002821,-0.05109476407362608,-0.062375046337072575,0.21517008410519484,0.795024383783797,-0.06985751083811056,-0.1600081085210031,-0.45781458908000255,-0.07598887184967634,1.0608067592965542,-0.25690432620236353,0.09009095087008206,-0.8221495171661383,0.37440767665910374,0.9650380110541403,-0.9516112760057472,-0.44237645953087873,-0.9589473006538332,1.0486322194438615,0.6345459881596047,-0.16599151868060907,1.0877359223407495,0.14912014066208348,0.8758932653654999,1.5418844694827252,0.5229394106426499,1.4731512319920184,0.3081599080978715,0.34602388703938336,0.5659251517578734,1.8150696419225674,1.3031384777797481,1.4830343258786083,0.21312701466610404,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5166837,0.0,1.0,1.0,0.0,6.917372464659558,0.7882898669616716,0.5345343586628318,0.9712674963827362,-0.053028329858134285,-0.061913194088647525,0.22359383511315734,0.8200543861635774,-0.08875357035962417,-0.19258946300357765,-0.03887514774240547,0.15111287632641188,1.1120912851239761,-0.2598296853892411,0.11233913251330252,-0.8020789870681637,0.37955823558876994,0.9898561023028027,-0.948819145501736,-0.44148934198625367,-0.9506733969669495,1.0735354644186506,0.6512429440201231,-0.14622089987175688,1.0961046820808595,-0.21152676162314152,1.4406930122123378,1.5960420484467621,0.2712598345975814,1.607378400223372,-0.20173868995290883,0.06066648220552233,0.48906717122871973,1.5071280118833486,0.9196385259867288,0.4415427111247109,1.1779876699807994,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5333504,0.0,1.0,1.0,0.0,6.930539538633575,0.7928145288551984,0.5326239233196188,0.9692099920683359,-0.05345427063496454,-0.05907530195142302,0.23299086017509063,0.8549046887167561,-0.07903074470641164,-0.22201651059470004,0.1855187504698414,0.4633791446786476,1.0856978085034026,-0.26395523235825236,0.1381141473233608,-0.768948009148443,0.38344968922967876,1.018617398220146,-0.9583359124534235,-0.44035423941292917,-0.9426450290083978,1.098869920315174,0.6652006670017307,-0.15127339887360464,1.1270022565392874,-0.255508609470045,1.6962253910157192,1.6642927626873012,0.14285289712203864,1.6380100753260174,-0.5616439634140306,0.1597357767563469,0.4568619792707153,1.4627847325228567,0.23099193856293068,-0.8329500714849707,1.9377707900539574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5500171,0.0,1.0,1.0,0.0,6.944781479413115,0.798443609713786,0.5301266585189853,0.9676703368829277,-0.05293794400508707,-0.0527318636518015,0.2408963340468332,0.9365995924728271,-0.054900135569509234,-0.2103218170683101,0.2980888306531104,0.7510891655602911,1.0533317327492753,-0.2683466560721499,0.1688800919621859,-0.7466024506924028,0.3843200083496977,1.044456547347675,-0.9675406483918012,-0.43616480544532366,-0.9354446338671271,1.122295053021728,0.6589426907050167,-0.173985957784594,1.1606971709340441,-1.3014467825087168,3.0974509429477206,-2.431163503412479,-0.024203796441844613,1.4182121802667285,-0.5738832618369353,0.2345775773054921,0.6418045947638867,1.1166612563518994,-0.9577238971464869,-1.4970408153013042,1.4081124826306892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5666838,0.0,1.0,1.0,0.0,6.959699747170762,0.805396618308539,0.5283153114179783,0.9658859423798262,-0.052594410948839286,-0.0448368691842267,0.2495752980800312,1.0040225356587702,-0.06331771284202042,-0.17379319117805725,0.2994323086720099,0.8826334647961434,1.0754220474306533,-0.3073368785383284,0.24136271858501435,-0.8499869546730925,0.3826428944013642,1.065891232109849,-0.9774653927735388,-0.4325349711975743,-0.9212514997292952,1.1360920366376543,0.633276473248588,-0.20117485918636913,1.1739394331678092,-1.590769005356652,3.0345175188520583,-4.382498333561648,-0.11433047450759631,1.4048514908187812,-0.8151728932514076,0.26531127211722905,0.9545150677800802,0.6502718023960066,-1.6940472014495844,-2.3929634201695054,0.9191815281664161,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5833505,1.0,0.0,1.0,0.0,6.975606631476721,0.8124419620584267,0.5266707222454803,0.9641178635196613,-0.05260254461620673,-0.036338250782097896,0.257661112844529,1.0486708405774183,-0.08414887104100738,-0.14878072426031755,0.4340992092776626,0.9375439192027293,0.9914447061902227,-0.32137239563530534,0.2700308782250891,-0.8926860206443467,0.3805089849107462,1.0912850240317338,-0.9947131325117077,-0.4273210786873312,-0.9036274013067865,1.143970823119715,0.6024743377202171,-0.2537515646544722,1.1913366164850265,-1.2711526062959322,2.286166593211376,-3.2138770028879438,-0.31128100815385096,1.51448010435791,-1.6651856852108187,0.1770837817357697,1.1701282163570819,0.2954130140074619,-2.004307174511591,-3.7268276540258474,1.3305143040846894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6000172,1.0,0.0,1.0,0.0,6.991786625988217,0.8200702070933474,0.5252352710258696,0.9625786552356161,-0.05025951026104395,-0.027019272838913918,0.26492692012773883,1.070738997005238,-0.10417415527558122,-0.13343442266497835,0.507463046709831,0.8925290692643248,0.891828907413613,-0.34970871682503324,0.31756842410316644,-0.9571164023611575,0.3722668400441686,1.116374003220453,-1.0329716932929451,-0.4266321666674632,-0.8822471478421781,1.1459391567987707,0.5664661004777234,-0.3254026961090743,1.2182899986715858,-1.4628417024712677,2.8832373417881345,-3.6571085451298,-0.4010429180091208,1.1370008391587991,-2.98879118856036,0.10055789732343882,1.350506332162385,0.13198725193065702,-2.014547468145124,-4.610006475175545,1.823108472361809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6166839,1.0,0.0,1.0,0.0,7.00834723105067,0.8274082464274078,0.5235436319045337,0.9610233680063809,-0.048801460568116545,-0.01903750615395949,0.2714591625853305,1.0864268982801175,-0.13929554157536306,-0.11500169377561271,0.31841177406324717,0.7450682904933303,0.783451198964641,-0.3701338832404611,0.3661389818338497,-1.0145898826225763,0.36714086090758097,1.1291851278037497,-1.0943397047164656,-0.4239691420726901,-0.8586104335342849,1.1483704069832203,0.5353226211455484,-0.4074187544940887,1.2521070204376517,-0.9562721799122013,3.018110336305144,-3.288648117874042,0.08470611449296421,0.18815072150944612,-4.282030185203236,0.2856438620134353,1.572475149990943,0.09803827388106758,-1.8434115750842406,-5.072739226288069,2.072497499529666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6333506,1.0,0.0,1.0,0.0,7.025293235560507,0.8347758609473935,0.5222720392467264,0.9595474173794886,-0.048774796996189314,-0.013016434608995944,0.27698437755296573,1.0990388662809691,-0.16118159202215543,-0.06666228049417489,0.21404957830433002,0.5405161439504889,0.6390466341838307,-0.3815845199069186,0.4181723031873603,-1.0667382255335,0.3750903828410084,1.122645706480816,-1.1757063182683987,-0.41711068555742453,-0.82983120467747,1.1492071057973579,0.5050189250808104,-0.494494341834625,1.287373386822408,-0.5182297549291748,3.054221763654532,-2.8175554139634076,0.45949490068653576,-0.8956174408283523,-4.081282833456742,0.4305640432213927,1.872560657566528,-0.041097081040418156,-1.7972604007814308,-5.36871233791008,1.9358012148871917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6500173,1.0,0.0,1.0,0.0,7.042312915152053,0.8422135360342943,0.5217997916497039,0.9583810707888577,-0.04800973544374217,-0.008881729403767812,0.2812861591671774,1.0959415651091216,-0.1693236110222916,-0.02703937401989576,0.26551211318977047,0.3083619572499748,0.46920108660098486,-0.38740824295341725,0.46794657757045166,-1.1085085842583842,0.38245738823012554,1.099331153401642,-1.2303827379172125,-0.4096169785943741,-0.7961916201113568,1.1470005015420677,0.47541382130214066,-0.5863761903385806,1.3166338566539724,-0.22947056330835064,2.9475496137850166,-2.162431758138994,0.041588857801508006,-1.351730154122029,-3.3466590593205905,0.3752531039103418,2.064542354824268,-0.14268931155477102,-1.6467786443185588,-5.537924906590262,1.5080641354517061,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.666684,1.0,0.0,1.0,0.0,7.059116010196835,0.8496998655378954,0.5215578561948526,0.9576165743521621,-0.04604735023218684,-0.006464486535173692,0.28426809261058655,1.0710155189094814,-0.17764516685923604,-0.003734139784970947,0.3586102051879003,0.06667379574967788,0.3025346783067182,-0.3892335539819012,0.5164241534835018,-1.1388194283002504,0.37647668087364916,1.0775879445614047,-1.2872618433563556,-0.40460222374353955,-0.7610129885471707,1.144450785899578,0.4501261938182821,-0.6790922079159608,1.3376422918750739,-0.07757522069237244,2.8664962094342115,-1.4291006600994338,0.38594011615045076,-1.460950204459907,-3.8959762162431044,0.20334562713684476,2.2281840637867036,-0.15677210436855846,-1.4991097502941346,-5.471376796848329,0.9145711880992794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6833507,1.0,0.0,1.0,0.0,7.0754658921569415,0.8567216973788174,0.5217272309843621,0.9572340694490378,-0.042632087339072824,-0.00587954568061732,0.286095914612107,1.030243661402821,-0.1784212863596049,0.010339914228158345,0.38332697323510945,-0.13792804823618438,0.22719016411926435,-0.3899940888148444,0.563496642318006,-1.1561453682017426,0.395322084497815,1.050632715856298,-1.3602488715237304,-0.4028387774667708,-0.7219186694395291,1.1417747542783088,0.42544339635168615,-0.7687557816586447,1.3471196238953609,-0.08434940955170193,2.7083049052743338,-0.8054653308737318,1.301843232048054,-2.665392246604944,-4.020416243662274,0.11742460354031448,2.230356700247958,-0.12419616831575449,-1.3522479760285073,-5.14207397018087,0.22084679136331065,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7000174,1.0,0.0,1.0,0.0,7.091075636180245,0.8636014725870866,0.5219555021780544,0.9567934732535706,-0.03929373788095895,-0.006676274685513616,0.2880237473873208,0.9960701013071034,-0.17440015803524095,0.008344609119018201,0.3543889007131234,-0.277667817256514,0.1545181861303795,-0.3920452065902519,0.6067011642129733,-1.1656683263603969,0.41987154206479976,0.9887413586484235,-1.4212759861728477,-0.4006880624638888,-0.6866676165151254,1.1403109053426417,0.40505117113413347,-0.8504950163935878,1.3450038663103037,-0.049918668775315325,2.56089493148332,-0.4545108735587041,1.9381032682255366,-5.164836271455926,-2.614169545422438,-0.09158853403674216,2.434230657628005,-0.17233335595380533,-0.9249434640527049,-4.6929503387030245,-0.4697601819990413,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7166841,1.0,0.0,1.0,0.0,7.106347724393359,0.8702278745615614,0.5221366193845125,0.956693905148183,-0.03566205949470022,-0.008500325226583297,0.28877800095567935,0.9729076073131789,-0.15160293013564358,0.005035460594302717,0.3363509356284216,-0.36549931975713873,0.06097514509411557,-0.39165804776859947,0.6488599774271121,-1.1712957609544243,0.4599256559788841,0.8784711624853491,-1.4473880306491147,-0.40589173470723117,-0.6407774852365518,1.1360302975909582,0.3946118858870317,-0.925187772478768,1.331460919844714,0.03061481004837291,2.3948727426870837,-0.19166948494743608,2.4474914359292366,-7.102455137888331,-0.9691774679135386,-0.18773501721710725,2.5566054291672846,-0.21230866907750426,-0.590305508299724,-4.013100951310905,-1.3190460180838934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7333508,1.0,0.0,1.0,0.0,7.12087536145041,0.8773532045864164,0.5223520310758452,0.9566484309560062,-0.03217925216554598,-0.010848133766571125,0.2892586961065483,0.9655323992061947,-0.11541945975134194,-0.0030851120547498896,0.34365156489507787,-0.41673233860454983,-0.03125367249216979,-0.39102471088098545,0.6865304152940589,-1.1720573219699437,0.5014547530952034,0.7519923805551366,-1.4535819663817968,-0.40694590888679355,-0.6014472651025207,1.1332339355528136,0.38537428150377545,-0.9842653156440148,1.301035577771106,0.027742372176977836,2.30904319321178,0.143139970964068,2.144748565587365,-8.345649952984859,0.8054142094838418,-0.174489866959845,2.4284421788466006,-0.19350064459683974,-0.3653775912114982,-3.050957281838366,-2.266822066322612,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7500175,1.0,0.0,1.0,0.0,7.135269454956027,0.8848612241507743,0.5223638950775281,0.9569508291851841,-0.028165020377051254,-0.01350023213650548,0.2885646996450006,0.9711716144227978,-0.07761009825244164,0.01016035192799919,0.3545980438117882,-0.4618777535483769,-0.06402098280374141,-0.3907333001798754,0.7258282378037176,-1.1665244190462907,0.5314174178150339,0.6002822743425236,-1.420540836638706,-0.41170807523855046,-0.5598292507121865,1.129580263204354,0.38243260848814237,-1.026886551937199,1.2559000331791559,0.07092018805182677,2.195176217458074,0.353854015970956,1.1920238989755552,-8.957799601737328,2.8921807037295504,-0.27507866959476873,2.599077015295854,-0.38301367563005645,-6.130238680894512e-05,-2.025577813025105,-2.99692808864869,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7666842,1.0,0.0,1.0,0.0,7.149257273059515,0.8931201767659142,0.5231598921085832,0.9570190656779843,-0.024290096355363777,-0.01654204440359322,0.28853225108267305,0.987031520472373,-0.04147986658854841,0.0368406499984337,0.3572985434080256,-0.47361336683026223,-0.048996270368801165,-0.3886606998845787,0.7597031022210758,-1.1602621645139775,0.5411889625293151,0.4533984633105856,-1.3571757501120982,-0.4161152162118638,-0.5148111913208578,1.1204667874975667,0.385372238086795,-1.0517847111167058,1.2011377750209438,0.040365248005449106,2.0310987640567193,0.6684264712716628,-0.048463512813273435,-7.871806849675316,4.415087314200167,-0.31339532378959606,2.76156893159728,-0.6890390496400579,0.2788149964161495,-1.2226304563442503,-3.282783549044451,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7833509,1.0,0.0,1.0,0.0,7.163380859732438,0.9019522452199963,0.5242478249971694,0.9571997128428495,-0.020173600934147707,-0.019354440035703267,0.28807488819718474,1.005574755431534,-0.006518924483976951,0.04647717275853304,0.43867509432834106,-0.4412540992745645,-0.05311538226937999,-0.38938778922201056,0.7935316653455259,-1.1442434921088038,0.529801964157024,0.3378881878995564,-1.2733709651595462,-0.4221546069245586,-0.4677767688876817,1.106612248947082,0.39172646028968044,-1.0676409819907045,1.1464736960254376,-0.1533789217173688,1.9404485684385266,0.9487816367068544,-1.125039651609688,-5.783980720930707,5.457931339121691,-0.4184176762085237,2.8511588546545417,-0.9710899898708252,0.42411099587492707,-0.6026489443605948,-3.103100744982044,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8000176,1.0,0.0,1.0,0.0,7.177232315419412,0.9114933843460955,0.5255698920214248,0.9572754307159009,-0.01515676881972714,-0.021495121544216726,0.2879791344115595,1.0193130945631022,0.03903816476310468,0.04729581882033666,0.5240321729293413,-0.39428094689351295,-0.013864667002897544,-0.3937733408337524,0.8243848505322646,-1.1286360467049732,0.5036875658063488,0.26059872034751397,-1.1752443416126193,-0.430062499979993,-0.41977237275511614,1.0880970564292065,0.3995092995566923,-1.0718730494386552,1.0977008766481593,-0.3612831956001161,1.8337058997866231,1.0311299552045763,-1.5355909290817156,-3.709561653561136,6.314029635372082,-0.5026590984139514,2.9743340998506906,-1.2599057066911596,0.5111642723530312,-0.14453839435930638,-2.3978568289332487,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8166843,1.0,0.0,1.0,0.0,7.190895791737433,0.9218187943654319,0.5268699734397447,0.9572562868249508,-0.009916065775040986,-0.023134759150977048,0.2881438111302739,1.028833097605382,0.08270910359484723,0.04222153831930516,0.6514115626027839,-0.33663720052135127,0.025919718607065538,-0.40143058649422747,0.8546553175854733,-1.1098724248599876,0.4786154974815715,0.2142358854767416,-1.0629028897118344,-0.4389099437156302,-0.3686321006037187,1.064615308063663,0.408765303445733,-1.072458938105241,1.066544975203874,-0.5919302818781067,1.7007920441958884,1.1915679460007078,-0.668808946927548,-2.312272357676498,4.2070760412776105,-0.6024011349463546,2.9862287313654248,-1.4543138407803073,0.47131088477473937,0.41960116173389767,-1.6258428127430589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.833351,1.0,0.0,1.0,0.0,7.204205368157186,0.9327344347745687,0.5282093885564103,0.9571187294639368,-0.003158119103656568,-0.023735029995870665,0.28870471479378634,1.0317776780763057,0.0887918839690558,0.039394892607136606,0.8559994975413384,-0.31147756172106955,0.055631897833514,-0.4135043896917081,0.8810780320582638,-1.0889170357337532,0.48139388965483404,0.1835228209401402,-1.0350081930982962,-0.45014257797161383,-0.3202312159610199,1.0396198314489402,0.4152196938032426,-1.0578863160741145,1.0435060078338698,-0.775565635977554,1.577880142427967,1.315828506657807,0.6188894483536704,-1.6994650107733784,2.0633641682452746,-0.8484730355122548,2.8279374887810045,-1.3113734482501358,0.2971888673233521,1.2127508642445184,-1.0870168365112787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8500177,1.0,0.0,1.0,1.0,7.217819105197186,0.9432872594183115,0.5296230746742612,0.9568978345286367,0.00521519494672815,-0.023981379890462857,0.28938595237955633,1.0354206096599392,0.05824819739089199,0.02259182604687287,1.036501608967429,-0.2589883595064816,0.06238317732364981,-0.42728282606452167,0.9072514275250817,-1.0660113869161603,0.49924518701932374,0.15758693848662828,-0.9941239465460474,-0.4671924347975744,-0.27436732911518597,1.0209027723637618,0.4186716188357692,-1.0320338284470327,1.030311008185709,-0.9040378111485862,1.5105483621839961,1.3190486466464197,-1.122026777759377,-0.9199995316858809,3.2644899517890833,-1.1327516049857578,2.5341553418209823,-0.9407407221329465,0.17432701577712392,1.3169222548822306,0.21173836813049815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8666844,1.0,0.0,0.0,1.0,7.2317909590074265,0.9534389262285831,0.5306421912334771,0.956611753052879,0.014595278639315963,-0.022871209804296595,0.29009970617811065,1.0290673305507603,0.04174914702472904,-0.024924095571876644,1.0824785917732103,-0.17539146498977382,0.10390019863568682,-0.4436390436658484,0.9314297448342879,-1.0449486595756294,0.4439929222610696,0.15285610855064205,-0.9261916437393299,-0.4879010403212461,-0.23575920228996436,1.0082617446617939,0.42103060595094777,-1.0139888197832232,1.050563967554111,-0.9713276356831538,1.4202144298036325,1.239885388432645,-3.036342199808161,0.606898409037723,3.2984470613801737,-1.1986939303988,2.0305383814349063,-0.40249455107394183,-0.2986845244887046,0.9190026618292334,1.3334014954983684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8833511,1.0,0.0,0.0,1.0,7.245567907798125,0.9634940566324912,0.5306053557535064,0.9560695241611237,0.023282577092473566,-0.021576021297470684,0.29141630338611263,1.0222070102957375,0.059454392936337086,-0.09167340452597687,1.0235388480457068,-0.16604605512653126,0.11890038353792912,-0.4596604786758025,0.9545920031994981,-1.0246817913093795,0.3980335779362384,0.1778169259144463,-0.8841754912702375,-0.5071489790571297,-0.20668258103146367,1.0074862604949937,0.4087154481071774,-1.0014003451192142,1.0747578135957543,-1.059189348249399,1.512749634946772,1.0935348493553443,-2.0544788288280027,1.5694490435549304,2.29095800657541,-1.272030704789984,1.4651911752659992,0.45196180727441615,-0.8169306266096774,0.8898365536934676,1.862888602984457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9000178,1.0,0.0,0.0,1.0,7.2590238558165705,0.9742090253646959,0.5295239986663142,0.9555814092130014,0.031668347458876714,-0.020588705070963876,0.29229675222146967,1.0295783398971698,0.08566667771503372,-0.167612783198776,0.8735719153888504,-0.14270582895521744,0.08914546463715012,-0.4789454258867849,0.9818548335158226,-1.008497425028128,0.3755101576682143,0.20517118129907597,-0.8498262241229492,-0.5303021486162925,-0.1869193987683527,1.0233271683683949,0.39379953060191675,-0.9843275420043374,1.112660378512833,-1.1123762606026966,1.7089794996424568,0.8294933359724216,-1.1470544280346298,2.3732579500274835,0.7041214419347959,-1.350282772351755,0.6855987939924463,1.7806076464711071,-0.6654768572122999,0.864451612467353,2.179432993492069,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9166845,1.0,0.0,0.0,1.0,7.272511340058854,0.9853882937627358,0.5271584216477921,0.9551400759730692,0.03786033307696486,-0.019641658404119966,0.2930669474788942,1.0349572026730136,0.09753636372964258,-0.21322047933607471,0.569624719349529,0.01592564757007231,0.13542103676326242,-0.49673976152097643,1.01155810045288,-0.9970319581440764,0.35979835386478887,0.2569256824658924,-0.8607047295976482,-0.5521584948210397,-0.18382924219179586,1.0668399674178737,0.38653284183497694,-0.9725852337401949,1.1474057253410228,-1.0171122541992343,1.8020278967284957,0.44510738889951795,-0.4562484593944275,3.1092837619428093,-1.7078564091490467,-0.8756291384536956,-0.48473158861486176,2.941486319631571,-0.4249615266107691,0.8312223097490004,1.9845738720768733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9333512,1.0,0.0,0.0,1.0,7.2858537815504985,0.9967507067927269,0.5247001981779682,0.9545749457855546,0.0406144134848858,-0.01764666608921662,0.294662073351356,1.054609836491375,0.10193956236058804,-0.1755972513012754,0.06452785979730129,0.270709481613659,0.20613669206169064,-0.5128492355009097,1.0419225502086322,-0.9936604823909848,0.36030184527183606,0.3088141806494204,-0.906754884951678,-0.559489844940025,-0.20307715070428733,1.1213769084552019,0.37963411805078934,-0.95662007626455,1.1788129732203203,-0.629262558275193,1.5824021127330434,-0.10978405166832164,-0.23963370182259236,2.7431620754546557,-2.2059932246863303,0.35128701278096647,-1.4511580888251887,2.8089025068574123,-0.18953065923872578,1.2157012550182593,1.4391613126282983,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9500179,0.0,1.0,0.0,1.0,7.299679354029019,1.0084252209857334,0.523582003372009,0.9541571589091926,0.037496420147621085,-0.015167965899132056,0.29656039416775404,1.0828407281364005,0.11373471718509087,-0.10003890679125998,-0.4393561062530977,0.4847462574647753,0.19714066665927643,-0.5177152220809867,1.0643049430374556,-1.0006914338519572,0.35181054782845567,0.34836460119185264,-0.9342379841534075,-0.5404489043092067,-0.2322012752298414,1.1604702382399545,0.3802151405583088,-0.9320617775261693,1.195377865039387,-0.023756712870585905,0.989434930648494,-0.8106522094263121,0.10810591621495104,2.669253346045731,-2.2187846114679246,1.5640872798524994,-2.245024616472837,2.014565034605296,0.09723633438919718,1.6298195370269,0.6111214004546944,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.966684599999999,0.0,1.0,0.0,1.0,7.313455518784174,1.0205190374170887,0.5234611581627887,0.9539809343359652,0.03117902837959782,-0.012240323296571019,0.2979906367629335,1.097395157524625,0.13744090578031642,-0.062302194054403015,-0.6944003142464351,0.57517973872013,0.11784779694128766,-0.51364112751371,1.0749037805259107,-1.0206822767486758,0.3639053830193955,0.39778947013450117,-0.9807145199195829,-0.5073534980057897,-0.277911454255023,1.188529210579714,0.3828753356795182,-0.9022926497090176,1.1991837273102368,0.4268541075432299,0.322424589122188,-1.671560407624027,0.7184753764210855,2.8900505763142768,-2.6976880555730047,2.0262340380612827,-3.328276172205724,1.6500729215035872,0.18750397870923702,1.8716607573758828,0.09952737754013156,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.983351299999999,0.0,1.0,0.0,1.0,7.327153479797446,1.0330925035640546,0.5232830588665739,0.9540413425236038,0.023572674764457048,-0.009539986363732437,0.29859409642588136,1.1174017453086094,0.18121497447915103,-0.06517865356405624,-0.8298468687975812,0.5478460536638494,0.07910134405346592,-0.5034867233726052,1.0750524508365011,-1.056410225543452,0.3757597749408503,0.44469981307236695,-1.0241610991850447,-0.4729076346248947,-0.3431440361884437,1.2154727789616022,0.3864652856822153,-0.869672960836256,1.1986954509258831,0.7316948207388487,-0.25966268327083214,-3.2171674234643626,0.5761605409502268,2.9107446776054213,-2.4735226411599056,1.995924915488991,-4.37006942042765,2.0233838604379195,0.23663765609167783,1.9786368762855107,-0.05649115372031106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.000017999999999,0.0,1.0,0.0,1.0,7.340618518333833,1.046790132042174,0.52273096384051,0.95399417035845,0.015245904021427179,-0.00768919661922881,0.29933854009801847,1.1436707410620401,0.2091698385301961,-0.06620697467842096,-0.9305995844611247,0.45284936136126497,0.03959219299091107,-0.4892512513760937,1.0662483404393708,-1.1279214053419828,0.3831107727951058,0.4948144867709937,-1.0631654395264225,-0.4408225344278289,-0.423580726273906,1.2559754741532354,0.39076327332508454,-0.8363379552570421,1.1973006850868162,0.9895043930105005,-0.9973366201465669,-3.9671362137257598,0.5659607792985623,2.9909474094933612,-2.2747231515070623,1.8098869147767012,-4.940718593034858,2.5637613658849037,0.2856391251147284,2.135514509702235,-0.12117194057514817,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.016684699999999,0.0,1.0,0.0,1.0,7.354468049110065,1.0606505638641341,0.5221554126093844,0.9541334857402816,0.0065112793039845095,-0.007000083066794649,0.29922883127797595,1.1541392066210387,0.22410013218330538,-0.052959154942368865,-0.9793880862490609,0.32922144140819243,0.06509705144622674,-0.47050317763862903,1.0418078303425076,-1.1886483638100582,0.394625171981521,0.544398259451973,-1.0999853558834902,-0.412577950139877,-0.5078349853375118,1.30093166207519,0.39598660889531456,-0.7984890014785475,1.1946563781619155,1.1186993025242322,-1.6063354797509652,-4.360761909066989,0.6191137725766852,2.9655956368403547,-1.9889699827176797,1.7685467204763567,-5.1081042248488595,2.4481690373979164,0.27272863167091643,2.369532497893863,-0.22521344049616734,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.033351399999999,0.0,1.0,0.0,1.0,7.367947415195426,1.0749151281232645,0.5216913151584366,0.953813272302053,-0.001977106478823556,-0.007334234746566094,0.30030408194212654,1.1454505230870995,0.22354958897747462,-0.02271284485267583,-0.9471066863260937,0.18784332628324685,0.18771147678033015,-0.45196120004533247,1.01270371735864,-1.2732804263616764,0.4037479398219135,0.593667872372048,-1.129464571548344,-0.38187085917550234,-0.593851207642483,1.337581271944435,0.39985424589602386,-0.7573533806917468,1.1897935553893813,1.0675580518753394,-2.9964112732704113,-4.586074664573389,0.4734753854764186,2.9059472552348327,-1.440291262961071,1.856582421929637,-5.4672367436597495,1.993182140332568,0.27996587984734883,2.5733871919772895,-0.4108407789132512,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.050018099999999,0.0,1.0,0.0,1.0,7.381501930800939,1.0886328498676805,0.5218263351891458,0.9531882695255923,-0.009506807259622855,-0.008740435291057311,0.3021015528683328,1.1113783211988755,0.19545552785468234,0.01970221635065664,-0.8467869900554696,0.029551652796806605,0.25074971668628,-0.4349178380722476,0.9419272548060756,-1.3415178250341488,0.4104077163957606,0.6412633616896177,-1.1479951606682768,-0.35069174563672767,-0.6900765746086197,1.3673711996317517,0.4053188235546182,-0.7127092568534917,1.1809616581420885,0.659744099490591,-5.397221025975979,-3.2797279232168473,0.23946727732932785,2.7270163929042166,-0.742861611027479,1.7734996721620826,-5.499424647797546,1.030838988434251,0.33901891342955587,2.7365093178307816,-0.6300846641575358,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.066684799999999,0.0,1.0,0.0,1.0,7.3944598770001555,1.1015900323620647,0.5225998403115668,0.9524251828484774,-0.015613497435333364,-0.0110837015365454,0.3041704149553831,1.062783716128458,0.1843037259318725,0.04380989300021183,-0.7238702482759846,-0.11007235279280342,0.30408801493188586,-0.4299696860793728,0.8327959900113723,-1.3826049091174328,0.4117301983640429,0.6845686006032814,-1.1542266747733674,-0.3227540852034548,-0.7771657291973777,1.3719426402815094,0.4111548989449366,-0.6661362209967663,1.1687906912451524,0.2353442962733826,-7.514411833219191,-1.4778341711507992,0.036962940815277075,2.4936524241613887,-0.30853380871636205,1.5778745518398614,-5.063928714141054,-0.05633790916119632,0.3836605506288547,2.781543217050186,-0.7515259826889784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.0833515,0.0,1.0,0.0,1.0,7.406762086615373,1.1142082945271177,0.5234729147440031,0.9514392491819362,-0.02049556174123658,-0.014071690027410683,0.30683101962610826,1.0357583781757924,0.19622008179276385,0.06487840174690537,-0.5916728919770013,-0.281212489412233,0.46793710411007444,-0.4270730125068484,0.691446359404647,-1.390779062594787,0.4116398168871326,0.724385275405159,-1.1582796415277428,-0.29809582205042884,-0.8588745360085691,1.3654932655705179,0.41810753415295004,-0.6199909641822711,1.1559107419507237,0.12979351658086985,-9.055168383517394,0.7511012355963543,-0.17652894462928925,2.4120799375998834,-0.07544477391111941,1.3583026165576921,-4.408669911282417,-1.0311843740931002,0.425063557959961,2.8156347071639964,-0.7916349118091187,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1000182,0.0,1.0,0.0,1.0,7.418570563658715,1.1271372984319405,0.5249384520062202,0.9497545234743864,-0.023670082173049885,-0.01839324920561811,0.31155699435821105,1.0287351980595443,0.1953504577874431,0.08427180755384031,-0.4344360397166646,-0.4463257990724841,0.6087088795725553,-0.42564322687377604,0.5309564402162336,-1.3575681511908053,0.40584588844113695,0.7649714259952733,-1.1567415056000563,-0.2774772407646906,-0.924121686818119,1.3375697590661144,0.4253237125478392,-0.5722815430489859,1.1424028080758544,0.016226685236704414,-9.490734473716554,2.7889439849481774,-0.4050752727689494,2.2766013257701334,0.36972922632313404,1.071754785118876,-3.4469058265373307,-2.201606382209186,0.4510646793292237,2.9362766965000158,-0.8506155077293915,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1166849,0.0,1.0,0.0,1.0,7.430385417405956,1.1398662449026216,0.5266018306503244,0.9479683865523938,-0.025240288297017414,-0.023143515987375563,0.31651736699852173,1.0312044442561727,0.15482036952167477,0.08196822928839217,-0.24298183789303887,-0.5385088772695069,0.5628059101889714,-0.42653212191717926,0.37508791089846366,-1.2978140771669153,0.3981372807898161,0.8002721380375851,-1.1459553093350232,-0.2623705910961473,-0.9737716266868686,1.2921062393897862,0.4331430535349028,-0.5221148785471574,1.1275568349853768,0.20941313403566758,-8.707151128356381,4.146185026061354,-0.5073960593529164,2.045404131732249,0.860505424678959,0.751566214009195,-2.407269527642538,-3.1992465190024495,0.3901397173337226,3.0108425446404454,-0.7927878810462727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1333516,0.0,1.0,0.0,1.0,7.442765554338532,1.1520157239158133,0.5283008013625816,0.9464781822291235,-0.024880824759843233,-0.027937828761826537,0.3205923780248043,1.0396424945406877,0.1014316093015748,0.07199743039785242,-0.14104564300357636,-0.5555178559113739,0.49932778346606776,-0.4186627751117115,0.24071748879427896,-1.2193617072430918,0.38893265263630244,0.8331517000799571,-1.1280579340770627,-0.2524249835266365,-1.0043641648908388,1.2309279951495982,0.4383283958016111,-0.4719199241714681,1.1159764925217865,0.6569217421281363,-6.737032327824483,4.691990399600441,-0.4918166655793247,1.9195278790416723,1.1732220912043145,0.550994500398342,-1.3192208355437935,-4.030949042352819,0.4052372281775303,2.964483979631837,-0.6433329252905751,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1500183,0.0,1.0,0.0,1.0,7.4556501695703545,1.163697211246626,0.5300550916191379,0.9449851717305996,-0.02473024508208667,-0.03245406175432695,0.3245584293515045,1.0440618748745982,0.061614332785452086,0.0708397502763487,-0.13668886063783786,-0.4728502745030503,0.4796790040452287,-0.40463468671812525,0.15051971750215903,-1.141414084380874,0.3817433591493942,0.8642565286408328,-1.1068478280800733,-0.2440040710165692,-1.017745742486384,1.1577410025814228,0.4466509881566357,-0.42329854826049756,1.106112361253496,1.0683443691333627,-4.333627064458919,5.114236220544489,-0.36307613403365774,1.7400918376187706,1.297514976495682,0.4215589194618088,-0.43482708972754114,-4.424756830817342,0.5262659784063048,2.930325997935175,-0.7384633987781986,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.166685,0.0,1.0,0.0,1.0,7.468723119743226,1.1750986530326155,0.5320910012691837,0.943576434139523,-0.024738637658268135,-0.03592756172583961,0.32826928435629105,1.0306681455947315,0.0297377087185125,0.06978461157873203,-0.1894805474385861,-0.29987538834716404,0.39446803805581643,-0.3830512249176415,0.096262964403844,-1.048886825609194,0.3768300906301049,0.8911548773400386,-1.0848073483595415,-0.23837299144064825,-1.0188584302035628,1.0834358058052314,0.4558706301662198,-0.37424219555189575,1.0913609966649533,1.051885225069184,-3.0716853079217747,5.184011866558784,-0.11804250515588323,1.5201892485720276,1.2295466179041448,0.20872613677958982,0.22707811054509852,-4.00880489890188,0.5878168477995025,2.795894848131603,-1.0059098724142739,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1833517,0.0,1.0,0.0,1.0,7.481704953000556,1.1858715636329344,0.534074080269278,0.9425772643554942,-0.02630669174020914,-0.038050452973748906,0.33076913658667007,1.0175378922849612,0.006476944728939671,0.066029964174583,-0.31255368032424,-0.17012958967307093,0.24612529231948296,-0.3695717757568041,0.04813000245907935,-0.9686133432281234,0.3778086011080311,0.9149296049391836,-1.0658628588468273,-0.23704651920884043,-1.01017645699634,1.0241139053643669,0.4662449222710756,-0.3301018669297876,1.072581965112362,0.25505861606717495,-2.480446771735205,4.824324260249313,0.18052426848202152,1.3753330713596168,1.157459284056641,0.04180843474393131,0.42500486952949634,-2.5003898499902846,0.630823114713757,2.608175208095485,-1.1419500197149999,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2000184,0.0,1.0,1.0,1.0,7.494790710787433,1.1965382616124556,0.5361091436465835,0.9419757360126699,-0.02886401186876852,-0.04022012490914777,0.3320104262436966,1.006516088706535,0.015852809573203896,0.05582542136065537,-0.4338147439389961,-0.1366997604122867,0.1509237637563923,-0.3745492540448279,0.01358123998288574,-0.8880756953125997,0.38284757828112354,0.9369994047408973,-1.0462252950603679,-0.2369793741619549,-1.0046915728855883,1.0000893107795652,0.47689810937821936,-0.2873028480703657,1.0532959198777854,1.456946546403148,-1.1845570930097327,4.717768577781751,0.2921517580517175,1.2420118485371177,1.2723684748790534,0.010755552308719055,0.44570967769499387,-0.6117588828342072,0.6209432090607808,2.4737044324713438,-1.096644723439598,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2166851,0.0,1.0,1.0,1.0,7.507244413772852,1.2073976223324934,0.5377821432753823,0.9414394469567637,-0.03246111755766333,-0.04252667312341634,0.33291068717255756,0.9754923577382872,0.034615913631890094,0.01602521494175968,-0.4396598190142782,-0.08312192522802805,0.06115727237824903,-0.3210067937469294,0.008644687054948726,-0.8113540761174932,0.3875470125198722,0.9563300826912108,-1.0234504915262939,-0.23668800008151297,-0.9953194380258618,1.003721901819301,0.48694307063598224,-0.2476448876004473,1.0360270678880605,2.7796547914481327,0.5220300296531403,3.8338110156476497,0.33229834526264374,1.1920650520749778,1.1694610235576297,-0.12025589110623786,0.8407629926933566,1.0631071231345175,0.4023960693751369,2.1764806143023874,-0.8106180380607424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2333518,0.0,1.0,1.0,0.0,7.519207592274258,1.2179235501644683,0.5384379535397652,0.941344312779515,-0.03534302201289038,-0.04393447424028989,0.33270334769263793,0.9728669913355593,0.045416363616122224,-0.06855745231614725,-0.29594897978326695,-0.045185361378631925,-0.012982450925739578,-0.28189390901957073,0.030982275773325726,-0.7602817392036103,0.39392421194310134,0.9767349859477333,-1.007243182977712,-0.24098791188255556,-0.9766660837449436,1.0355262857578573,0.49031133851712855,-0.2147533491615785,1.0262752645678914,1.8510976723110741,1.9898264835872659,2.369854779723657,0.350737792353862,1.4398038027242723,0.6503946503654578,-0.2887570363139003,0.9576343505040024,1.9708481514837815,0.18399815003700695,1.5912476913313605,0.09649399459656789,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2500185,0.0,1.0,1.0,0.0,7.531668173431525,1.2289007827993972,0.5372861428485561,0.9413071684803915,-0.03684427758051502,-0.044884669692512785,0.3325186915101043,1.0093880593106284,0.05234828224081961,-0.16197606830046324,-0.14353037614859812,0.048034156914093476,0.04342480060655293,-0.25930341459671546,0.07497236916295649,-0.7323587588030527,0.39923829564752045,1.00432363876894,-1.001770626487802,-0.24631325387577874,-0.9633982291667716,1.0694169715919706,0.4930763545704258,-0.19460319180622254,1.0392435408075458,1.27204548721032,2.7378225482466125,0.9805338830909636,0.2864466730078631,1.7587607897817836,0.1356608859107421,-0.36706600795713484,0.6362027599312092,1.9060299644045198,0.2832948560419993,0.4494679216064074,1.6655634521505502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2666852,0.0,1.0,1.0,0.0,7.544779855771531,1.2402385848348303,0.5349207346952812,0.9410525777552733,-0.03789408086932937,-0.0439483560410282,0.33324559492439676,1.0366675004665926,0.06733668171266954,-0.18373092122382573,0.0966845702594849,0.29352080124137125,0.10024381188336046,-0.23949230797619425,0.12224320990304936,-0.727597211064986,0.40347245347314165,1.0353604628578454,-1.0027211444032949,-0.2532234699521939,-0.9554592826670526,1.099060744973339,0.4997545192715189,-0.1997710551435035,1.0817941573438066,-0.14001497949943897,3.2257856959646487,-2.1585053331390154,0.03416918013801143,1.6753243500843047,-0.13740734988459302,-0.3424605398120253,0.7623498957217739,1.6091509078665083,0.049831300883286536,-0.9617915272587374,2.7416475403990233,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2833519,0.0,1.0,1.0,0.0,7.557676286889173,1.2521714786370743,0.5329627294371835,0.9410202319593176,-0.037033854937002356,-0.03967895757338727,0.33396855683975185,1.0824647641938359,0.08101554078217432,-0.14281071992848726,0.3764344187460077,0.5232791178777774,0.15587618281391163,-0.26397058991436206,0.18249877408082452,-0.8043090804747087,0.40037727059673284,1.0601678954600402,-1.006350880644445,-0.2577286280335489,-0.9379865151527195,1.123055442464248,0.49473740125528876,-0.22666297350094894,1.1306319749306826,-1.0402426357057886,2.9962317520915605,-3.434924531601454,-0.3411501827608455,1.4546149111043831,-0.2751113856361936,-0.25270390003602816,1.2019149954503259,1.0786490651231728,-0.576513426377316,-2.07555622722838,2.407771100659123,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3000186,1.0,0.0,1.0,0.0,7.571483395524794,1.2649089182901123,0.5317306056974952,0.9407528359494662,-0.03500274800908236,-0.03354946658602921,0.3356089131364694,1.1276686541553453,0.061239752901503186,-0.10155967870853014,0.6581780096884748,0.6307657623430498,0.2267496155664583,-0.2741671318492296,0.22211780138821818,-0.8420949244466699,0.3921007579711013,1.0838477235356523,-1.0118915422652603,-0.26164695013365485,-0.9153953693577087,1.1350157857207157,0.4805373666247133,-0.26895640108819796,1.1620533545505174,-0.9288321026826073,2.9146284017019712,-3.04339198130524,-0.6615777297629822,1.2076397128275682,-0.3868084486704658,-0.430929345921807,1.4985236260414196,0.49500609749347946,-0.9370179991016907,-3.3584758389623115,2.039287155573682,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3166853,1.0,0.0,1.0,0.0,7.585722170321155,1.2774251252955462,0.5309025272568662,0.940475114293922,-0.03036938253204804,-0.025970975039615866,0.3375052124841159,1.1398609918535711,0.011734402508787323,-0.0831938448861235,0.8279466878645863,0.6602238131231862,0.188917080005099,-0.2949317219259225,0.279653248446117,-0.9057556827443488,0.37832463549945144,1.1004226330636067,-1.019244521387357,-0.27209296829289886,-0.8880356277164304,1.1395556787144372,0.46350340548403246,-0.33861239203141524,1.1986083494022823,-1.1734535572106273,3.2425418015891965,-3.5097586892571178,-0.7495657599091778,0.8090601623866364,-1.0091099195018283,-0.5995362345362509,1.6792342822384898,0.15280428284659864,-0.7541872788119995,-4.83667641169157,2.514156301292282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.333352,1.0,0.0,1.0,0.0,7.600716099400529,1.289281039294753,0.5300143158308707,0.940396698582175,-0.025826944452747008,-0.018444403863961217,0.3385953664805291,1.151850315887526,-0.04236047902934492,-0.080370260496889,0.7818877261556895,0.6071983579087654,0.04309024068071239,-0.3132823286531543,0.3302027442773115,-0.9590871147391531,0.3671151826697447,1.110816449552551,-1.0455286068559826,-0.2816315312539455,-0.8594207813341402,1.1401092720025545,0.4553977403851614,-0.43017927058967775,1.2458587322040136,-0.8745664850347047,3.103053919738522,-3.068748580784394,-0.6452339691751339,0.30271258843146165,-2.8117897352932824,-0.5576549533533798,1.8141092706328699,0.026834251672966564,-0.215250013836333,-5.632519384857747,3.078951009075347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3500187,1.0,0.0,1.0,0.0,7.616325042799335,1.3007297294921405,0.5289755444064838,0.9407647768077575,-0.02156556873130465,-0.012016629143016455,0.33815996449488955,1.149475763510666,-0.06837899298653283,-0.0789681925519134,0.7153378299376953,0.4713188061881383,-0.10832210244545745,-0.3240839963981783,0.38308858597432904,-1.0080475066870673,0.35681679351134904,1.110513072858828,-1.1129710333497822,-0.2906815039150084,-0.8275651977547167,1.1404501555591529,0.45632839067282044,-0.5263634136946325,1.3012402549681945,-0.5420904509302642,3.172179951318057,-2.7163185885358696,-0.5375372636397517,-0.6521339318305309,-4.111762948140569,-0.5462876490429451,1.994655206943126,0.03340862170768177,-0.15302280605725924,-5.63228777758724,2.9044842554700723,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3666854,1.0,0.0,1.0,0.0,7.631804900581515,1.3118384045396172,0.5278037189405569,0.9413676987640258,-0.017252219351176885,-0.0070581029226979754,0.33686703583804956,1.1339428749429472,-0.0898866839967648,-0.0711433810591442,0.630659434734937,0.2994890044748083,-0.21024314900411617,-0.3313520464901932,0.4359422874665768,-1.0496312487782546,0.3491972380459354,1.0890786083492712,-1.1825876459115314,-0.29984115597455363,-0.7929321414590222,1.1412228949533854,0.45029696998173235,-0.6179225719951043,1.3426750676852997,-0.31956651573055667,3.120884322800315,-2.229540991883998,-0.1384431601083217,-1.1568012258060325,-4.3339217450849805,-0.4560105200076967,2.1254436215917463,0.01967789621865009,-0.39866137198292795,-5.37368707187351,1.7700704202220852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3833521,1.0,0.0,1.0,0.0,7.6474994710698745,1.3223315496406822,0.5267802500488841,0.9421704686723955,-0.013333948520730244,-0.0038337347043472525,0.3348467056082558,1.1323808890311102,-0.11547325833940036,-0.05011651933971323,0.5741835771454924,0.1397570467075213,-0.31829816802616445,-0.33473623489363125,0.48711827145996106,-1.0823656883859334,0.3522020122781943,1.0719529548785451,-1.2574353804473979,-0.30588188498263297,-0.7567169353387504,1.1411060867449676,0.4430396516959647,-0.7054866743362209,1.3602427203136254,-0.09018563770718718,3.006501365751338,-1.6983175513385012,0.2896849137408505,-1.2590926863545202,-4.777546052728706,-0.3902751800704549,2.2417791246556273,-0.08209881491576654,-0.3862071014106514,-5.230136475079872,0.5483346443899917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4000188,1.0,0.0,1.0,0.0,7.663540785863715,1.332636459479885,0.5261760226372626,0.9432810928861072,-0.009001196614923997,-0.0017268330703261374,0.331868613024248,1.1278472820568557,-0.13471461294798676,-0.018029880587520038,0.5906685316247812,-0.010432053278970121,-0.46328045350686353,-0.33435824042614193,0.5361592000917125,-1.1062419470440414,0.35885342114962465,1.0471087681979414,-1.3418394995055585,-0.31285035466191413,-0.7182060211852264,1.1384862623162721,0.43742337418757055,-0.7922608031735316,1.360952925720609,0.08347552379428731,2.878345940706827,-1.184104747744754,0.3075567903529141,-2.958263869230782,-4.317118229936565,-0.5056482792525204,2.4542444148091405,-0.2428207050894318,-0.3772038320219268,-4.675892326828985,-0.6147809543609619,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4166855,1.0,0.0,1.0,0.0,7.679629917740963,1.3423604436521872,0.5261586227155962,0.9448169748949318,-0.0039834392304110835,-0.0007963468681412149,0.3275734757179724,1.097391570326427,-0.14927214952347395,0.017553440372301193,0.5537439403804777,-0.15793803125722913,-0.6038365135679947,-0.33195371186878675,0.583063328039918,-1.1218359255844084,0.36245392579374414,0.9733439620199278,-1.4013396092531654,-0.32273686133426893,-0.6749086245621514,1.1330120470539395,0.430466165481645,-0.8613500636233422,1.3397499808495297,0.21482063601938048,2.692036490212112,-0.5710057306575697,0.2844383781547815,-5.785839390863299,-2.4119589646794752,-0.6502465247140582,2.736178827175206,-0.43345872431129784,-0.30703105091572247,-3.7013325925910125,-1.7921225301774273,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4333522,1.0,0.0,1.0,0.0,7.695347706730746,1.351375709860933,0.5267607505495171,0.9466123868886264,0.000581750606515394,-0.001223973771741888,0.3223711408353043,1.0670955907960142,-0.16601095375368036,0.049260164970914004,0.41083489848195226,-0.2859979190270028,-0.7595426738980305,-0.3271975382374535,0.6258939292345489,-1.1252755094663425,0.36833471938400925,0.8542470694465387,-1.4222382924588053,-0.3345252821688177,-0.6269998778674644,1.124037609275314,0.4271889853549764,-0.9156388030154049,1.3012153885731927,0.4545626606775719,2.5099403943409206,0.12047477308937707,0.36513986166889617,-7.743907057476955,-0.39406973477092516,-0.6154005765539223,2.8240219675090215,-0.5998088016951605,-0.015619061026566109,-2.826466939694417,-2.7427081444797055,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4500189,1.0,0.0,1.0,0.0,7.71118081613401,1.3596828167841652,0.5278946638499845,0.9488830721837087,0.004043158088455621,-0.0030801391753870035,0.31558688334361834,1.0569405373083338,-0.16608376493437343,0.07528824094075996,0.2976645081830937,-0.4462379412957207,-0.9208970110951887,-0.316801592875357,0.6667281751806416,-1.117820091783111,0.3746252788586981,0.7152132105102255,-1.4144752933501785,-0.34325025491277145,-0.5807743707103862,1.113018380343514,0.4299455290728221,-0.9555658167109521,1.2483261931863299,0.7311342104770817,2.343969398512591,0.7025720771546174,0.20036667844813744,-8.42487109059467,1.5546810779598503,-0.5481750902448491,2.879510631150247,-0.6902901301020302,0.25260873000872325,-1.9607595811058682,-3.4463057727275475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4666856,1.0,0.0,1.0,0.0,7.726868228074505,1.368017939990134,0.5295343676424972,0.951402303630803,0.007673161792623626,-0.006650874151910433,0.3077832761979133,1.0509074084559813,-0.13989182788608617,0.07788600937359942,0.28703811853356553,-0.5783446877162515,-1.013656960550185,-0.30282634914593676,0.7040263987829285,-1.1018563933897167,0.3750136220233924,0.5734174714353103,-1.3704154862147384,-0.35279782172198537,-0.5310159981950807,1.101027892252571,0.4356092931958492,-0.9809975864362392,1.1863382997285563,0.788165607472271,2.1277750208003896,1.0958916301194113,-0.3204486583578671,-8.04245940611514,3.6532241942875965,-0.7901698877116384,3.001479110561986,-0.6849620133447374,0.3300021008791255,-1.1708884307700904,-3.764980224565548,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4833523,1.0,0.0,1.0,0.0,7.742281968725454,1.376367211060617,0.5310501213599431,0.9539751132476115,0.011671852948236286,-0.010649768635533439,0.29946925314791706,1.0211500058722505,-0.09889886057267483,0.05929196505142745,0.370981944573227,-0.5658563752282995,-1.022604284831415,-0.2905293534152408,0.7376541510589893,-1.0812902977196885,0.363943635550192,0.447130694142427,-1.2927009099923124,-0.3695893038478186,-0.4807248669263793,1.0901862675678886,0.4409456211022663,-0.9945955091291838,1.1228266013687966,0.5411685664535862,1.9924814029541242,1.2439178913061204,-0.9847869571794629,-6.930288218372994,5.355875397166364,-1.0627937409750223,2.877165784694141,-0.5398471509434742,0.21587776699917915,-0.5635496229015472,-3.721614849769348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.500019,1.0,0.0,1.0,0.0,7.756651739609509,1.384697021885693,0.5323869846483176,0.9563337415410595,0.016584834841218313,-0.013606618001038033,0.2914885555042281,0.9856232207378868,-0.05623415585144681,0.04490711839298638,0.43714201619492093,-0.5362443929366405,-0.9441893370759987,-0.2847873608529128,0.7704425783801595,-1.0603923807516533,0.3421873244649465,0.34240740213699594,-1.1918859492508331,-0.3882243506074022,-0.43511028022755704,1.0830329512313117,0.4428052331543396,-0.9997826114362657,1.0622842232952547,0.24916916190254337,1.8200037687958193,1.3592524053492423,-1.2472554612920415,-5.772844624126839,6.096489363943242,-1.1301499051921136,2.7041898898019223,-0.4329681025967578,0.12733000951261025,-0.12634185570489598,-3.2020800502017295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5166857,1.0,0.0,1.0,1.0,7.770562449915104,1.3930549936426835,0.5336737397084009,0.9583264995678297,0.02145378826211756,-0.016816466005836944,0.2843716963172485,0.9615982055835043,-0.02203938878118955,0.03726315873762376,0.5886459103134786,-0.5164183166174892,-0.8574947911873742,-0.28222369807387854,0.7983210646857679,-1.0359817935912201,0.32236837035675986,0.25470215514855743,-1.0894841914282467,-0.40726104269754937,-0.3905850236536559,1.0757539686167898,0.44518996324135396,-0.9988069127421374,1.0160903862234023,-0.05790345598350442,1.586417572820499,1.5818380294378254,-0.9420272872803759,-4.58526422139061,5.201606982372576,-1.2546346114767315,2.624006805639993,-0.499651215329643,0.10965566461611662,0.0532244413346387,-1.9782767536522448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5333524,1.0,0.0,1.0,1.0,7.783878881915573,1.4014661963492296,0.5350282914618241,0.9600316421291695,0.028681665709849966,-0.018778533152210914,0.2777840435581751,0.9479355768152455,0.008303750804317112,0.016759055026713866,0.8424638224443247,-0.4296202260700382,-0.8128607498587215,-0.28671747991259333,0.8233232699020143,-1.0076643409811905,0.3107863520871148,0.18956495573969417,-1.018498703064615,-0.43004558796560066,-0.3476432117724369,1.0663778774102426,0.4464604292852545,-0.9980084598434816,0.996341532955063,-0.44311114551472586,1.471601661174192,1.6349913484040712,-0.6059477040416388,-3.534696584322408,4.457241920959913,-1.4807502203868348,2.526759090053154,-0.6194251932866736,-0.06342201527466203,0.23614283775083963,-0.5886879092719693,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5500191,1.0,0.0,1.0,1.0,7.79710246975618,1.410071141242378,0.5358862125973206,0.9615426034131905,0.03718511387747329,-0.019412239028784792,0.2714337011190622,0.9599375582933618,0.01689693317999008,-0.008248628617107623,0.9574452734838172,-0.3338544357758908,-0.8136262303599275,-0.2969940991317791,0.8473745514983517,-0.9814819729783278,0.3021700731588583,0.13687870002470487,-0.9409091635801216,-0.4566194820937919,-0.3063595522012781,1.0551064208788878,0.44307589183739754,-0.9909354690742536,0.996467416668476,-0.6507904593428286,1.4734384436666688,1.4681712560741138,-1.6687748760956989,-2.60747056043432,5.3154144953460705,-1.6302479446192455,2.4255573726220008,-0.686930738810381,-0.22022758733617354,0.6855901324900037,0.5195104449060757,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5666858,1.0,0.0,1.0,1.0,7.810847664848847,1.4186238729249703,0.5366291047425323,0.9630069157360336,0.04580361731298144,-0.019292112339832038,0.26485377718108005,0.9829483848858553,0.008462205969345438,-0.022036879985555306,0.8759910192273642,-0.21954194064588034,-0.8345756348219774,-0.3084105386100516,0.8724379829201329,-0.9587252012339696,0.25516041163226644,0.10264909656051281,-0.8413178655254464,-0.4843872948027718,-0.2667911376478787,1.0434801403211806,0.43911949502554287,-0.9751554097211393,1.0136585824192952,-0.5719546755895083,1.430533969857369,1.3331443877879998,-2.413759561581511,-0.9103689586940122,4.751343437595188,-1.4850227421172977,2.205384951383036,-0.6443000284704534,-0.27607367836122776,1.0927237431212233,1.227463026215394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5833525,1.0,0.0,0.0,1.0,7.825111407104873,1.4270406882743567,0.5371896862708437,0.9644986525910265,0.05248776310423314,-0.018418258905491692,0.2581630330107289,1.0270199507946909,-0.007408783559752885,-0.07480823876326095,0.7007395578313147,-0.11706644561425927,-0.8265084610868372,-0.3160592931150744,0.8950591125291953,-0.9370437378424353,0.22171126018883716,0.10653300737697388,-0.7825307322373861,-0.5061203391658846,-0.2328465734628468,1.0336297103098708,0.4338734174871114,-0.9545112714552966,1.0373829327065243,-0.47929646871555026,1.517141199563697,1.141099599998609,-1.090302284549729,0.46682909144836204,2.645928795079344,-1.2398703634839956,1.7551702524626653,-0.07346825354021014,-0.388176209988317,1.1562101576060801,1.655213829656445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6000192,1.0,0.0,0.0,1.0,7.840639709126648,1.4356696124963866,0.5362723323726707,0.965922899661308,0.05782674620823667,-0.01742833269905629,0.25168486754707764,1.0727128834285575,-0.024569540162100167,-0.16336349579616805,0.3632464996253716,-0.013879208506392848,-0.8606840435518197,-0.3243871195203345,0.9230094573816694,-0.920688471827376,0.2188169294604565,0.11821009739739764,-0.7531200626275486,-0.5257163895769292,-0.2082853455544397,1.0410311936386234,0.4261802621475183,-0.9366149940535928,1.0688324870887653,-0.2627502483906121,1.7454807522524405,0.7476040161869063,0.22944496969717093,1.669581279520505,0.6708353854288155,-0.9895096305291559,0.875382576007425,1.2473379119218817,-0.22874101326327242,0.9482456084998974,1.8526522642123793,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6166859,1.0,0.0,0.0,1.0,7.856741447414509,1.4443006805980119,0.5339443768597993,0.9677613383544171,0.05864455430683761,-0.016253917578826705,0.24440666603012387,1.0879978641487353,-0.017635648934365533,-0.21115766497500546,-0.012156148970593028,0.1934872228056256,-0.9440480093716641,-0.32481765224477804,0.9532419206363268,-0.9121235541292707,0.22935944114174084,0.16218582799974268,-0.7601695080007332,-0.5391040594841652,-0.2036670959037609,1.0752077238631277,0.4262487017956014,-0.9229030212889261,1.0991381316904212,0.03242002645626449,1.7553572813510074,0.39502107104079826,1.271682640699358,3.2420861742659626,-2.3145526606937747,-0.5135640314806075,-0.33149117086491936,2.3277597690769145,0.024595246908570373,0.9330598039803193,1.698779854075202,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6333526,1.0,1.0,0.0,1.0,7.872853335127175,1.453097866674596,0.531404378990487,0.9698233127102986,0.05710965223232134,-0.01341610886527044,0.2366458065726938,1.1231754085403627,-0.0019950694516115974,-0.19305206676059894,-0.3394265493888393,0.4301059430689893,-0.953045854032787,-0.32330644981045725,0.9815214837838551,-0.9075210764579447,0.2612064355959445,0.22627985267867468,-0.8302719722875185,-0.5428352248638849,-0.2193350733493484,1.1186233411251718,0.42700010535082045,-0.9055129383835953,1.1254585954765957,0.32169307924629664,1.658053255446898,0.1553990591887788,1.747395663954108,3.3210248226625527,-3.866454000267847,0.46075136529900496,-1.155580993860445,2.180427008014529,0.12986389126971928,1.1988712897198457,1.2557693040106856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6500193,1.0,1.0,0.0,1.0,7.8899980827448175,1.4621233447578204,0.5295328719263326,0.9719244377279922,0.05168250682711673,-0.009701362761866048,0.2293418614116361,1.1707769008806879,0.020324754068683393,-0.16445250699209332,-0.6085314039192317,0.570063231686234,-0.8923118324238195,-0.31409452815702954,1.0085104730214405,-0.9069435751297075,0.2876060797665887,0.2728868768234826,-0.8890515657732615,-0.5237456499241073,-0.24218653940450866,1.1478887694920792,0.4305775068288515,-0.8829405650401786,1.140997192208731,0.5385494081125608,1.8056821805734178,-0.6728028290904652,1.3895327665579034,2.858029950331025,-3.265590390465085,1.3863192103724518,-2.1226563816788544,1.9241441582000234,0.21156971484166667,1.4858091890414526,0.7922828637127967,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.666686,0.0,1.0,0.0,1.0,7.907437326611819,1.471634454566463,0.5276790803274646,0.9738468374702146,0.0452216151084297,-0.005728361062127686,0.2225860026052591,1.1828508286141701,0.04784670368357796,-0.1936928208482891,-0.6085696542401773,0.6325373133730327,-0.8556781656644046,-0.305354766970078,1.041711010181781,-0.9299478822811488,0.3075242871167257,0.32154770822503886,-0.9391252030090473,-0.49662449209685583,-0.29009042758240233,1.1827616080081165,0.43405244328352366,-0.8559858663616009,1.1518680770858798,0.48759536538719245,1.7188492982231356,-2.0550201710267286,1.4118343745441488,3.1586420930656436,-3.5235923796124347,1.551365825712307,-3.500046749081263,2.5301308103360403,0.14980207490596756,1.5744085152795806,0.689734600199073,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6833527,0.0,1.0,0.0,1.0,7.924766806590388,1.4812117708292434,0.524473326111257,0.9756214436010681,0.039545546279756656,-0.001052772438986396,0.2158653289099374,1.191146817231191,0.07503343081650488,-0.20047805146823053,-0.5872856195065748,0.615776703960091,-0.8013278311120953,-0.2978413168044321,1.0658055642188315,-0.9754443844986098,0.33466731970701863,0.37817515716847694,-1.0065048799998346,-0.4720333523093087,-0.358854997710334,1.2322266318453345,0.43557091931252206,-0.8304601762369582,1.1639883915310067,0.009089158764511652,0.84217216031243,-3.260243199060407,1.4797038663411617,3.385263965589947,-3.715659023007471,1.592897887502101,-4.4199486595081785,2.984344982309788,0.1377494216813972,1.674221943019138,0.5346267487551175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7000194,0.0,1.0,0.0,1.0,7.942287821028707,1.4911339999557474,0.5219686848037017,0.9771331439883983,0.03346885661350716,0.0027071088735325186,0.20996029652741321,1.199412723510371,0.07245489760865592,-0.1613468736037054,-0.5679567172293439,0.5802848314006026,-0.7369192866069003,-0.30505179440531704,1.0697834716703394,-1.038622872932709,0.35684784797502217,0.4343900660956348,-1.0629807514865646,-0.4435277896535933,-0.43742234422925225,1.2822399730414415,0.43864409985619834,-0.8001783566461668,1.1696890043528336,-0.8452312740939945,0.22991126795931707,-4.934330786083517,1.2979000046567035,3.356358729174261,-3.2470307643149843,1.7536172611880134,-4.8566958453746825,2.620661518928178,0.10587824283881331,1.8991058303301813,0.17800069768000049,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7166861,0.0,1.0,0.0,1.0,7.960127187097812,1.500166230293624,0.5196183117810032,0.9784962065883883,0.02823529773201959,0.006816948537660815,0.2042093799676036,1.1979072549794663,0.08084287436573112,-0.10621937272696602,-0.4538805802445667,0.5023036539309672,-0.6764885855314704,-0.32601574895631685,1.0734692884782266,-1.139922406323446,0.3779307397222424,0.49005400523153425,-1.1147394552790517,-0.4135793266952242,-0.5207451830025465,1.319582190520375,0.43910020113236536,-0.7671565219522302,1.1699217599870533,-1.175939737520888,-0.081560888974375,-5.924324567562487,1.0238253978281946,3.318287023748123,-2.808519322665184,1.8398012923543623,-5.284759894043583,1.8937332575196062,-0.05862150977505772,2.1647140561245277,-0.19051948626186763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7333528,0.0,1.0,0.0,1.0,7.977720170765036,1.509758478793974,0.5185181823658317,0.97960625756266,0.02427675284501273,0.00966904653489535,0.19922030256599801,1.1891417921616494,0.092301014422901,-0.05625057925422679,-0.311087714454518,0.34288665406136576,-0.6416117550029231,-0.3442498640519958,1.067064769933801,-1.2361007534730963,0.3909754294909885,0.5449998547730405,-1.1565982494766922,-0.3822009572550284,-0.6135813596813646,1.3453645412076456,0.43669004562226243,-0.7280210771277454,1.1633383421094723,-1.6687865586530466,-1.0135185096525212,-5.83316791095382,0.6978886880318762,3.240340147503869,-2.2046252322439157,1.6007721035379845,-5.507874486311221,1.2047307049183338,-0.237764953107835,2.4383031416091283,-0.45097736903719937,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7500195,0.0,1.0,0.0,1.0,7.995358443050076,1.5185670133386249,0.5175365608114132,0.9807030853141842,0.021909125770144672,0.011632574440378511,0.1939230050177572,1.1728215911499216,0.07658607492518982,-0.021013001610566275,-0.2730511568365689,0.16736685530831769,-0.5854291331029609,-0.3816420788305223,1.0396852705885753,-1.3343617255664342,0.40119374251588413,0.5980655595043397,-1.188227109995531,-0.36022014985915113,-0.7043413664045529,1.3597399609996998,0.43117468684444066,-0.6858795880117164,1.1548891509539887,-2.3427058462451438,-3.4467613027642567,-4.824019262462484,0.5406565603659036,3.1098445176621143,-1.5168589603824574,1.2878401714973398,-5.032671007461545,0.1435689966503407,-0.28170052879194707,2.6970724928324312,-0.6347252524197765,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7666862,0.0,1.0,0.0,1.0,8.012871716034754,1.5270336745700213,0.5173800486609857,0.9815711909111309,0.01915169506026921,0.011740862442597413,0.1897718680382494,1.1401020359059253,0.0786243371391735,0.029438613236203146,-0.27795505051063424,-0.022695921755172654,-0.4849095821313349,-0.4223402151072237,0.9521724967242389,-1.3969017171564633,0.4089973508802893,0.6486615460180788,-1.2071603159467048,-0.339272865682439,-0.7813373954414833,1.35015018400059,0.42730000921582895,-0.6381184808951649,1.142180791380463,-2.4337732963959304,-7.03014002838457,-2.1311645056137216,0.3675926516172073,2.939608997889244,-0.8763803058811952,1.1692978806912286,-4.605632278741926,-0.8999870965796918,-0.18437011665005615,2.8463057989846616,-0.8556082047988091,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7833529,0.0,1.0,0.0,1.0,8.029668723062205,1.535139872843953,0.5180273765966962,0.9823325289339818,0.01733335222759984,0.010534174800586129,0.18604136276643587,1.1069776201492825,0.0675871235494836,0.05744540575323469,-0.35932146343939386,-0.26334593612303503,-0.3595912590225045,-0.4627680176286064,0.8053468009664211,-1.4054006844978586,0.41344685540930115,0.696052722074581,-1.2174398452835913,-0.32124347588291813,-0.857862749404769,1.3297403311145704,0.4250290039980977,-0.5910025382918411,1.126368820420148,-2.650705238313781,-9.480868121301336,0.5554914918326801,0.2747381057128626,2.7425854292843734,-0.3078543029988604,1.1470606396459386,-4.278878149429846,-1.5665144273487681,-0.04448720097654325,2.84707396727082,-0.8292545619916541,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.8000196,0.0,1.0,0.0,1.0,8.04643792467107,1.5425720836927745,0.5188531822234086,0.9828290199754393,0.014009165700934502,0.0064276009924994154,0.1838737249200187,1.0945449534664646,0.04869375887716243,0.06133715043339562,-0.5155180787083515,-0.5438435925670244,-0.2605681790414544,-0.5106972330980323,0.6361429272896529,-1.3783852970626078,0.41815530605325846,0.7400812431665865,-1.217422146570287,-0.30103743455686505,-0.9239669523476881,1.2979329319880026,0.42581709955079744,-0.5432158255145397,1.1145389173637703,-3.05080267634056,-10.179813433454266,2.232755417925026,0.2686034484434823,2.608156315261845,0.3005352980304993,1.1642352099985813,-3.4694364646705504,-2.2461546970204433,0.21002034437101486,3.006985607863363,-0.621975308528676,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.816686299999999,0.0,1.0,0.0,1.0,8.06313354270108,1.5497945549577532,0.519846510945619,0.9832966377912109,0.010522570013465233,0.00010711656784809359,0.18170576808360506,1.0907176867524153,0.020368538221571864,0.07508226468762258,-0.6619352748751172,-0.628030771793417,-0.34208074611481054,-0.5644616435601368,0.4660190078637167,-1.3309753550499965,0.4224003215976471,0.7829914397937302,-1.2074219819802214,-0.2824355579339514,-0.9735108628562184,1.2548683581369091,0.43202969614515446,-0.4907694842306885,1.1056362686708383,-2.6796354963486135,-9.622866200167254,3.1959190389384604,0.4285566347546563,2.4467547866824,0.7725589516581169,1.2704117200170444,-2.4591847245186,-3.1266791104691785,0.4474436789221123,3.0894407360848835,-0.533212094274325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.833352999999999,0.0,1.0,0.0,1.0,8.08016191538907,1.556146417231942,0.5215008239426486,0.9839743467835772,0.00507230082166426,-0.005809838798748384,0.17814320758687294,1.1089792360988913,-0.028090725224046043,0.10524715454742295,-0.8015708445685122,-0.6233035098393996,-0.4753921694418282,-0.6000185949520191,0.3153800790929978,-1.2718544493700565,0.4324405557821893,0.8216398991729856,-1.1916701300110863,-0.2586902925288489,-1.0059399404439564,1.1937100865270893,0.4407319186777798,-0.4402342616823279,1.0967651453404865,-1.518673479976624,-7.923232438875601,4.037490093200922,0.6723779185206399,2.3240951140164947,1.0473659042140122,1.332194804458594,-1.3227405888748032,-3.935123258805279,0.6073551158807434,3.1707435713509837,-0.6595950093427424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.850019699999999,0.0,1.0,0.0,1.0,8.098045410008464,1.561832649427078,0.5238363853079778,0.9847055269158909,-0.0007240340667291728,-0.012457391942275502,0.17377949942949109,1.131371091570397,-0.09639023951463854,0.10615627765446954,-0.9082783923796383,-0.6339904728630743,-0.5527952610138709,-0.6150841941375896,0.20191073168570073,-1.196392082777293,0.444812963706863,0.8604614318672876,-1.172509715348694,-0.23802897563901132,-1.0176023040014177,1.1236973205018492,0.45227490716485363,-0.38507782046941763,1.083649724386413,-0.031283993852897235,-5.424194801810864,4.774299316968755,0.9378421334933654,2.120949865190217,1.3442701243019601,1.3241708379042656,-0.3501691858294632,-4.10082281535523,0.7331276789698052,3.304355135038465,-0.8368551105273574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.866686399999999,0.0,1.0,0.0,1.0,8.116596745948735,1.566024703500869,0.5259725010924066,0.9854252133840109,-0.007878281230601426,-0.018848807120424613,0.1688780743082568,1.124952113827103,-0.1371545054816052,0.07367519675234646,-0.8974845473664096,-0.5063518036741935,-0.6851995659535755,-0.6010613968327153,0.13457322408631556,-1.1127108205178102,0.46370202275477707,0.8923383694093172,-1.1468610362496794,-0.21455117632065085,-1.0176122699828842,1.0570157192937273,0.4651695568519519,-0.3300888702240367,1.068869919199234,1.3990325148551042,-3.8145944638863156,5.541854105115257,1.076549505576922,1.8738125732394788,1.39465830319526,1.2375568673698842,0.10769770993932666,-3.4367082127040467,0.5884026520319326,3.241445587885873,-1.0013892916833451,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.883353099999999,0.0,1.0,1.0,1.0,8.134800879227221,1.5700365470482984,0.5276834913087105,0.9863660676190196,-0.013803689674547811,-0.02340776161900479,0.16230685597703035,1.0892042857261643,-0.14951124997435566,0.045871168206940836,-1.0252205124381322,-0.38682323343332353,-0.8487671378198178,-0.5684496837069185,0.0747573285831926,-1.011663243149844,0.4806980189960608,0.9229219758961085,-1.1260210122649652,-0.19677699755622402,-1.0140123731569262,1.0091401509645002,0.47188836812609486,-0.27702941811018267,1.0502700145710153,1.1144148143991293,-2.7730976137338925,5.450884464117134,1.2413974632797002,1.7148573709885164,1.426453537081743,1.1676794672018327,0.1530648071662306,-1.7962102043865382,0.6072716082409708,2.9859633928675606,-1.01881656072336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.900019799999999,0.0,1.0,1.0,1.0,8.152465987045392,1.5729839693237588,0.5291867304637206,0.9873008085744265,-0.023350095092677565,-0.028158159364774272,0.15459302865470595,1.0581702355881586,-0.14010446376944405,0.043868298020518226,-1.1336094013280984,-0.2744752737027753,-0.9612233442335522,-0.5639141620584234,0.042136452088678215,-0.9310143083216081,0.5050820209572646,0.9495003960994258,-1.0993124899167188,-0.17562844956862528,-1.0125100995396894,0.997141926066829,0.48541198427809146,-0.23055655806422518,1.0349092992540179,1.9410262973095942,-1.5598408335153835,5.057132991384356,1.3479415014939293,1.4623361271875723,1.555506643572537,1.2115455727503273,0.4744671892776745,-0.07457881860675211,0.5997459566086164,2.588159453363717,-0.896756680309016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.916686499999999,0.0,1.0,1.0,0.0,8.16965901440004,1.5764630233012071,0.5311043805141377,0.988287540627974,-0.03128201641266201,-0.0312396596641392,0.14605908445809695,1.0358640880862457,-0.0825104288491875,0.012270742931849127,-0.9139206767622627,-0.19946428076386918,-1.0656151178705648,-0.5037486777281789,0.022762530143290924,-0.8430918062948327,0.5256294922419585,0.9716666109581027,-1.0741706871121044,-0.15639206436150827,-0.9981967685498577,1.0066541853723538,0.4918799399961125,-0.19075726378742855,1.0203780654436028,3.3216920357042055,-0.16777404998344497,4.5235381063698235,1.1228743004185022,1.421489764530564,1.3370580413428839,0.9076312246999814,1.0609670940570728,1.438997728147128,0.22322096788944243,2.0320481836659603,-0.31178863789106465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.933353199999999,0.0,1.0,1.0,0.0,8.186213886395016,1.5804137638691944,0.5316058600441189,0.9893186097333353,-0.0373599623577662,-0.03424663007700892,0.13667512566775109,1.0290863433884836,-0.05552874400776783,-0.09879883620046834,-0.6249556684836948,-0.1529738206482762,-1.1288377270502334,-0.4531908727554808,0.03654397257096005,-0.7802294032067403,0.5425112391628347,0.9968834830164289,-1.05474379940142,-0.14537401490321092,-0.9771444590066474,1.0451086129382485,0.4928526980891374,-0.16282148313881425,1.0245163238717399,2.617440591578853,1.599885874424642,2.9103181530825886,0.9317400588378381,1.6580877206224096,0.8441373844090673,0.4581748556891596,1.1463773388439331,2.4481152124229286,0.02100961125940995,1.0899113555567255,1.1190842618759136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9500199,0.0,1.0,1.0,0.0,8.203352545674004,1.5838381043442493,0.5299562622657498,0.9903971488144514,-0.040581369803541635,-0.03591651764715689,0.1271874357205735,1.0520302592944044,-0.06491207876006796,-0.1872290185247814,-0.3545836919323159,0.025780186247250328,-1.020962024600159,-0.41650048351284435,0.07609216594983728,-0.7460810071708696,0.5566875563192237,1.0269363121846977,-1.0460327180226432,-0.14111953862687923,-0.9599841141632374,1.0882581889941323,0.49258026177206693,-0.154426812608114,1.0576809487784173,1.9192382773098102,2.511178748826983,1.1519786445525817,0.8530191416760042,1.8753760371044061,0.1689572215361235,0.11037941501291929,0.9678450491821998,2.347660902827339,-0.008586382492319803,-0.230341377632487,2.6519130879455766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9666866,0.0,1.0,1.0,0.0,8.221103837090222,1.5868194205736919,0.5277280676639465,0.9912801112430673,-0.04263826881797741,-0.035268967268826536,0.11959021295210025,1.1110476870320791,-0.07859135384628518,-0.16858431563690243,-0.08384289303519875,0.32594490719925673,-0.8803048311423473,-0.389216135562602,0.12025009827710942,-0.7418300382564113,0.5709452674199776,1.059396142611645,-1.0491118807530677,-0.14169469371081928,-0.9448828928442374,1.1233641328765533,0.4925664847669679,-0.170499544415989,1.112913603597465,0.8443236572294286,3.230915919969824,-1.880892200434555,0.5698035153899963,1.6519337231909637,-0.0009289828790639785,-0.02307798733565451,1.2770106057353223,1.6101316151702707,-0.4285613319524551,-1.6489330971088147,2.9997086069942003,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9833533,0.0,0.0,1.0,0.0,8.240299553052264,1.5897674105165238,0.5268266389239916,0.9922822057564523,-0.042073341640818954,-0.03134345905835292,0.11235410823170613,1.2040505061258322,-0.06732848221281007,-0.10067195468629286,0.37519731030517794,0.5344798066921926,-0.8231024023214655,-0.3883563053169529,0.1837895786765594,-0.8087775392448348,0.5756810448191246,1.0820008797533114,-1.0460636841805442,-0.14188880640993354,-0.9174170088380196,1.141929350175249,0.47829485546956296,-0.20939135910728096,1.1576714356587978,0.3937322632024031,3.427420358159572,-3.4463908006586785,-0.07102404606001983,1.2171935156118348,-0.028636148328761407,-0.297647729574133,1.8677458491630161,0.7930544370956473,-1.180334238043745,-2.9506863571286623,2.32801489193859,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.00002,1.0,0.0,1.0,0.0,8.260881751084842,1.5934381160626212,0.5267110833732037,0.993352073366816,-0.03699316765370913,-0.026337331198803306,0.10578047490022467,1.272295342675897,-0.07565330231686646,-0.07876044198138793,0.7248930629505376,0.5878907772702902,-0.7757197781265919,-0.376091700540371,0.2344976720437857,-0.8567099613710872,0.5685777944830406,1.0999693409449405,-1.0500664209397697,-0.15161630453980568,-0.882624573355747,1.1497993336500374,0.45322193147656054,-0.26885595303270154,1.1905142551964107,0.2512622530069124,3.504413749038174,-3.3966145633076024,-0.5153766086068123,1.0420254187813327,-0.9528366816232151,-0.6113562112391776,2.2193595181373755,0.313027801668377,-1.3428206599300352,-4.155617669926415,2.0713308863002786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0166867,1.0,0.0,1.0,0.0,8.282384521290005,1.5961259231704557,0.526298666119146,0.9943476263061114,-0.030763245266775006,-0.020819623625702124,0.09946338055858715,1.3065190959299096,-0.12133073464681951,-0.09065034348683951,0.850293126177912,0.6365702103905364,-0.7751816723299674,-0.3799808801325723,0.30060360393874846,-0.9219982511293924,0.5585017901737903,1.116735129847717,-1.0778249704237635,-0.16226738754165354,-0.8434382102761392,1.1523636310993817,0.4335340772838511,-0.3479122251460061,1.2267159366241995,-0.13996022324176605,3.8137878061685577,-3.7198141650223473,-0.8327293287917416,0.7841025436743438,-2.456796527934909,-0.6739888439338173,2.4461385166423035,-0.0038053773945851007,-0.712026742725835,-5.324465277750974,2.571399666452323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0333534,1.0,0.0,1.0,0.0,8.304471434014115,1.5979793007180674,0.5254985720448295,0.9952839189995747,-0.023685918682190926,-0.014779595934458269,0.09290027653910791,1.3151440417571965,-0.16882797375799236,-0.07961337549931993,0.9854644165620566,0.6106796278465699,-0.8376390810400279,-0.3807570506457781,0.3616241865019247,-0.9807040148594431,0.5408200946746939,1.1261061446742548,-1.1319598023240351,-0.17408264427018919,-0.8010864597251024,1.1496724874831927,0.4294876592505832,-0.44633848392208586,1.2762277488381326,0.0017397103406596318,3.59097256037914,-3.2306503893606044,-1.65802280102676,-0.5386272567671601,-3.118130680853274,-0.7709742356384851,2.6537940810476384,-0.3410561524812489,-0.16893593968677012,-5.692545416003311,2.7572648793831176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0500201,1.0,0.0,1.0,0.0,8.326573398321164,1.5986213761001697,0.5250265908685486,0.9961727143172877,-0.01516526458174632,-0.009498575723208025,0.08555533331782188,1.3060269499488264,-0.2156018131418916,-0.06145995299363257,1.0694149175764593,0.4575790757790852,-0.9157827219950241,-0.37992288967190296,0.4203029286828905,-1.0296868128181051,0.5032342529380449,1.0987808520469946,-1.181762867660918,-0.18796658012788542,-0.7549782306549458,1.1409950699462632,0.42790286803189614,-0.5376641185158109,1.3186249497546287,0.09146803377678521,3.5074101570398075,-2.664447437065999,-2.0172791129798644,-1.2213183363630222,-3.415096533281343,-0.8556079763632725,2.817287118570845,-0.5427397929341996,-0.3045786734067868,-5.444477668817626,2.1906921725278763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0666868,1.0,0.0,1.0,0.0,8.348627616765146,1.5982757232773979,0.5243909328162504,0.9969358197695086,-0.006453278132186615,-0.005886706808781662,0.07773463285302032,1.2866245469382371,-0.23244752066959054,-0.05518163043738712,1.0272847710898727,0.2499376701335759,-0.9606025850309629,-0.377708110088683,0.4785380922305954,-1.069519107058139,0.47357732309009093,1.0853954520409317,-1.2457965811065155,-0.2026029671894967,-0.707176701286933,1.1315811248693999,0.4193350164984454,-0.6278214358478513,1.3492509673018733,0.13295204594303353,3.436319177532407,-2.07364066084501,-1.8221342482727432,-1.226532756167032,-4.482038908794341,-0.8982779443198162,2.9285517407103274,-0.5651298220422758,-0.37525243822590826,-5.562241076650661,1.2800879242060177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0833535,1.0,0.0,1.0,0.0,8.370163457850907,1.5975959382578613,0.5237546258118501,0.9975612610498223,0.0016583788427619582,-0.004111394080652763,0.06965541379545184,1.2620135980000435,-0.2252031605155939,-0.02419917498218646,0.898863424590143,0.0493734342861417,-1.025005635975338,-0.37549114594366545,0.5348471303552492,-1.0988083064223162,0.44249632318667026,1.0578963450725765,-1.3311644634233233,-0.21790923815707558,-0.6573596440611522,1.1221573715361992,0.41539442840753665,-0.723072525220238,1.3612946325673576,0.23967396311195946,3.2480677741436836,-1.352300099240241,-1.7161859683965164,-3.1317112064052846,-4.388824755376813,-0.9375479980436712,3.069397778425239,-0.66749759657749,-0.028551973050890328,-5.5296761461237525,0.13955091898408079,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1000202,1.0,0.0,1.0,0.0,8.391334947895388,1.5966905038038346,0.5239185707864834,0.9981092685363064,0.008489119576808146,-0.00397697934919042,0.060745424074461166,1.2290032285270966,-0.21952355260292128,0.008766304381814154,0.7299578185069577,-0.09215717964198436,-1.1369150994890898,-0.3697189620066868,0.5868072345732365,-1.1145958671861536,0.4163710097311425,0.9810048697133418,-1.392091032207393,-0.2338546296274856,-0.6048632373795731,1.1093311604836438,0.41838328215995085,-0.8121443426970528,1.3539026739047373,0.49415599246549935,3.01033534055923,-0.732981634732667,-1.72256929014828,-6.46416513161049,-2.1558526928330917,-0.9405667695680606,3.152303265217624,-0.838034999329493,0.16379160059492354,-4.886671870455635,-0.9388718062622196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1166869,1.0,0.0,1.0,0.0,8.411712482192506,1.5952933580896038,0.524293801714564,0.9986014746541965,0.013961728443296975,-0.004725199479994796,0.050772408325921475,1.2038166787803397,-0.21917921263214576,0.01683199268095218,0.5076808533057212,-0.24011860461968051,-1.2666228736927976,-0.359019246584416,0.6351918423962463,-1.123241076445514,0.3850772320104416,0.8424237430745514,-1.4030263635746059,-0.24926152651379557,-0.5522826584003471,1.0942228156895495,0.4208541593468075,-0.8859619133468839,1.3299988431004965,0.8076799365644055,2.86694270085917,-0.366508111790573,-1.9118517171558387,-8.3685208243003,0.0036141549977255047,-0.9540253391816286,3.156506552716395,-0.6848503150140413,0.3706114277128185,-4.0138403714493105,-1.8365133748654558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1333536,1.0,0.0,1.0,0.0,8.431990887798529,1.593472843265016,0.5247147557575412,0.999039554094937,0.01722475419713455,-0.007220545111827881,0.03963762007141465,1.1755988741182566,-0.23133140444480055,0.03275507095937216,0.3070039287574642,-0.4259566526865508,-1.4055678350238339,-0.34279624360921085,0.6823721823980555,-1.1268128286797134,0.35264249170250006,0.7020536176686102,-1.3919705601331918,-0.2656555378685625,-0.49964614185525646,1.0865027709931547,0.4307370211244733,-0.9459392893347213,1.292685438974997,1.0561327513185281,2.7011988032774887,0.27604937247585903,-1.9082105444087143,-8.40584068479072,1.5667505634560326,-1.0120338290041886,3.0977900559442206,-0.3666880944625459,0.5570585132728227,-3.0105042045462653,-2.84592063530216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1500203,1.0,0.0,1.0,0.0,8.45137033391653,1.5906667041962856,0.5257427691695947,0.9993748096890449,0.019510230208319518,-0.01119620166224205,0.027276102077498785,1.1453653679050313,-0.24865274656930386,0.03143781546126685,0.24228512774029565,-0.5945412835030238,-1.5175754945140465,-0.32381475113161495,0.7252319825854161,-1.1140394122930273,0.32147008664944815,0.5622284931921484,-1.3508012403427005,-0.2829960549495238,-0.449022783349536,1.0819998547615917,0.4394228135931358,-0.9863122541987064,1.2351346321957155,1.1270460688160115,2.501669625193305,0.9855539685066582,-1.8250212039128149,-7.744634648392175,3.2408718475238185,-1.1678309395297297,3.1463799923402553,-0.3073793852831752,0.5789822452031657,-1.9122576148380426,-3.6974807297368546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.166687,1.0,0.0,1.0,0.0,8.47053658425869,1.587226302162178,0.5263384884664698,0.9995249024459939,0.02179946046667153,-0.016517803336624153,0.014209682847306542,1.138236505186762,-0.23351579890564705,0.025923482850838023,0.2586043740380969,-0.6882183887987627,-1.5192597758069142,-0.3052279661789392,0.765761336682474,-1.0939609640258936,0.29180832990399264,0.4438986130798945,-1.2839412824909413,-0.3045833137082828,-0.3947665990185818,1.0762567709917565,0.4500364678967285,-1.0096813373131637,1.1694358348183866,1.0520743938759078,2.2658835911080373,1.3893381991177884,-1.8688520962337134,-6.632868151908325,5.000579604184908,-1.3081128405770248,3.285888701805161,-0.4386347136930055,0.5370046711515789,-0.9215472094592685,-4.0324174624157205,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1833537,1.0,0.0,1.0,0.0,8.48947431674103,1.583905739186011,0.5275463645661295,0.9994575663790043,0.02439318463748651,-0.022053125448173193,0.0017903097404737404,1.106260087519833,-0.1786334013663504,0.05792453131718758,0.3314135766624718,-0.6476016564765855,-1.3683965756860972,-0.28874553453079177,0.8007615866812567,-1.0677280463665544,0.2591748921848513,0.34113244593732744,-1.1841149201645633,-0.326599903509614,-0.33949294089678383,1.0673786683961772,0.4573230050984998,-1.017030555950496,1.1007204479540273,0.8033694082075188,1.905052753821085,1.7780089354727284,-1.791310475749386,-5.781860457458858,5.830422075519112,-1.353084132817286,3.2363752773264785,-0.6756035132391489,0.2631132887565217,-0.07592142405251986,-4.179754272449046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2000204,1.0,0.0,1.0,1.0,8.507318658850483,1.5812769599355685,0.5296040401771431,0.9992161711772591,0.02784246032537867,-0.02675497780442894,-0.008718475989108368,1.0620201827834352,-0.1325854183438937,0.084134069808593,0.5728680005278032,-0.5396655569782156,-1.2398005238876662,-0.2784489323473947,0.8292632221466938,-1.034693880976207,0.23209786129164806,0.2511695457072354,-1.0895934912788325,-0.3496862083411345,-0.28688720734934736,1.0537366088435507,0.45880692839616516,-1.012212056509676,1.0301104137531336,0.35199780629469135,1.5340830255624796,2.062302397285305,-1.1880376398807655,-4.846128478693288,5.0980308581823195,-1.5761669058368384,3.049024545678871,-0.9222784137580529,-0.08347023934591577,0.16549213868835272,-3.275704436749047,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2166871,1.0,0.0,1.0,1.0,8.524597267401742,1.578669465167279,0.5319701271474749,0.9987620569728738,0.034414763261879554,-0.03058225083233281,-0.018833575204166588,1.0454767230027269,-0.11676319526066732,0.0808584114282964,0.8569099327510746,-0.44008593733315726,-1.2294500338139316,-0.2770122508544483,0.8518977898055411,-0.9989844956368844,0.21957355831964978,0.1795945069056526,-1.0141802183564288,-0.37913890544863565,-0.23785858610585175,1.0366359931190146,0.4545406582222867,-1.0115141402947416,0.9915300816820967,-0.03657616422152973,1.2753263166582665,2.2034451275740117,-1.1952747775949972,-4.0966816240303325,5.829152346941324,-1.8281669805492307,2.8374667026890585,-1.065100763317168,-0.48875187270664844,0.21650961420490375,-1.6892071460086198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2333538,1.0,0.0,0.0,1.0,8.541771666772627,1.5758302404175313,0.5340995811817945,0.9981040875066316,0.04260208042694429,-0.03366009833234317,-0.028987773734928935,1.0537867690390281,-0.11364251271877657,0.016665498227398948,1.1107971611493945,-0.41288101374957514,-1.2698663096881706,-0.27966814025985665,0.8717741843903904,-0.9612455631607314,0.19225528902016298,0.1146132184607827,-0.8952880244372986,-0.41062522957057424,-0.1923047947619319,1.0182331790595942,0.44251516672248536,-1.0049950549355382,0.9738033962723699,-0.36653048779924613,1.2592970278542646,2.1369820940247997,-2.7599141134907703,-2.301036653588427,6.358429586064431,-2.0602000329713936,2.4521348648907164,-0.5939774382238652,-0.6188358469564016,0.6696075774398297,0.26425838146732017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2500205,1.0,0.0,0.0,1.0,8.559337899479786,1.5727219849153122,0.5344662962330604,0.9970965357155102,0.05340153808652453,-0.03710696164512587,-0.039621302244991795,1.0517653636065312,-0.10543587675029045,-0.09145570030108857,1.270346823435998,-0.46173594150456704,-1.1949007866057033,-0.2892299582164557,0.8938744413538184,-0.9277516167039181,0.12757623720901654,0.10289313171692813,-0.8022321415923087,-0.4478123772276843,-0.15612059380050355,1.0168367055797232,0.43391275540135016,-0.9891938430729088,1.0003387120148994,-0.6777223963384575,1.4833875578872722,1.727861607668334,-3.118809350641591,0.003984402498996072,4.7650593207752525,-2.284356121262077,1.5472059665669624,0.9651156400931962,-0.3048995164968415,1.1471723999008832,2.2590997844500627,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2666872,1.0,0.0,0.0,1.0,8.576598683963255,1.5697534298326112,0.5331381735780937,0.9959142770388576,0.064134878104934,-0.04112763185967107,-0.04847667581683368,1.0822667166196875,-0.11076515701814696,-0.20660264473999096,1.03514284550809,-0.4402942111070493,-1.0908293087411827,-0.302258931985965,0.92122053521247,-0.9036500610476798,0.08829476941148658,0.11474603214304274,-0.7364523960741688,-0.48677058590305156,-0.14073115939596872,1.0504037647370768,0.43235182917928955,-0.9667558984606821,1.0491068730273576,-0.6609004986197368,1.8589728453581307,1.0823979956827623,-1.5755797118141364,1.407294955043946,2.6207262302070573,-2.015377659871177,0.4406828390021208,2.7194453614669873,-0.07752206491147544,1.0107315393804155,2.833017808019798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2833539,1.0,0.0,0.0,1.0,8.595391884006036,1.5662561497175493,0.529904062225175,0.9948440814419568,0.07098768501713108,-0.0440506711425071,-0.057493830692627874,1.1383274731047102,-0.11374865425837899,-0.28286054348387835,0.5574985757037869,-0.1987789846496058,-1.0970820692869931,-0.31126001889714683,0.9558403267972791,-0.8916716113546264,0.0750568084432312,0.14980305737139,-0.7148744258703248,-0.5149917669152342,-0.14143113645491026,1.1074850655916468,0.43132868140283,-0.9555027243781257,1.0947728278167466,-0.4144382021409725,2.1039108770324426,0.32577282225740595,0.503126008831671,3.0277099716107005,-1.583087764837312,-0.8781996085312794,-0.4472655048051435,3.034485579611339,0.0014376764771193444,0.7048954609052871,2.587923938931677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3000206,1.0,0.0,0.0,1.0,8.614638229809147,1.5627311225998854,0.526302322654883,0.9940810318896364,0.07402531618562745,-0.04362638534022498,-0.06648227660813101,1.1492464272416,-0.09294448795713273,-0.2772938071440753,0.08155103595731264,0.18806423363389257,-1.0511692096739516,-0.3160735663532109,0.9913510380409433,-0.8927909452542447,0.1050656699142762,0.21566989971073086,-0.7892220937745968,-0.5160439647340681,-0.1556400393738405,1.1515534863564933,0.43239975182437196,-0.9432593361041418,1.1353711768533428,-0.15169210239518247,2.1372205339516612,-0.5506967784773681,2.073242030360724,3.501461508382784,-4.249536045495875,0.7816360351452655,-1.683355146674035,2.1369907378930693,0.07364248670157862,0.9207900501177606,2.1491919669041644,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3166873,0.0,1.0,0.0,1.0,8.633718914843763,1.5592151459621912,0.5232691223025111,0.9937196330466296,0.07334381341538117,-0.039697565194691344,-0.0746061609317547,1.161423882211717,-0.06804054049133593,-0.23174921139893523,-0.3264246838286433,0.437333172032128,-1.0244263189663292,-0.3163164324231264,1.0270811537437035,-0.9100282073503239,0.14416501433805737,0.26651867441491667,-0.856525910689257,-0.488937180301323,-0.19754308690105454,1.1787182326541317,0.4337834358690484,-0.9248096613215303,1.1664127033263498,0.21560812817333266,1.8480623496212194,-1.351915425607796,1.8672672505145038,2.9721768736445853,-3.7176932058688954,1.9493854563413773,-3.438837797848778,1.5629659989396891,0.21011161179963528,1.251500926487585,1.485514592342945,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.333354,0.0,1.0,0.0,1.0,8.653170375613485,1.5556272389748063,0.5209714904578658,0.9934829955486894,0.06984691760500664,-0.03470206798485995,-0.08311866297202138,1.2072392858790313,-0.041952363596344355,-0.22221962137676857,-0.5743011828310739,0.5016381385481845,-1.047768684287878,-0.3088866143735579,1.0529532395658072,-0.9378548829021996,0.16730803608257636,0.31474266031067527,-0.9131454484831071,-0.45106431956365844,-0.27026819522465295,1.2036524571855496,0.4394034862251339,-0.9015425551211605,1.184888428965747,0.2856202039016064,0.9714506570174155,-1.7940971001467336,1.6150619306794953,3.283766942913651,-3.9263275841268563,2.142490887877141,-5.029265748091928,2.0431977559590466,0.339018066796272,1.4763179931712715,1.0965120753878037,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3500207,0.0,1.0,0.0,1.0,8.67367993485118,1.5519938808721536,0.5180572258674753,0.9932201541643202,0.06513760075764465,-0.029366007173695533,-0.09169763329561044,1.2586891988982298,0.006704139978460921,-0.2318032319450219,-0.7694822265740963,0.497507667093088,-1.0045967869961179,-0.3067957399183926,1.0594629070743278,-0.969831563628355,0.19800051969816926,0.37597779142983456,-0.9874037585819911,-0.4175206745393591,-0.365185613788502,1.246824960732617,0.44508406069679524,-0.875598963127955,1.2029631789400816,-0.28896487428375633,-0.08479465363665926,-2.7202082409669224,1.627509303238733,3.6675168327322454,-4.038547419121666,2.0029881617668974,-5.779906627613588,2.677895019892123,0.326493483887293,1.706128545339148,1.0038913943241081,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3666874,0.0,1.0,0.0,1.0,8.69493171372676,1.5490002812690724,0.5152999828132185,0.9930228548829333,0.05836356497599481,-0.02417893064075094,-0.09957250261247474,1.2868588626169544,0.07776570888709256,-0.20438491695415,-0.9724595445560433,0.45050616868752835,-0.8757536873637197,-0.3185187961140081,1.050126745458275,-1.0285286722816465,0.22155845469115434,0.4369934659028723,-1.0477639650236572,-0.38429791397221774,-0.46293213480554773,1.2929158030416217,0.4502866241209426,-0.8446714898679526,1.2183515423693103,-1.1622851668431986,-0.27933576885551337,-4.351633245815208,1.3720081928808725,3.7064760549931814,-3.4249038322664527,2.1635796480754896,-6.088448883781737,2.5846938710160288,0.2955945336854241,2.0449211276370933,0.7410263865730589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3833541,0.0,1.0,0.0,1.0,8.716586218074225,1.5466700411657521,0.5131730019380679,0.9928964417001468,0.050147329371815236,-0.01942426608450358,-0.10613481663968802,1.2881774527308483,0.12850530626031706,-0.13107516529696872,-1.1200512700921843,0.36545832825670277,-0.7187367100902361,-0.34553865629884367,1.0501516961567594,-1.1148862952644116,0.24373421759474453,0.49952724036134427,-1.1015674479844617,-0.34540120869819957,-0.5681343158111521,1.3329815954127426,0.45493723152594495,-0.8074347892119768,1.227664107894276,-1.7320506558285633,-0.35072572128337026,-5.432287329725767,1.3551151893168547,3.6071036178901617,-2.84483934562536,2.19131476789611,-6.331014788147571,1.7770296103023873,0.2907549859798052,2.50560451479119,0.2271211057362867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4000208,0.0,1.0,0.0,1.0,8.7379807534649,1.544449207471153,0.5125994994765622,0.9928076485813614,0.040708137024807016,-0.015531705236417073,-0.11151047767257828,1.2664597102904769,0.13347990422405748,-0.0432166223120759,-1.2698198947771449,0.2983228265275325,-0.618126332653465,-0.3762539334450039,1.038435864700448,-1.2096052787583274,0.2667290513427288,0.5572304936394522,-1.1425921328671256,-0.31125394228802955,-0.673966383144786,1.3521502418536753,0.45997847637060185,-0.7611511723346119,1.2259222610352603,-2.353983475101166,-1.862881092803875,-5.454731306270727,1.3430980070911054,3.265909579295102,-2.004230247567986,1.9349097267653523,-6.252701372783464,0.5000194961392939,0.37617985345003757,2.730977844853183,-0.40061551764518155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4166875,0.0,1.0,0.0,1.0,8.758768434120816,1.5417048456142919,0.5130316286286819,0.9926752293640749,0.0298515157295512,-0.011697296125742584,-0.11648154050739688,1.2388187940493045,0.08987729483254861,0.009907968764692791,-1.4712251138688714,0.2768778116173613,-0.6193807198273835,-0.42400492906778087,0.9880555355378907,-1.2967110357888563,0.2885042407043152,0.6083911107318196,-1.1683752565187444,-0.2809040888120394,-0.7765581117506924,1.3496489452853522,0.46747658505293643,-0.7164020123183477,1.2143102305984022,-2.667474647986349,-4.930113668853234,-3.8106209899744137,1.5211798917517227,2.94623549101043,-1.4448904939468288,1.8414201186423516,-5.848362498001421,-0.7534804626970422,0.4998107720649967,2.9007702883629762,-0.8814100228275111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4333542,0.0,1.0,0.0,1.0,8.77882371133492,1.5377614521267522,0.5137866158018605,0.9923662361282874,0.017024126542657676,-0.007781736321139776,-0.12189699376056821,1.2070811715745378,0.0727030999671052,0.05266437477349407,-1.5462998757099808,0.20868642931297443,-0.5055821372105727,-0.46516993287619207,0.8740984137310955,-1.3366262324655405,0.31743514914644566,0.6554385397554993,-1.1907552456580528,-0.2498731489052766,-0.8689121896356665,1.3270341761984097,0.4766388687601532,-0.6644586360044935,1.1965418681803417,-2.4746348592653344,-8.165268633120085,-1.0180859388622276,1.4201309931312733,2.7390752894701875,-0.9316875555414215,1.7699012724185836,-5.020880759991981,-2.0107967810122633,0.6260797412536497,3.128130088587437,-1.248124598768022,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4500209,0.0,1.0,0.0,1.0,8.798355222929228,1.534253776017372,0.5153268010108973,0.9921360477069097,0.004770531040221691,-0.004934403627920287,-0.12497582380182093,1.196662491048816,0.06756870415387112,0.10108646185919168,-1.430136316242299,0.02558289824003529,-0.34574084042603803,-0.506492922685616,0.7158793700826457,-1.3306473016233265,0.33584203515075717,0.6996938029858452,-1.1994315704826288,-0.22190726173800177,-0.9439211384758092,1.282622251865158,0.48834595150004084,-0.6121308008234272,1.1727059940978282,-2.385995264488666,-9.839167817078469,1.1655805170239866,1.20092516695083,2.714120659897884,-0.44076547485470596,1.4600866806693782,-3.924867488247256,-3.0623704897869337,0.7205576886435608,3.2730179228236023,-1.4976421684869847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4666876,0.0,1.0,0.0,1.0,8.817985976310394,1.5300217960365115,0.5175229479631732,0.9917808353020261,-0.006547752423167528,-0.0043513624442991,-0.12770656721836438,1.2102472181177808,0.029583122157651298,0.11464753913577341,-1.3336463069523654,-0.1663061420864047,-0.2882095992193359,-0.5447032674254986,0.5461254972172921,-1.2977734708593731,0.35746606810648446,0.7459094093601394,-1.2054474575375747,-0.20120349554385195,-0.9997413675684076,1.224954955714146,0.5006575064187845,-0.5553578203758452,1.1466203627212976,-2.1404198547312125,-9.908537225291498,2.3191653978421174,1.1784670384923477,2.650927726620698,0.03332119996536653,1.0673908749388907,-2.9185952731862765,-3.7551467886770293,0.8263469307283797,3.3814425625207596,-1.5576728521470111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4833543,0.0,1.0,0.0,1.0,8.83760274517312,1.525044713289303,0.5195518727961561,0.9913709804802675,-0.01760955094599475,-0.004869979067642793,-0.1298066488318459,1.2250544745965952,-0.01571198731698442,0.09499943986492532,-1.2235556019168015,-0.305191668471064,-0.26977033917824034,-0.5778403938713134,0.38559413533711406,-1.253341633750896,0.375124348331638,0.7880582372683835,-1.1983208615957033,-0.18632749474731375,-1.0412078421550366,1.157450441899471,0.5158909042807822,-0.4994158233098977,1.120783461848071,-1.3507797573527427,-8.71718665191783,3.159694790005712,0.9609235632504659,2.49660795912566,0.6736906824419736,0.6264518320412735,-2.0077821837816003,-3.9101763168914347,0.9595354642674906,3.463149913998264,-1.5475981302409847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.500021,0.0,1.0,0.0,1.0,8.857292157125103,1.5191277188676637,0.5212860989975426,0.9908261160235657,-0.027405523662353517,-0.006831753545327367,-0.13215851172718132,1.2346003160460592,-0.07344961663695337,0.07836222778366247,-1.0039427164109231,-0.47944892111376974,-0.31512782612212875,-0.5897293493892405,0.25555202767425433,-1.1924501005461967,0.38949691760973754,0.8291298411048587,-1.1829910565434634,-0.18032172604568736,-1.0666675742132732,1.094615484472677,0.5326420858633985,-0.4399192590325755,1.0950336552067228,0.023364662358952428,-6.510592049813072,4.094447117828397,0.9171809082282127,2.483814373564465,0.9941260796234689,0.13718231967047329,-1.12312229045706,-3.4211698899508987,1.040390141054071,3.583531762779167,-1.293027896265672,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5166877,0.0,1.0,0.0,1.0,8.876656213226639,1.512069812357997,0.523143574550392,0.9901773158293857,-0.0352125625169424,-0.010728654174704514,-0.1348845974805986,1.2204307774009249,-0.13143327654747405,0.06818052868211269,-0.7703308486168801,-0.5825891827505273,-0.3772428850131315,-0.5770615702350375,0.16857396630387503,-1.116859790193475,0.4056971064179723,0.8708522153081573,-1.1651832593331823,-0.18175474161281,-1.078645326711758,1.0434112174897818,0.550570645008594,-0.3799645256484746,1.0776824457706888,1.137772747767146,-4.6416855341877605,4.737488017786128,1.003382288008244,2.4392228085796277,1.0822341743886834,-0.24942818257088326,-0.3622424498847344,-2.6447606692011587,0.9965148418073376,3.474574953351781,-0.9138699943889733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5333544,0.0,1.0,0.0,1.0,8.895283317517297,1.5042459711070353,0.5250962320786864,0.9894314051357419,-0.041359333595186114,-0.01494491378816344,-0.13817217378161917,1.1846641208349284,-0.16883920654322848,0.045737695844886364,-0.721070063884999,-0.5746854623649689,-0.4210181604004259,-0.5518035152788191,0.10082886708896005,-1.0345335174541246,0.42294306076883154,0.9104374306723668,-1.1469165119148956,-0.18863601542659564,-1.078742346692261,1.006456619181927,0.5658593136912992,-0.32409986228251925,1.0645712611357574,0.36491407299634265,-3.452892672048309,4.489834854281708,1.0636611886971634,2.213680480881908,1.1598719593454447,-0.3484681226905337,0.38387726700177244,-1.8865652088876355,0.9795420552059776,3.2360666588311733,-0.7058969340085346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5500211,0.0,1.0,0.0,1.0,8.913046203270273,1.4960586693706357,0.5267188231312858,0.9885623541242363,-0.04831980362714134,-0.018833366972023473,-0.14161558132592492,1.150417793269355,-0.1726905765642116,0.022041806183532717,-0.706097886708922,-0.5028618417816704,-0.4538176914424695,-0.5648977434742212,0.05347731370941994,-0.9671983290617611,0.4411525502852903,0.9446417122495863,-1.126520783363537,-0.19337036893370263,-1.065849392219881,0.9805255847558467,0.5832221121515969,-0.2720954212829916,1.0541525009106087,0.7643888212257508,-2.3927528508192744,4.60816307413686,0.9773997951860793,1.8668482451288833,1.3772150452683076,-0.28946141975370643,0.7918003986302201,-0.8541467938587299,0.914875729648521,3.076375648978125,-0.7046296616376251,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5666878,0.0,1.0,1.0,1.0,8.930425827276814,1.4881543448316636,0.5282989401446816,0.9876428003876907,-0.05403341588331649,-0.021936360146141615,-0.14546781401354555,1.1221295623237104,-0.14521415215134936,0.02118374270036835,-0.5798732236036622,-0.37644283719855726,-0.5170064353124084,-0.5263238369453727,0.021070279211460853,-0.880927774438691,0.4555231191016872,0.9726658299665459,-1.101009251924949,-0.19828474871581384,-1.0523489472845604,0.9779850024435165,0.5963552323379652,-0.2215538022248718,1.0410835587725258,2.6474697999341803,-1.1287937295999035,4.2416779035623415,0.8135088849148132,1.5926396112246701,1.5100629921562032,-0.07531256172866155,0.8053722002227045,0.6392755728272796,0.7652306774786737,2.7248249204968116,-0.6393230076467797,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5833545,0.0,1.0,1.0,0.0,8.947409740973985,1.4808720569820901,0.530114645893555,0.9866543939088355,-0.058582978836510306,-0.02409818877573674,-0.15000139622269687,1.125844533411785,-0.09644712620672558,-0.0048608939485853125,-0.3361919126706098,-0.3100384439281945,-0.5502184143105122,-0.47664857364509516,0.015850780803174515,-0.8258087828311561,0.46826956734970976,0.9977298054663827,-1.0761852496207973,-0.1958807926788288,-1.0390035985209776,1.0018348131351276,0.6087298524162645,-0.18126774227810316,1.0328416913675156,2.079862555048112,0.5899235647579366,2.728422072918592,0.604882573992241,1.618139987188416,1.3547873691866736,0.19414168419502623,1.038459394758807,2.146005084548381,0.5956091927711578,2.20568656063961,-0.1219275682946725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6000212,0.0,1.0,1.0,0.0,8.965265834372529,1.4740839126361018,0.5309307659428552,0.98582420929375,-0.060119142121209106,-0.026744625867265608,-0.15434066900263957,1.1663497415077737,-0.08159446411240107,-0.07932252769768063,-0.019584688450557185,-0.19636768013925637,-0.49213105558307624,-0.4569949464529319,0.04073443736496306,-0.7899801901132664,0.47568591189360016,1.0266039374154923,-1.055849582632902,-0.19181334629986735,-1.0177335648953072,1.0495186483288015,0.6162089118042833,-0.14803076982444743,1.0370192983675321,1.1553592495902893,1.9354041288896466,1.8425499995942944,0.3912488143731881,1.7865187072582438,0.9524542493287792,0.2244135635938651,1.2375708173607294,2.6056555679227533,0.31964129359036225,1.6316100309504475,0.6064176594888869,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6166879,0.0,1.0,1.0,0.0,8.983634232435723,1.4662603413602309,0.530564978132144,0.9852888876488487,-0.059185973957771726,-0.02777716114293161,-0.15789635106994687,1.2007872027395863,-0.11115629540588862,-0.15848363911119676,0.2345449049362259,0.04447544342082504,-0.36368201595609606,-0.4381365216348022,0.08036438079310466,-0.7643903266746797,0.481311220578737,1.0572805481429046,-1.0444367111462214,-0.18840032559812905,-0.9977511554375654,1.0886901724429239,0.6193845835120295,-0.1268806324724195,1.0530556537783224,1.208729189966066,2.3875666267494933,2.0870917261233,0.22808072356685233,1.8036990739661019,0.6270711111859383,0.1991438685000829,1.2142519204631934,2.2026187886749344,0.13904716734060418,0.5021903525550883,1.7310266213392638,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6333546,1.0,1.0,1.0,0.0,9.002259951672453,1.4576044668358679,0.5290318054731181,0.9851190053629532,-0.05597688362508069,-0.026999598918911096,-0.16024404959482272,1.2432479615337098,-0.11974551617704188,-0.14881621827855984,0.5303699926456606,0.3475222353029329,-0.30797196846792485,-0.41670389287211707,0.12032015076105461,-0.720410326769708,0.48328861788454347,1.086727360127634,-1.0349471704552966,-0.1851752040736067,-0.9772584199297394,1.1229394214592185,0.6208438266521146,-0.13129105792658766,1.0947203011472824,0.34384819975682523,3.4055882659146985,-1.0116843822051007,0.028349834694667023,1.703322262569137,0.4310968366464039,0.05200197549109528,1.5736997671215283,1.5445185472240548,-0.5314858094525029,-0.9561765940494393,2.3438157013078813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6500213,1.0,1.0,1.0,0.0,9.021789824490972,1.4489501515432075,0.5289964016348327,0.9850964269043514,-0.049404680921638355,-0.02378112687695019,-0.16302964518078766,1.3017927564308402,-0.12713630831410355,-0.09136759832797225,0.7948022463578318,0.5877725998730916,-0.3468769766437041,-0.42667489205302805,0.19388421669614567,-0.7981132068604752,0.4822562169585482,1.1140580704500267,-1.0300667878515521,-0.18666692294829418,-0.9452943916201967,1.1401742269849622,0.6016683544312255,-0.1587532493525071,1.1311830000762986,-0.2922148858346769,3.5225184492064963,-3.3640946686498405,-0.2739742234110246,1.3438054342089456,0.38089658773611895,-0.24435674458993578,2.022198409044827,0.7334595224628018,-1.603305757180816,-2.228144825445407,1.8094430870174805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.666688,1.0,0.0,1.0,0.0,9.04201985255271,1.4394565632261507,0.5291162989380972,0.9850483457469109,-0.04119126365581029,-0.019796919533174098,-0.16610574438203182,1.3762837634328684,-0.12549079838053828,-0.09668920940370213,1.0457452078936882,0.6910863316243554,-0.2669806801517857,-0.4264444085475987,0.23773766723583442,-0.8325470399976805,0.4741561255058944,1.1315209641882944,-1.0222505921376535,-0.19332044518372085,-0.9098516714816846,1.14738812110528,0.5674001945257036,-0.20556270065108959,1.1550351913440708,-0.5152894083534709,3.4557910363572297,-3.2970109321394245,-0.7856851030259816,0.9934251903406168,0.01028124857853984,-0.6165231730323923,2.1931727403695462,0.3268858613754795,-2.0518042411022894,-3.359431368945251,1.517040112961966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.683354699999999,1.0,0.0,1.0,0.0,9.063804431343426,1.4297914828822664,0.5285158674859242,0.9852781793579747,-0.030226765801366663,-0.01553525578254439,-0.16754673299708062,1.4362393093839732,-0.1439835377497387,-0.11377491590073692,1.1884922880503745,0.7486881137884841,-0.22173305681391625,-0.44385124001743764,0.30907748162745574,-0.9080137910658514,0.45606666114534195,1.1471723096897266,-1.0297240788801842,-0.20721773648425212,-0.8721884873963625,1.1510704441565356,0.5332747429408664,-0.27073451894610673,1.181751104977705,-1.035820062155545,4.118077630860337,-4.222813267515872,-1.2154669447317414,0.6592694478946194,-1.5272347093604641,-0.792177652993583,2.371131118992314,0.07603843239463136,-1.8482271708196563,-4.514667815866277,2.0316755094702668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.700021399999999,1.0,0.0,1.0,0.0,9.085672200853109,1.4189283193517557,0.5275439502132728,0.9852224932664959,-0.019530234089976322,-0.010923365038580542,-0.1698113329974593,1.4579925858915863,-0.18566918995526016,-0.11681184917944559,1.152685660037475,0.6997775039005659,-0.3068259089047018,-0.4609718130074543,0.37500719613635436,-0.9733077637690941,0.4336404796503734,1.153496656402745,-1.0731585175986496,-0.21972641976201715,-0.8308138094398662,1.1499227405876633,0.5057924989499036,-0.35605192882448655,1.222757843771447,-0.8292449003551886,4.066411497151784,-3.8546676673336244,-1.286520377367151,-0.2120709523266076,-3.807363928804463,-0.766791061385644,2.646287349920615,-0.11483016588308313,-1.474006505937833,-5.14077048377373,2.695931265852947,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.716688099999999,1.0,0.0,1.0,0.0,9.1075743261008,1.4075588972386397,0.5262096594758432,0.9849182191094156,-0.00926852291714843,-0.007399984548846927,-0.17261354633385062,1.451088753938575,-0.20976037375657275,-0.09399944449744813,1.0379682129486867,0.5192144880958207,-0.40973548793497355,-0.4714927919789373,0.444624802626615,-1.03650297028815,0.41318256279841176,1.1401032638074429,-1.156636463664595,-0.23277748964984435,-0.7839787326465186,1.1472427643050884,0.48414109447583825,-0.44209387778993,1.2716156602348876,-0.39821555165395817,4.026859782806755,-3.3709075697215507,-1.1225154027679647,-1.1076088584976096,-4.5552979460822565,-0.653215645427307,2.855191907975659,-0.3137816413413228,-1.3096798007600723,-5.197963293734222,2.751182354231001,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.733354799999999,1.0,0.0,1.0,0.0,9.128811488066704,1.3958488843330183,0.5253811495899974,0.9842849027369848,-0.000956224155236381,-0.005432904447040003,-0.176501556448318,1.4174977474110064,-0.23507952905670593,-0.05267599665913749,0.8382962549577846,0.29227880353850055,-0.5258630433965739,-0.47424569127695637,0.5092361240205651,-1.0856715741536505,0.3962232247237477,1.1165762872789007,-1.2250020861545878,-0.24150031815730374,-0.7356405554945503,1.1394633316241765,0.46213641827924784,-0.5293177184798469,1.3144641056579707,-0.0073792313644788785,3.764641493878856,-2.4565342717506584,-0.8553422519713678,-1.3272364216264814,-4.877317241706204,-0.5018150390394681,2.9753412183145125,-0.5319231297692721,-1.2509508910770026,-5.586261046129121,2.125058632976579,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.750021499999999,1.0,0.0,1.0,0.0,9.149173058118773,1.383787671014816,0.5249749092273766,0.9834221014026904,0.005382851101341815,-0.005065136446385873,-0.1811804067208064,1.3764188405057838,-0.2517516920290057,-0.0324354254308581,0.7080072390961732,0.08721797453711738,-0.6420298266170814,-0.471738766849702,0.5701131033986765,-1.1183876097821235,0.38467109737654936,1.0958619612707987,-1.3192140302092845,-0.24950469107216255,-0.6848004936799537,1.1295119578512374,0.4424426480432121,-0.6283029517449704,1.342451089671349,0.18764607474438763,3.51882486139116,-1.6476697171432013,-0.5764037582101552,-2.388560723795909,-5.200031262586799,-0.5249959869735729,3.165703398218095,-0.6314223963987846,-1.1594404368150983,-5.934877892708837,1.1494129645547595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.766688199999999,1.0,0.0,1.0,0.0,9.168700572066466,1.3716657702895154,0.5245634243267031,0.9822866865432086,0.010958773168478682,-0.006072869285996378,-0.18696494588355697,1.339255765399863,-0.26095282395023994,-0.011325201384601228,0.4717171916113849,-0.11982046707607616,-0.7551978173824248,-0.4679908096090718,0.6265305206552612,-1.1405940079030716,0.3770097276898253,1.0369574372483221,-1.3983368082428986,-0.25900021938948864,-0.6301168978403873,1.1184158763160572,0.42348832642271544,-0.7271473772286676,1.3527779477706603,0.47308097970416124,3.3481373487040984,-1.0106381346088937,-0.3604046218833359,-5.270110795303423,-3.567004395170441,-0.45966990424612575,3.204051090970082,-0.47976311563118046,-1.0608660952218651,-5.421328830500196,0.013895280241276656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.783354899999999,1.0,0.0,1.0,0.0,9.187502929894718,1.359303496260109,0.5247401668169541,0.9809754376954484,0.012802058282995195,-0.008332314720235271,-0.1935300247334898,1.2926103704677354,-0.26303554614240676,0.025167282060814394,0.23602909782811513,-0.24528624221278347,-0.866853542527837,-0.4559693693208313,0.6817179048979697,-1.1520756149782956,0.3726575859534634,0.9201912500866316,-1.438114414515259,-0.26482705185836036,-0.5779985770442115,1.113519822012657,0.4070803741447436,-0.8090142741835656,1.3429142666057436,0.7861687304837777,3.0664161946250816,-0.3249712050327101,-0.2277475511824088,-8.214741261106314,-1.1716934227741307,-0.3893024083371361,3.105438322521631,-0.3713837125349542,-0.8857602177284789,-4.731029223860476,-1.1864154283396529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.800021599999999,1.0,0.0,1.0,0.0,9.205209001614708,1.3471699825737602,0.5256443105959023,0.9793988975549051,0.014148895859792508,-0.010654122082823484,-0.2011568987055367,1.260401457498571,-0.2554022609239496,0.031538342969736385,0.07995899199769385,-0.33586539809873767,-0.9950149499372045,-0.44178513284836385,0.7287445982371769,-1.151426403068909,0.3694181274672416,0.763132180895361,-1.4373933337815978,-0.27197699228755373,-0.5266020800604447,1.1060363944726446,0.39396292678108497,-0.8848486667592984,1.3132306877316433,1.019849296131093,2.7658936286368916,0.13546442672775305,-0.16044650063648058,-9.627909965738263,1.0644931167741305,-0.4210140146969045,3.040824196929921,-0.270024083179121,-0.5022900512716421,-4.21801213321203,-2.171848590664539,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8166883,1.0,0.0,1.0,0.0,9.22272691852163,1.3348907739468958,0.5261559855447375,0.9775492193471116,0.013153653601762228,-0.01382830583120908,-0.20984109013397756,1.238421094067146,-0.23358739753700947,0.03200620034052589,-0.06325261112302585,-0.4673282021020314,-1.0459544139490542,-0.42197432479317515,0.7739145435787746,-1.1475601250564087,0.3673093585691473,0.5992602760346918,-1.40263123965658,-0.27886088041585816,-0.4766375677582677,1.104519001238414,0.3903373389496854,-0.9496149598247755,1.2705191687936863,1.1440770785417504,2.5956433522067717,0.5601009244804201,-0.35283904521849374,-9.484934950444996,3.1579703916911877,-0.506743678975638,3.196147076641889,-0.3801466684056369,-0.28391877255794473,-3.1561535307568858,-3.2005908303133985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.833355,1.0,0.0,1.0,0.0,9.239612250129971,1.323100007243571,0.5273531548327789,0.975645371220499,0.01171718855297915,-0.017813324419646722,-0.21831514510347033,1.217238926772268,-0.2109114428372435,0.0410352424243373,-0.044809048015611225,-0.5356525301114832,-1.0513782101898406,-0.40364915395850026,0.8152662163536261,-1.1327563349128333,0.3576568024373555,0.4469670502181977,-1.3321274435271988,-0.28886848203632026,-0.42006363109591,1.0933648135160121,0.38449894876790197,-0.99005399486143,1.2065441133484747,1.045291682934949,2.3399541625663827,1.1272402544777416,-0.9739540103036958,-8.21494909238784,5.2072403045768585,-0.6153103453110551,3.4059022715295724,-0.7177035669756197,-0.35721635196412876,-1.8512668724160202,-4.075149597146609,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8500217,1.0,0.0,1.0,0.0,9.256361646506932,1.3112102165400723,0.5285099162715751,0.9735704825311787,0.010786024075236532,-0.022174698319785132,-0.2270516680913901,1.2180283023981129,-0.17524952345928813,0.049781477991318795,0.041587994074053086,-0.48894608004475704,-0.9805246707516868,-0.3871311990092313,0.8519131716612649,-1.1099853747578003,0.3348441599620901,0.325428091958491,-1.2290562156879978,-0.2993712662802497,-0.36310726498046386,1.080595501158989,0.37843010340312433,-1.0113239789897677,1.1346805772121595,0.8001705026150497,2.048913059526993,1.5343210691124498,-1.2811361670108492,-6.52637196008983,6.526333326520794,-0.6778341494690119,3.4047471907422553,-0.9804867891830468,-0.43697529531195617,-0.7208490751582802,-4.511462426360994,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8666884,1.0,0.0,1.0,1.0,9.273327591572938,1.2998746674646158,0.5303831920143158,0.9717630375779968,0.010904873571439407,-0.025736444858367766,-0.23429749878227063,1.2173649293761684,-0.11995728971385528,0.08238726287108575,0.28815801614445236,-0.37682721345343917,-0.7670387093200445,-0.37697675052663177,0.8835634549320631,-1.0816121969876804,0.31495217812791604,0.22942088312373937,-1.1145825642209506,-0.3114629988742306,-0.3065718310880221,1.060681855177458,0.3699330764591504,-1.014082345423311,1.0561617317056131,0.33252687720091423,1.7505201367558407,1.759263861578339,-1.1420354381529991,-5.193846114391748,6.449134459294029,-0.8224619617860959,3.3311413691512586,-1.3456507362423324,-0.618037682384507,-0.2491558256137723,-3.56309868475639,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8833551,1.0,0.0,1.0,1.0,9.290461654851073,1.2891255818460134,0.5329412821962534,0.9703713265498154,0.014302966748294127,-0.02928856483186309,-0.23940988643378677,1.2207970075828853,-0.07859464395489979,0.08816157856375384,0.6061788073827581,-0.26830292558707036,-0.5676709607785897,-0.37604694760074237,0.910263959587802,-1.051343128754265,0.2967762358879609,0.1522995418890251,-1.0140846371025662,-0.32678671983725033,-0.2520689972659973,1.0357403869075288,0.3578288061211286,-1.0196291897872818,1.0159103835137009,-0.10657992090791786,1.5064961006213817,1.8789848021939304,-0.9935468263911287,-4.134435955769367,5.945315043621469,-0.9318657676653351,3.199874524224918,-1.5471239297067783,-0.7925544818346069,-0.03240456872633695,-1.761794625118818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9000218,1.0,0.0,0.0,1.0,9.307884015714782,1.2785743225659951,0.5352405924231062,0.9692220192642439,0.019912767746597677,-0.03237514567534089,-0.2432365289106722,1.2271388636646698,-0.051230176711075215,0.03472796529435243,0.869758715785498,-0.24691459349581552,-0.48815066499259135,-0.38052942166222375,0.9337800920525159,-1.0189792449822292,0.28183388434509,0.0916060756356968,-0.9164049997458987,-0.3425252532541263,-0.19990913362222323,1.00911095437897,0.34351454089436473,-1.0151624998744935,0.9974351267486775,-0.44861170514151755,1.4443189141760255,1.8997435816540558,-2.1865320398330628,-2.6658233945731413,6.329095684655058,-1.0853855873380407,2.872421412358633,-1.1818764447786463,-0.745850377138426,0.6009504423678965,0.2396875378744373,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9166885,1.0,0.0,0.0,1.0,9.325553613710037,1.2682555464954794,0.5361735561155555,0.9679530312628811,0.027609565255402105,-0.0366494771697212,-0.24690374034954138,1.2002478058404864,-0.012664607442054276,-0.06006065132363414,1.0770738926904115,-0.33145510194711486,-0.4575352567624489,-0.3910007010129066,0.9584080196815972,-0.9880182160495576,0.22389168879138951,0.06343858434836074,-0.8031143590076854,-0.36296631177422417,-0.15632142535928203,0.9963444266231443,0.3329670771598226,-0.9995974683116557,1.0238999840886847,-0.7987911383966775,1.5721978555222156,1.6754978947103076,-3.6600866608424454,-0.09909955557204463,5.953983139461583,-1.4379959056547187,2.0661753291316947,0.16753573420248408,-0.383215608793153,1.1596731071168507,2.324013737952816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9333552,1.0,0.0,0.0,1.0,9.342875356146816,1.2590708057789692,0.5355099165494925,0.9666297547330629,0.03619786143400318,-0.04195028007969361,-0.2501135863833446,1.2294354930803792,-0.014224050935355614,-0.18850630664695472,0.9176065808871783,-0.3309847928283179,-0.35014525159964927,-0.40715584619485556,0.9861867920497801,-0.9631292034586927,0.15983075164456442,0.0883027505099916,-0.71793849816497,-0.3904585459756773,-0.1310364849061448,1.014695490021435,0.33074066172021904,-0.9765066523257246,1.074902406281354,-0.8592561877182118,1.9210872142737947,1.1495682603324702,-2.4024311712316977,1.9210676763099295,2.9597334538516162,-1.203473495387247,0.7588722159758692,2.2110536264276557,-0.04697481854450334,1.0342356236765962,2.916502112383292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9500219,1.0,0.0,0.0,1.0,9.361658882358046,1.2482095227009522,0.5324670112715036,0.9657413476851303,0.041257750773620726,-0.045595881614247546,-0.25211597123591656,1.2989342095623186,-0.052292169389045906,-0.2781444182198842,0.3296166581145539,-0.08526278545638827,-0.261375317751345,-0.41964263122059287,1.0224443882298713,-0.9496991974005913,0.14381048958825485,0.12747430162987014,-0.7044563798970679,-0.40308217518536543,-0.131025634235272,1.0700463615743079,0.33140124674335125,-0.9651228785733943,1.1211169156016019,-0.4899032774112105,2.171308845369611,0.3632721094045781,0.662349537715353,3.3587496079218306,-2.305607720853524,-0.005523414207072624,-0.6315524125055559,2.929484812052033,0.23153266391155164,0.8478432706304339,2.6071183606657824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9666886,1.0,0.0,0.0,1.0,9.380656129552237,1.23683378301194,0.5290419510551606,0.9652600141339305,0.041354287046488504,-0.0445185110628212,-0.2541279800214656,1.3060300477825229,-0.042031230531965114,-0.269806322459761,-0.1879956251990942,0.29425706396298573,-0.2235705290657463,-0.4234859881021144,1.0585638983160235,-0.9510201089270661,0.18190911372504537,0.20026129469069315,-0.7947922425672689,-0.39064266015080734,-0.1520882740931575,1.1123451790554904,0.33845843261944836,-0.9482451534484921,1.1618065254447707,-0.06624933995892801,1.8654798582890766,-0.38293742347345056,1.122841315372887,3.897223262598766,-4.303942890409562,1.2466462616163385,-2.2194961882770485,2.2249569902678092,0.37938175628186077,1.1970051238795676,2.024743657596343,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9833553,0.0,1.0,0.0,1.0,9.399677528315063,1.2259904935593968,0.5262227911845375,0.9651326002417048,0.03965303930212097,-0.0399074925013923,-0.2556444649646094,1.315902530676678,-0.01902089941231022,-0.22992856876820106,-0.5280914354908078,0.536244089337451,-0.21190863664043885,-0.4218509469691798,1.0846271745381644,-0.9624638037122012,0.18123860829010544,0.25738200353137985,-0.847921429840246,-0.3615272166884034,-0.20500898847758617,1.1442117429137009,0.34404733057819703,-0.9252226279770671,1.1886085058377238,0.2817790988770043,1.2533895284199623,-1.312989241491946,0.25468335827620986,3.5565846535864902,-3.2791372280633255,1.7198618605449605,-3.972448757073053,2.0422780715896462,0.41575731926407594,1.5556207138482128,1.2954995413093477,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.000022,0.0,1.0,0.0,1.0,9.41908152165379,1.2149310865630303,0.5238542981915226,0.9650473064725213,0.035285849485837455,-0.03349851930582551,-0.25751981341347646,1.3407931907301556,0.01384690557755508,-0.21253992955593926,-0.7647674446454751,0.6299452513410764,-0.2587359510115218,-0.4140933326876077,1.1003436328226575,-0.9947865045094137,0.19039857597980958,0.31881435358255306,-0.9040970354451949,-0.33331381680851796,-0.2845034974921764,1.1804212509270167,0.3523170376454055,-0.8963910259455041,1.2049899298550517,0.47879568386728816,0.033043821190538926,-2.2635750058949555,1.0994132860032204,3.7550876297511353,-3.8976553568367556,1.5028632749211635,-5.320159537065263,2.6057336544824006,0.5647670712617173,1.8662859008411459,0.8078775458455658,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0166887,0.0,1.0,0.0,1.0,9.439157770511745,1.2044301040084655,0.521288469010677,0.9648148043692935,0.030198619560346526,-0.026341464994059652,-0.25985873829536354,1.3542456053398135,0.07074786428267321,-0.191502179565801,-0.9434643519645607,0.6501961023718712,-0.27570876546997347,-0.40589105892055793,1.085728637447437,-1.0379164548137,0.21788579111776518,0.38255184152892635,-0.9778435349118283,-0.31143167400014626,-0.3823479943903974,1.2310697051120245,0.36287293727139236,-0.8630129735299689,1.2155378112244124,0.3344631630134337,-0.9043036876484775,-3.611464744951283,1.4475218352867443,3.8345876804044,-4.0447556536766465,1.4003552209032712,-5.873885754079703,2.842871811604681,0.5939628097869437,2.211885958224955,0.4082042057139895,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0333554,0.0,1.0,0.0,1.0,9.45966737853882,1.1945439203899977,0.5192471158742977,0.96460255557807,0.02305356814859077,-0.018812474371893245,-0.2620239179462093,1.3627088147891198,0.11056441786521243,-0.16836169679830518,-1.1656165882165386,0.5798112650240599,-0.18721936065595374,-0.4029445382896157,1.0702001162807957,-1.1151689034387728,0.23864940032415674,0.4466341985685451,-1.03892249355146,-0.28663521608806086,-0.48030008088721676,1.2751838341719601,0.3721158375691576,-0.8226613465456084,1.2185967639257984,0.2256848544077922,-1.0906714861868811,-4.859041583611297,1.1632610788491322,3.8038421170817385,-3.401935613937705,1.6319614733058156,-6.085093524268124,2.5195093815579486,0.6689833714499955,2.416776200119704,0.09853751207535726,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0500221,0.0,1.0,0.0,1.0,9.480443356160462,1.1847988853300364,0.5169863817526634,0.9646229744357387,0.014058154061083768,-0.011845167020333135,-0.262991592096408,1.3604234842101992,0.12969180906545785,-0.11435729288336022,-1.2418021741976082,0.41074002173960306,-0.09211575206671523,-0.39836821539464123,1.0493728485297753,-1.1998848315368489,0.25666123796347484,0.5093468323544588,-1.0912416155054594,-0.2570328494258542,-0.5851848508722365,1.3150535191312482,0.38517242758528364,-0.7824536057408987,1.2188224015294251,-0.2232867872165987,-2.2261501108708814,-5.1105287466812825,0.9725899675750872,3.6447431617006094,-2.622659652977499,1.6352373172538164,-6.370265313202253,1.9117234830742453,0.6900144644678563,2.6780845259358452,-0.23113104760833286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0666888,0.0,1.0,0.0,1.0,9.50103658341075,1.1753235780689144,0.5162829350500369,0.9645853134882599,0.0049083634699309585,-0.006741902002991817,-0.2636391999081026,1.3420451038926344,0.13819415043445965,-0.029264065161025827,-1.2072605116655857,0.21746878237276085,-0.029204516309081142,-0.41038744608262145,0.9959949641750923,-1.2855202023633987,0.27106913074932415,0.5681258802747762,-1.1263446568280202,-0.2321271964971125,-0.6926426826783127,1.3389080777226672,0.39511636571905046,-0.7333916838087785,1.2108923802634508,-0.6984408876356579,-5.191132331643799,-3.8412908266520485,0.8400765920293138,3.4784458231955506,-1.8257716168928868,1.1914189465225444,-6.3308103768291115,0.8461256656242079,0.6414804666716369,3.0852811516268375,-0.6812059702795598,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0833555,0.0,1.0,0.0,1.0,9.521313343650025,1.1660151928036058,0.5165370987711287,0.964626274139718,-0.004388373861929456,-0.0030355074504804396,-0.26356721933634236,1.3141897901159019,0.1539284647963715,0.01325793362448556,-1.1718398861827137,0.06272771107557257,0.13671006782955988,-0.4216496248785557,0.8763347580661599,-1.3279281151779723,0.28466384703622477,0.6252952583573653,-1.1521007911199967,-0.2173188051138396,-0.796212285487232,1.3432577643937662,0.406555152573036,-0.6796106950012607,1.1961154904397084,-0.719018690415083,-8.455286021593833,-1.2851026177970313,0.6771039517596845,3.304246944272327,-1.1513273412615943,0.8337565848199628,-5.6616031670328875,-0.41352303398890433,0.807208267520944,3.295034801509175,-0.9828933312987707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1000222,0.0,1.0,0.0,1.0,9.54136353092661,1.1574720596777637,0.5170474894255332,0.965108132240873,-0.013654872240078761,-0.0005568464212591916,-0.2614947943434131,1.2840078572414413,0.16839890608985836,0.053338788461377795,-1.0457334481328302,-0.17550923884641456,0.35157256039694623,-0.4343547836977036,0.7141515331028964,-1.3283570419634743,0.2936393076149104,0.6782676653669834,-1.1647223116252294,-0.20433525475267475,-0.8813631656862868,1.3251239490215014,0.4220233617836331,-0.6235569707561526,1.1781292036939364,-0.8069542838155372,-9.824226392248189,0.7865108103312858,0.3123301316740486,2.937471206940415,-0.19989249181886862,0.49605952499209766,-4.633678419724057,-1.525719696970685,0.9440366984548217,3.4523684584814873,-1.1188671404750652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1166889,0.0,1.0,0.0,1.0,9.561104470532783,1.149303655290131,0.5185197391854486,0.9659323259617086,-0.02196659939324018,-0.0012042054608477986,-0.25785802307182215,1.2769638754777304,0.16070630636207522,0.09061952102005712,-0.81450821531889,-0.44683929016922963,0.5624521290740371,-0.4485481548026925,0.5488598900427941,-1.3017110357328754,0.2950748722473685,0.723211161086793,-1.1587638875067918,-0.20078345454346802,-0.9506685417232619,1.2924003394467636,0.43802310545730994,-0.5645315162273139,1.158819844499397,-0.9600678042584624,-9.418154143374391,1.9451495809163932,-0.08089208241769354,2.737488642366405,0.632518360079439,-0.1293108799007523,-3.6524743359981247,-2.410125522670998,0.9333557056056117,3.47597695382514,-1.1312522274385794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1333556,0.0,1.0,0.0,1.0,9.580964516161867,1.141039833047463,0.5204224493771434,0.9672219853654792,-0.0286922053595803,-0.004021496616343346,-0.25227408892359376,1.2915942645166565,0.10563619353359865,0.10690197663760231,-0.5555817944357777,-0.6141619373753342,0.6945698518084498,-0.4663571078441726,0.40021243378014043,-1.2635185929229558,0.29094289947484847,0.7695174692784397,-1.1436383241213575,-0.20864562603675849,-1.0031125537178467,1.2447862709241,0.4531352808608672,-0.5076908405635177,1.1404207206958352,-0.7944981408955831,-8.236469255786563,3.178612471926801,-0.2530717303053641,2.704808017656579,1.13515150734792,-0.7911489439997837,-2.4488384571932684,-3.3469771536767015,1.0827769476794593,3.4254291218948025,-0.7214489532298076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1500223,0.0,1.0,0.0,1.0,9.600419365836412,1.1315754128196585,0.5228470592310056,0.9685533661309811,-0.03354335849056557,-0.008423782040613717,-0.24639046238369558,1.2934242857084168,0.02487630795841811,0.10087002269747643,-0.32505351095012147,-0.6743446245621448,0.7154067303708567,-0.47503147913242133,0.27431036575195833,-1.1957570747611506,0.2866391310324077,0.8133716086625468,-1.1209254282517607,-0.2271551387533904,-1.032296653552268,1.1808342111923966,0.4741157425650884,-0.4503503171355457,1.1347714979618064,-0.010426888373736024,-6.746121028471027,4.657134682081552,-0.21489613176293157,2.5415537792453766,1.399706912144297,-1.2337965824194383,-1.279008303559304,-3.9512617128733605,1.1360053542834725,3.4156679417258666,-0.6031523225118551,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.166689,0.0,1.0,0.0,1.0,9.619234797538034,1.1214455376265862,0.5251424947296953,0.9698896917732297,-0.03680758632518619,-0.013162170637827774,-0.24038707254144168,1.2769104530294981,-0.027513072394208526,0.08983585936878798,-0.2115569789785018,-0.6550107539624421,0.6892500961901701,-0.4667046714850897,0.17534128308970431,-1.1082804597112585,0.28377968075634197,0.8542360980235375,-1.0969813337360868,-0.2497722610371786,-1.0457462491037104,1.1130772837442071,0.4910022017373399,-0.39383501479479266,1.1203156030686185,0.790505647270628,-5.048319185960514,5.101432092528777,-0.11838342014306809,2.322299677955944,1.5589318547517816,-1.40247663383338,-0.44281530265362434,-3.9371022683635557,1.061321229242504,3.5323628144822106,-0.9057368083244943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1833557,0.0,1.0,0.0,1.0,9.637597213771398,1.1111933870673802,0.5277320586504923,0.9710464198311238,-0.03973716058533165,-0.01774119397553765,-0.2348937177493148,1.2478821772306996,-0.07256851772084966,0.07125907745218024,-0.36205179317421926,-0.5734514492218292,0.5652566015684619,-0.4486812381896906,0.10603272299866215,-1.0257089982480518,0.28269300913541073,0.8907817527477234,-1.0689609291645776,-0.273904453379612,-1.0470571931617423,1.0495972064401269,0.5094931876279205,-0.33260465449528437,1.1045802106352027,0.5595183147196897,-3.9078267538931204,5.329939361037609,0.26386260898101976,2.074673210645783,1.6014224969517963,-1.2730706857925533,-0.02122167510698021,-3.258567854881366,1.125907347108927,3.609832890333474,-1.1202016823434473,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2000224,0.0,1.0,1.0,1.0,9.655070225998893,1.1005873509319017,0.5298850383168534,0.9716931243654282,-0.04508098639709322,-0.020669666726872878,-0.2309825569254478,1.2324079847073712,-0.11838262247314196,0.05061269139521167,-0.6620389813824422,-0.4770914662109811,0.4166969804111275,-0.4480540236932124,0.04508013077148338,-0.9306154590140475,0.2925751186465499,0.9233920100232776,-1.0436004770761937,-0.2922080354349761,-1.0464536396887214,1.0044581380103046,0.5285325217014606,-0.27350701112815085,1.0829754723103915,1.6297291829019442,-3.070032354276579,5.784043014505737,0.7188108978782118,1.7295649363508656,1.7482172186438107,-0.8618992264326619,0.1316321817106394,-2.0143762814929707,1.2268293218897022,3.4846711067823346,-1.3333149795978483,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2166891,0.0,1.0,1.0,0.0,9.672447601224606,1.0894843872632014,0.5322245847784999,0.9719791422253008,-0.05243950519736609,-0.022619104782794504,-0.22802416861475205,1.2473782036344958,-0.12642776441214865,0.04099792506679577,-0.7733808454935721,-0.4081194228123104,0.36843549013018617,-0.3943568234443469,0.0036981065206192288,-0.8329071788283263,0.3066534203187443,0.9484340325970814,-1.010686905328636,-0.3026344850539825,-1.0426694449959089,0.9824511960986091,0.5503875801461987,-0.2164487186244661,1.0601362890942758,3.046703906262172,-1.3428216029297755,4.894752554232176,0.7948032566384364,1.4382522727585936,1.994669650381831,-0.5325837958285581,0.41521334345048727,-0.7444737284806063,1.2145693126150687,3.381849906449519,-1.4245901259432812,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2333558,0.0,1.0,1.0,0.0,9.690377736104246,1.0786556897088762,0.5344514928611321,0.9722667886951962,-0.05930133005284473,-0.02401768554934014,-0.22495287203133768,1.2393258214241114,-0.08404013953744005,0.013463762397948255,-0.7337469905282036,-0.35092133814829374,0.3598465937081898,-0.3464970237042129,0.00031932115238400837,-0.7674567142228047,0.31906861352138155,0.9713338483320489,-0.977111355752156,-0.30996086413484775,-1.032613167226149,0.9796422974293691,0.5690182464265837,-0.16077845545650646,1.0354890398062737,2.0647546794314136,0.4267940647271332,3.3811556010637536,0.7913351165244084,1.4373043453639227,1.8235229081289652,-0.26691281155386665,0.7528790167482716,0.6561414919850744,1.0725124265425248,2.987014636067112,-1.1166511579598097,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2500225,0.0,1.0,1.0,0.0,9.708287549859618,1.0690899613363707,0.535993994982204,0.9724658170319751,-0.06578958261816832,-0.02519977058760948,-0.22214170496687977,1.2047905389988922,-0.011216492558531799,-0.080597409296685,-0.6997685145219557,-0.3175897292072816,0.40054789124719953,-0.32553152981298783,0.01792460379779465,-0.7202017667158278,0.33303131029189903,0.9963442732628351,-0.94990268682281,-0.31153159656663215,-1.017573427579032,1.0043226229075444,0.5861380658651113,-0.11688136495458663,1.0229145093855383,1.222074608112457,1.5402421893342886,2.8509180433018013,0.6615881109728566,1.6099489368746258,1.478186945450242,0.2338035530064523,0.9054467213493381,2.443411048987724,1.0890445183544553,2.0973576703883454,0.10828813293413114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2666892,0.0,1.0,1.0,0.0,9.726413344380113,1.0607302151208375,0.5349773728742385,0.9728478980550254,-0.071988748411948,-0.026128160537291396,-0.21840766144743579,1.206532470802426,0.03586958691630143,-0.190307452967686,-0.5025398836155289,-0.12025349586194473,0.5060730672549779,-0.30576112196215716,0.05166083014633958,-0.6724259227182084,0.34112159465968417,1.0249989202244656,-0.9278383590246849,-0.30216739678106247,-1.002431549484723,1.0610894952896965,0.6053198029747001,-0.09086639328638359,1.0390986514566203,0.7109656517097239,2.1946052058619556,1.884679162573493,0.46495649961353486,1.8278035983497356,0.8486418295607036,0.5008748805200268,0.8127119220628535,3.0191749486383,0.996850088885119,0.7492448160039562,1.7008746134528494,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2833559,0.0,1.0,1.0,0.0,9.74524914343943,1.0522587490834725,0.5328802379359869,0.9736619407861425,-0.07460628032599298,-0.024695473876588835,-0.21402444152594435,1.2391454172337275,0.03262198760108548,-0.22889243619354868,-0.257782510291826,0.24103992054420453,0.6671541751800987,-0.3018326273582869,0.09107825696687355,-0.6573790023181005,0.34852989127611683,1.0572711817280662,-0.9216145692613312,-0.2948357338243059,-0.9904829759961421,1.1049619891404843,0.6193664686179545,-0.09190648780480036,1.0796104432256075,-0.6699524709438954,3.3344774269434305,-2.1728711138567474,0.40443550623934615,1.938759255802497,0.10767961857531812,0.3714684060961625,0.8055563823018173,2.296893451182333,0.5143810950219218,-0.7936927350637372,2.46783822817888,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3000226,0.0,1.0,1.0,0.0,9.764464295043767,1.0434541119007712,0.5306008023957123,0.9749900343570181,-0.07559573466087426,-0.02045544222483032,-0.20799349193897873,1.2857709535512079,0.027062062938291165,-0.19882920648330976,0.16839831055023427,0.6413552066159736,0.802342807033656,-0.3280929156571184,0.16281030000961572,-0.744855104704841,0.3546028051633628,1.0896243580018325,-0.9242490312268664,-0.28978509181329665,-0.9755796163709035,1.1376527634553377,0.6224658737675038,-0.11732287070135716,1.1213600902517982,-1.359693002944229,3.7978076614271177,-4.661584481295477,-0.04808806920525852,1.827572569601344,-0.5248324301386068,0.05371652280065661,1.1435568123419486,1.4232690245019148,-0.5504933677941477,-2.1615240722799047,2.0501928765639854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3166893,1.0,0.0,1.0,0.0,9.784788710199807,1.0347886938678554,0.5292659183378202,0.9768375604824995,-0.06993148652118622,-0.013804397650559264,-0.2017607648405446,1.3472839677776882,-0.00035024207735673274,-0.14888177817037912,0.549730624134172,0.8897837802164903,0.8671628877618647,-0.3471558181026281,0.21767209886828823,-0.8127654624669152,0.34692695243007027,1.1181903892196157,-0.9391090185881135,-0.2930451794831825,-0.952364339347623,1.1524043848418164,0.6010166529919251,-0.16395743431573534,1.1479503424572655,-1.3646437932268913,3.658287348782126,-4.474126241585245,-0.5531521927495879,1.431025307903689,-1.2572979115447565,-0.10965173403173777,1.5605439902001683,0.6670079932122298,-1.3376141811650686,-3.5160236805282765,1.651884173167059,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.333356,1.0,0.0,1.0,0.0,9.805689605732718,1.0251223162273246,0.5281685037283231,0.978741812923551,-0.06385008117323683,-0.006808753451759857,-0.1947851935998344,1.408745063458535,-0.05531260429966328,-0.15135973806682912,0.7363726099625525,0.9703438405931968,0.8630863766725487,-0.37358113307426766,0.2847534555215098,-0.8939929443660986,0.3361643618615637,1.1373252970003094,-0.9661590454315524,-0.2934401569244702,-0.9235613793279652,1.1598864076962783,0.5778786452210561,-0.23452389445387842,1.176423006149645,-1.7099119246696357,3.9991645644977023,-4.757117294464814,-0.6310723107275269,0.4860199621533144,-2.5017069638352263,-0.08359323190841347,1.809867344018525,0.3263637808379741,-1.4888867145493776,-4.660636256044194,2.168879239703285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3500227,1.0,0.0,1.0,0.0,9.827416445668625,1.0145920710680496,0.5262816471423865,0.9805108329185862,-0.05487519396932526,0.0005779006954974827,-0.18864486647379383,1.4389913967777812,-0.12398087200421715,-0.1629745279664338,0.9104229639027697,0.9700041146287124,0.709092561907108,-0.4041529962524109,0.35097785096251594,-0.9713363560902286,0.3258911666676653,1.134391087026057,-1.0224994174964186,-0.2958316261196784,-0.8920353072225159,1.163283199294001,0.5513869965811649,-0.3193122868929589,1.220246461705991,-1.643644944439063,4.008021488356402,-4.455373158260745,-0.20763379795448897,-0.6420444935433604,-3.796034676074318,-0.09866156232330711,2.0333700791403384,0.14543980033490087,-1.5171608471516502,-5.188347766907941,2.6877248996215526,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3666894,1.0,0.0,1.0,0.0,9.848594887833888,1.0029776270866289,0.5241530884981879,0.9818091403913217,-0.04592198722428657,0.0068434173829350275,-0.18410635668533917,1.4165256115643357,-0.1797651252044456,-0.12813305697040647,0.9519504746614351,0.8343212024392459,0.5178547403029434,-0.4283694074652327,0.4183544390014891,-1.0425056799996673,0.3292432214208275,1.1159237710792311,-1.092693787703008,-0.2967288822460179,-0.8557822411319487,1.1647344107367616,0.5273065158386113,-0.40746916590732757,1.26601401531869,-1.2547662871302188,3.966805060073997,-3.8942862436407073,0.18297233797315265,-1.006079258829724,-4.573038453393887,-0.05506214585242939,2.2895184965332627,-0.13280705418809335,-1.737874515403391,-5.376454565229506,2.3089334530646592,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3833561,1.0,0.0,1.0,0.0,9.869136631117941,0.9915574606369948,0.5227482865456937,0.982741019425873,-0.03668198396267515,0.011719470501819193,-0.18093417256426408,1.39109161549682,-0.21563558359478996,-0.059773965264765805,0.9425400927000696,0.5898301766948255,0.31294183071063847,-0.44597862280783734,0.4832049507519865,-1.1011461571640018,0.3319902567982596,1.1008550446597822,-1.1749343374787784,-0.29766703465223576,-0.815717871370174,1.1588562886339275,0.49345773020941747,-0.4985277974975801,1.2972110640703765,-0.809390448806669,3.8086690721663086,-2.963401715874375,0.4479340783122568,-1.0660670371437004,-5.416086274774817,-0.019435218417967505,2.6513630740821306,-0.45465406129922403,-1.9710478694647358,-5.4258307316994,1.5491947781443247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4000228,1.0,0.0,1.0,0.0,9.889293596926155,0.9796144875653016,0.5222626545925761,0.9832341371879852,-0.028645400642595097,0.013866467053876765,-0.17954886126530345,1.3652716052331688,-0.2520699814631696,-0.0014749401182154176,1.0425510547353594,0.2758045812999567,0.07681296328277579,-0.45534914305148494,0.5453103286516375,-1.1412859347555941,0.3441743872268413,1.0803881321033053,-1.273230357934587,-0.2973767241556314,-0.7674032952383394,1.14957924504985,0.4616047887865955,-0.5883305520193564,1.317653944536486,-0.5150659290659348,3.6132390589830674,-2.0017848325446637,0.7767945996876736,-2.1898999287838836,-5.688074877134261,-0.1562135292995521,3.037855954167858,-0.657083787405035,-2.2062367239871796,-5.305407790815407,0.7627100149097159,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4166895,1.0,0.0,1.0,0.0,9.908732197045671,0.9676037301442545,0.5224415546532568,0.9833864101618081,-0.018754191489218232,0.013174095716002272,-0.18007190733905018,1.3155926175335442,-0.24727680442980698,0.017406632546797626,1.1301942346853635,-0.025969195005686563,-0.05086264067942243,-0.4631475214477638,0.6036464936006927,-1.167872451701146,0.3578834619074887,1.0278582343736575,-1.3645372125882456,-0.30287416270978945,-0.7144558037075152,1.1369534519148405,0.4199163589940632,-0.6753750775519464,1.322634782081368,-0.41930232864001504,3.472259341976448,-1.2746368059191497,1.0470381632497374,-3.9368689936472046,-5.098882909981322,-0.3752520383153241,3.1573200554727565,-0.6412474590265915,-2.423467635519679,-5.041397359271082,-0.1045981477124873,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4333562,1.0,0.0,1.0,0.0,9.92739142364339,0.956378170226376,0.5223453418612102,0.9834434856274963,-0.010212390691584,0.010034490145402164,-0.1806486276192675,1.242871336572254,-0.241148122341994,0.010217703131337387,1.0024735212145783,-0.24765110916300892,-0.13840778366570686,-0.469325915292974,0.6610525382014752,-1.1837739132620195,0.3790757291377101,0.9491589031904656,-1.4431934615261583,-0.3098851504496114,-0.6621590829012438,1.128204286999133,0.3808223727047638,-0.756377466754883,1.3141673326395267,-0.20225727917610808,3.2550278888207678,-0.7599783465423101,1.6745492371869173,-6.088772910733768,-3.459260868942291,-0.47669485048285065,3.052398154221007,-0.5146798611213651,-2.3121822744037566,-4.65861406895429,-0.8797385217316129,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4500229,1.0,0.0,1.0,0.0,9.944602490097196,0.9453684689503152,0.522307796907621,0.9831861874117261,-0.003088333226192036,0.006085037995900489,-0.18247836965861647,1.1607493736629897,-0.2302687028521082,0.04304666974125073,0.7713125226120909,-0.3926698740759954,-0.22801152989259507,-0.46988944423745266,0.7121476402299108,-1.1932051139177795,0.4137018814503351,0.8248987314310046,-1.4798461388370465,-0.3187640228388745,-0.6127089950736047,1.1197974222321376,0.34284346236845303,-0.8306625237580273,1.2933101060410794,0.12047025821290469,2.8008625444968698,-0.12831089906222629,2.158081788823538,-8.625604074899007,-0.18301470806612216,-0.4331535481543367,3.018562824252765,-0.6254151031589437,-1.9684575474672712,-4.203937676124417,-1.7780447455640098,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4666896,1.0,0.0,1.0,0.0,9.960768438914275,0.9353345426228407,0.5234244045298683,0.9828380588700478,0.001208223444341859,0.0012490357873882003,-0.1844622729510479,1.1099575923810172,-0.18992770437215029,0.09754325161175657,0.5746070497642594,-0.5475217672770796,-0.1794542309459441,-0.46531023198786,0.7544148097422072,-1.1880509517848203,0.4510119326372806,0.661638192320227,-1.4492939639960096,-0.32432363093165917,-0.5615401208552967,1.1073570751994948,0.3152069898920183,-0.8965090028882087,1.2548990559177433,0.2616151131737887,2.4045590693727865,0.6712969005706099,1.494434691232839,-9.330431643594876,2.192254394427729,-0.2954913590896548,3.025254133644029,-0.6479774958880595,-1.5790134522117794,-3.420919686626077,-2.690944918509425,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4833563,1.0,0.0,1.0,0.0,9.976794138668849,0.9260438212287857,0.5254397759580254,0.982631906483112,0.004630028555541998,-0.004649161242996677,-0.18544941223060268,1.0661957508611724,-0.1612858837015239,0.12128534800131893,0.49681716815128785,-0.6334823630906596,-0.13899517822225357,-0.4611689230239855,0.7922997695129417,-1.1708285058122991,0.4635164707870758,0.5138837212823991,-1.4067708462058293,-0.3286137545079536,-0.5118669889351948,1.0981981291707026,0.2902095753604969,-0.944693408040209,1.2036117626944374,0.38087353792220124,2.1415354588532747,1.0223590263635152,0.4165885813653498,-8.708607318885583,3.7690406972982204,-0.32759531682283327,2.9238674490742356,-0.48433838067239965,-1.4278015962010158,-2.404492283197409,-3.530173717483601,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.500023,1.0,0.0,1.0,0.0,9.991859243710723,0.917344235460876,0.5276724100568526,0.9823212598229144,0.007399302121373977,-0.010648627291035025,-0.18675331205859677,1.0307263397259574,-0.11533733369934374,0.14027667822985054,0.47725867390426174,-0.6794797767621483,-0.009845266315455202,-0.4526144219988841,0.8257994678063469,-1.1539722494154347,0.4648982464553644,0.37135070111688634,-1.3236590228166891,-0.3352434966654414,-0.4640776776283256,1.0912124302211894,0.26761350816521134,-0.9766589059609412,1.1372263633233755,0.23757800903409268,1.8047967777388438,1.478495881225468,-0.8064052617974464,-7.525387279290762,5.68817526787304,-0.3887850953735836,2.986081738530202,-0.6203314671684427,-1.3899807791840997,-1.265639803002182,-4.1551146870673685,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.5166897,1.0,0.0,1.0,0.0,10.007226660982962,0.9098071117948077,0.5306667554383843,0.9824177051757305,0.01031477824217124,-0.017264854611070246,-0.18560975917856506,1.0226473392161812,-0.06045098681532057,0.14949569153916525,0.543193900362002,-0.6706609053969925,0.19831942291387375,-0.45324964021764846,0.8524597824240217,-1.1215452112050581,0.4366362416334768,0.26303697694688843,-1.21716462473171,-0.3415732836060794,-0.41233073191207215,1.07752037224299,0.24387679005564164,-0.9868814858496019,1.065107662784546,-0.12402057889590017,1.455365997245904,1.9536311081339617,-2.3074972469842514,-5.5059791781651715,7.3097139782207385,-0.4146081913150475,3.1164042126922817,-0.9780215817280276,-1.4428513323373093,-0.37785878714874355,-3.9562209967471076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.533356399999999,1.0,0.0,1.0,1.0,10.022656207609968,0.9029555137114211,0.5336236640940943,0.9826484778869621,0.01415420882538555,-0.02334603968219733,-0.1834573239478906,1.0059644142381077,-0.04921233385228874,0.1392889877241282,0.6449474786468878,-0.5369711421699792,0.3029053583952425,-0.4567484495634527,0.8743117647389436,-1.0888510822355622,0.38798151772273953,0.1878176947794354,-1.080001402895066,-0.3490637973498224,-0.3601973294449687,1.0586116456288164,0.21951836756387888,-0.9892542240564851,1.0053520663504054,-0.30934078781937857,1.1959615730505526,2.030860620983445,-2.6559991557981903,-3.849355439474109,8.049328588060268,-0.3469248592383981,2.9519173312386586,-1.161711073666621,-1.2756419276314575,-0.034061116065593644,-2.827451770125606,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.550023099999999,1.0,0.0,1.0,1.0,10.037637657095544,0.8960762553532834,0.5366075018293075,0.9829852768520232,0.01910990964211214,-0.0281031340801565,-0.18051307625901888,1.0015486031411351,-0.05264766923234049,0.1111895416759788,0.7783733176561095,-0.4247838027734716,0.4504932361812582,-0.46356102043434694,0.8923252479231449,-1.0538497217815685,0.3481027593735934,0.13472487234072217,-0.9488531351744619,-0.35313746870901663,-0.31393329074296145,1.038796592340031,0.20135530742513122,-0.9880168586558628,0.9708590819502411,-0.5932251363149259,1.1320466092014947,2.1026143515581963,-1.240544784579746,-2.8585120116941476,5.510835786262658,-0.24226582520041282,2.719021753915044,-1.1418468673648678,-1.1016064193096,0.3193455428195135,-1.2107068495360134,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.566689799999999,1.0,0.0,1.0,1.0,10.052961540053031,0.8893309494808102,0.5388518819960129,0.9835444680917117,0.025408525735226322,-0.0327947538946861,-0.17583853452284384,1.0062602671524472,-0.054495180151517664,0.03872385892554875,0.9111036213701718,-0.36178033969878165,0.5875949733479171,-0.4765226603222926,0.9120467271821007,-1.0187637970093322,0.34662994220042903,0.09253377048882971,-0.8963065092972583,-0.35713934100755784,-0.26956308971301696,1.0205500072601963,0.18279808014646426,-0.9786093513394651,0.9649950906520817,-0.7463365594819177,1.2357471203795318,1.8225038933411308,-1.090361338575969,-1.7679774804661275,4.569868381370419,-0.2867226740025751,2.4384336749594406,-0.8064474409873746,-0.8593040300905401,0.6827035737682472,0.705116300404962,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.583356499999999,1.0,0.0,0.0,1.0,10.068313307713979,0.882667024183329,0.539646203304425,0.9841181092863005,0.032657861456129006,-0.036951673161584965,-0.17052737290660677,1.0012176180584804,-0.057125968900847035,-0.04892752711665161,0.8999366558834044,-0.2980174864242145,0.6792212589894411,-0.4884389555061815,0.933516900985604,-0.9930994705032713,0.3117573087303052,0.07579217179335256,-0.7965238844708892,-0.36269491029061407,-0.23265200568206842,1.0119149572106225,0.1727117824685112,-0.9652600273500163,0.9943630056381598,-0.7469612000289907,1.464305653511999,1.2535642125196498,-2.9388222751567805,0.4369653991386173,4.863189941013861,-0.26651653904146494,1.8311496428868965,0.061047212337968955,-0.2973249285568885,0.8400988649869722,2.257820461463565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.600023199999999,1.0,0.0,0.0,1.0,10.083805638962202,0.8763437021833199,0.5391380509960915,0.9848045102979077,0.03889748675868086,-0.04062227907827696,-0.16430731104623122,1.0377809117395274,-0.07510464885944879,-0.1452084778205146,0.6070752992771746,-0.13561005270001789,0.739072325765864,-0.501421416787339,0.9608570132528775,-0.9769782396877297,0.248669003773718,0.1070993129244769,-0.7341998537174669,-0.3660232434100426,-0.20852464620681088,1.0225849184079427,0.17288722937290607,-0.9506059998333084,1.0402559232222313,-0.6029555574959443,1.5995247718062984,0.4569558564908416,-2.4623152734361353,2.037355354840713,2.4856830320533945,-0.029462244088435008,1.0076553688355776,1.2461774735006936,0.22966831628631285,0.7166681111819968,2.60585513752382,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.616689899999999,0.0,0.0,0.0,1.0,10.100570981673634,0.8693082231370242,0.5369369064021239,0.9856788195345092,0.04173241345101066,-0.041341476268609526,-0.1580713532824415,1.0763347358977786,-0.09752605734735259,-0.23317354595226308,0.15048071948736647,0.16969231966724208,0.7057058905717527,-0.5085375142864168,0.9868345000141321,-0.9778675781565195,0.22967996879474914,0.14370415277839999,-0.7136676176902406,-0.3636769870577115,-0.19906342621052459,1.0534542894058105,0.1803674083226094,-0.9413710425327423,1.0812250172792963,-0.24342545651345293,1.456530581552742,-0.37813205538271777,-0.10696750657168426,2.982822771004425,-1.6748588786294054,0.35696002397192966,-0.07910753858100776,2.2386324568262825,0.5859163683849663,0.5994791508570827,2.3695966376551563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.633356599999999,0.0,0.0,0.0,1.0,10.11750215387243,0.8625005637260242,0.5335599441775883,0.9866816273013521,0.04131009314897439,-0.03874081991799647,-0.15248603681012973,1.08095833876851,-0.09020655214235468,-0.2314583308665415,-0.2531299793860967,0.501969481637346,0.6424285089895523,-0.5095356148994845,1.0094081297400077,-0.989582666742624,0.24510341309016143,0.2065269374794758,-0.7900285946623723,-0.3541245521469767,-0.21116156943334705,1.097206149544316,0.1924178140468295,-0.9306233215061289,1.1192426357838456,0.07850416040857786,1.17094444783505,-0.8785249129067872,0.2932375671132468,3.0615842381399987,-3.3579416902252737,0.9733327459205952,-1.4806830017198205,2.492734834416643,0.7334823522762528,0.8913576120082293,1.772417543351571,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.650023299999999,0.0,1.0,0.0,1.0,10.134611060910808,0.8560314844660063,0.5312911483023508,0.9877954521016183,0.03841065291769722,-0.03289943639276359,-0.14731732292854807,1.0882519357178182,-0.07782761502412722,-0.17688403146967419,-0.6200150015217243,0.7632862264699142,0.5698158686666749,-0.5059207037058535,1.025866059671597,-1.0071518004884066,0.23945457391436184,0.24575716482201582,-0.8255992312271957,-0.33123249730484194,-0.24841962498005205,1.1365456167353543,0.20481686896397464,-0.9116590627086272,1.1403057202188516,0.38849169177868537,0.8555468862850043,-1.4737414704706833,0.30223504204559815,2.811559806664868,-3.094709370333603,1.547289567282167,-2.980942331355404,2.152594681785699,0.9129020710331603,1.263301844471489,0.9276826673051098,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.66669,0.0,1.0,0.0,1.0,10.151825728849902,0.8497676793984034,0.5294191535772856,0.9888755557932886,0.03264823904272341,-0.02503395245371478,-0.14294239702225878,1.0972328897256602,-0.03900963234575605,-0.14953477815931782,-0.8892816574690521,0.8818905861251298,0.5971486850570026,-0.4965858659407489,1.0379264163193003,-1.0387074806744114,0.25517793464068417,0.3002457851389585,-0.8931857799874504,-0.3025481300849333,-0.3105265125413493,1.1689594491101514,0.22284794394140625,-0.888513175803623,1.1501654532061938,0.5354394888199888,0.5583669552394881,-2.2625768957899295,0.9155937172104043,3.1281060047505784,-3.9153376322045803,1.4715016488299837,-4.426916573933402,2.011306917141821,1.076533102638053,1.451040271183042,0.3700736213874796,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.6833567,0.0,1.0,0.0,1.0,10.169572931240172,0.8446736854988963,0.5276997156060028,0.9900516720639887,0.025612511815274075,-0.016569652372466773,-0.13735768089942532,1.1010093754088661,0.0038224519611292362,-0.12483532381198806,-0.9908570318149613,0.8669686324136056,0.6410782601442471,-0.4880726850492213,1.044478328737377,-1.0825711811865306,0.26997442552762313,0.35002757352076874,-0.9561107466565238,-0.28218234424373256,-0.3959838059056037,1.2035893147272094,0.2407013774874499,-0.8632909569331744,1.152641532270009,0.9057859939135345,-0.6890066275721368,-1.05094387746558,0.7116898773849527,3.013105882415861,-3.4738997556773756,0.9852743919024529,-5.5914759526074596,2.596698059056321,1.0484532647392528,1.6863432347467828,0.04047276997474124,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7000234,0.0,1.0,0.0,1.0,10.187321452494105,0.8400692047052474,0.5262186505483624,0.9910111296325878,0.018105686432210815,-0.008740235219078189,-0.13226009735168037,1.090391103519398,0.004423876096157742,-0.08365846940799564,-1.1440515331337315,0.7373435662312271,0.540421039896428,-0.4663929390912315,1.0149594827997872,-1.0737390133195226,0.27890097799950775,0.40068284875987936,-1.0089826701033466,-0.2697055846698921,-0.49690941705999475,1.2555162241918993,0.25779645599626566,-0.8323016222225146,1.1515145482368698,1.1310504083495165,-0.051652040730793485,-1.7922730545310726,0.7535107441727726,2.9677397923870377,-2.896582513986877,0.4994462858100161,-5.772033796565237,2.8129577390450766,1.1399489572442432,1.9371204453632336,-0.21108526963460253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7166901,0.0,1.0,0.0,1.0,10.2047424970834,0.8353700681757427,0.5253745485870178,0.9916926112382088,0.008259711046449961,-0.002053728835227411,-0.1283484483226945,1.0767662091487178,0.019797215950293878,-0.04271244090932723,-1.1903878799183716,0.4948852894999369,0.5207477654542875,-0.4503709293675435,1.042756590602881,-1.1423137358224367,0.29509150056743183,0.4489524311163228,-1.052663690228254,-0.265534101420313,-0.5883853172600314,1.2973547602258946,0.27869975205885517,-0.7987201462797036,1.145605342543171,0.9810750327834835,0.2574546853815817,-4.013331766579201,0.810324378667462,2.8774340362784008,-2.2774284023466933,0.17319218857548072,-5.363521867896881,2.242230909092743,1.207558071093544,2.079431241551101,-0.32309814022868416,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7333568,0.0,1.0,0.0,1.0,10.222207683139176,0.8315917403152312,0.524876365552387,0.992328973607843,-0.0005117597086764412,0.0019260698298077027,-0.12360920878080313,1.0725248914508945,0.04425333242238505,-0.027098448711553688,-0.9986992014028626,0.22313580684348303,0.5775983023804269,-0.4336903725934465,1.0235413228094856,-1.2075170064276137,0.3059118446433817,0.4965975084647618,-1.08489710201013,-0.26393250017123016,-0.6756938368913487,1.3302574039770514,0.2980484722032552,-0.7629871088753951,1.140744588689371,0.7176256177808272,-1.9654615913880633,-3.892683617135128,0.3753538240909744,2.78506130835953,-1.4727982195374667,-0.09303934488119717,-5.36431672951925,1.6187069769968028,1.0612820802222707,2.2000231890525948,-0.23471400029174727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7500235,0.0,1.0,0.0,1.0,10.239758947949374,0.8280290638582067,0.524336933761581,0.9928863153749126,-0.007768212354817492,0.0037071750140379553,-0.11875469031350064,1.055475860048237,0.06911723860421493,-0.0017481731188063124,-0.8742855128653042,-0.06085218654538224,0.651591216883542,-0.4264500275998081,0.9772410731925062,-1.2720701159058487,0.3076033197273859,0.5417879937323944,-1.1017570623993842,-0.26863541911897587,-0.7671962325317884,1.3513117673729198,0.3140758921517362,-0.7253858933097378,1.137781526885846,0.4064476513527849,-4.111551470269514,-2.8311749756777527,0.11714319810516478,2.7117860101026974,-0.8700469078761208,-0.4136945986125134,-5.203161375510827,0.7672807946615596,1.0129293430677264,2.3155149960304398,-0.16236727461962921,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7666902,0.0,1.0,0.0,1.0,10.256939616550747,0.8255307642127765,0.5245864453901387,0.9935063466185854,-0.015044038568516816,0.002742131391980813,-0.11274438721093631,1.0361218330233757,0.0959609623271924,0.03229230617543457,-0.8047606704586058,-0.3522057793562774,0.8112800369941013,-0.4201420904518436,0.8864893330304038,-1.3018896943618705,0.3098166257231004,0.586990556253919,-1.1138987236091278,-0.2777223477046205,-0.8491328962858012,1.355833481617823,0.33181285116746895,-0.6858031213067141,1.135332335377565,0.4061115877466097,-5.983858584614946,-1.2439675805607133,-0.03299366852004959,2.7750096106380058,-0.3982670996326203,-0.6350601268198667,-4.395095028160513,-0.28139733778144804,1.079381498319358,2.58391926414025,-0.14976997046630772,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7833569,0.0,1.0,0.0,1.0,10.27414370112927,0.8234364245300202,0.525244224528933,0.9942163215436461,-0.02170657191275157,-0.00039412934947512755,-0.10517877815450039,1.0177620004508463,0.10516662104864634,0.045604132903373965,-0.700814244415732,-0.5003177648040774,0.9585993165011693,-0.41291294760081526,0.7777787214481023,-1.3135357848557112,0.3065035285771397,0.6342884990876353,-1.1150326589382782,-0.2898041323503132,-0.913699693143474,1.3419318373537157,0.3500553473878147,-0.6392550789104452,1.1327891845523044,-0.0350664026306495,-7.014235109893367,-0.5066156266898292,-0.36508211919019834,2.639719986419209,0.16348982976546794,-0.8402811572062256,-3.419252046356403,-1.357722049166086,1.1059621691165193,2.69261447180582,-0.20627982761867844,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8000236,0.0,1.0,0.0,1.0,10.29085343385932,0.8219265762179263,0.5261356324946149,0.994926743123492,-0.027539421264785785,-0.003960359355798456,-0.09667818599795122,0.9983052215886488,0.10716009284657704,0.05082480953524117,-0.4570863306061528,-0.5878753313018564,1.0318196875943026,-0.4213109728772921,0.6526810284182842,-1.3187769156925733,0.29764719741128587,0.6749813984492251,-1.1084490517176235,-0.3057317756302385,-0.9631081924478178,1.3105759894641502,0.36867833053549753,-0.5960491260722219,1.1284563273716206,-0.4153701682908206,-7.352010816404762,0.17360009811866375,-0.6030998024804687,2.367749767521205,0.4942900973908711,-1.1808983253364755,-2.5268052852908047,-2.3186921919177745,1.011622055398485,2.5978875246117417,-0.07465199795028125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8166903,0.0,1.0,0.0,1.0,10.30748112442498,0.8206359798547791,0.5271821933392246,0.9956366737730004,-0.030290914309905766,-0.008903740309547473,-0.08781114825012934,0.9842094262489269,0.10831344755801318,0.058388967396133494,-0.2959464928378418,-0.686863544042697,1.0955524073340377,-0.4267586475685205,0.5327112041005558,-1.3077491033450825,0.28640016162113724,0.7132136491883266,-1.0985562894059093,-0.3291674885880841,-0.9979267044401865,1.2646419430436437,0.38377615000923454,-0.5526586548975522,1.1303007796438285,-0.17354647938551354,-6.9613596571627125,1.2010501812630154,-0.6792530829898001,2.19964380161237,0.8516408574115384,-1.378156661104824,-1.5881717414302008,-3.201378086972442,0.8731256539736938,2.6408837219366705,-0.03117151508854222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.833357,0.0,1.0,0.0,1.0,10.323758445323534,0.8198763541495366,0.5286221144812676,0.9962673276449561,-0.03361663935022993,-0.014374743856284735,-0.07819654829364722,0.9739232769986027,0.08845325790557781,0.05808426977762752,-0.36596581250092386,-0.7264365136216967,1.0923445158805805,-0.42709586709324115,0.42063524242221667,-1.2787418295804607,0.27500538269475366,0.7483030051458909,-1.0800609663611818,-0.35167042287751005,-1.0160473563736072,1.203863173139863,0.39778257720966426,-0.5080194926154181,1.1274172747905682,0.292505700823925,-6.174232748643305,1.9347227306063448,-0.5397528573450012,2.0719645502741195,1.178622568469303,-1.2599684164559724,-0.7052067442593055,-3.847493379677724,1.0642141659952224,2.722446103485882,-0.11157260674890637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8500237,0.0,1.0,0.0,1.0,10.339951833772002,0.8186489002718714,0.5300228200149302,0.9966857181114562,-0.037571322126875015,-0.019885444297224428,-0.06935808656091541,0.9595600074206956,0.038977358842511856,0.05731832909308849,-0.4773571890645302,-0.6825979426874801,1.007392947787709,-0.4170084380406763,0.3269030341969291,-1.243258216676689,0.2684083637261134,0.782279272328434,-1.0592687918820947,-0.3711665198011776,-1.0214336429292796,1.1363919072214943,0.4192500264900197,-0.4619102699516159,1.1265816853140245,1.0355851503098787,-5.087278293938567,2.56402597035825,-0.23215473820264845,1.851207832112389,1.3169589152030972,-0.9709240324205252,-0.08645685717145313,-4.108549326704913,1.4208219972367233,2.709626794703155,-0.09957900034088416,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8666904,0.0,1.0,0.0,1.0,10.355526605919243,0.8169334041218955,0.5318666742335402,0.9969106118757092,-0.04267286777744539,-0.02454390197233472,-0.06120339174604952,0.9277787652447196,0.00035010902618400064,0.05560368146105924,-0.6395284842705113,-0.5874700711433865,0.9138606965796341,-0.39257629304390185,0.25105896013904483,-1.193274126300121,0.2672668759443495,0.810010056296826,-1.0361622480571508,-0.3840346220197964,-1.0189292573764461,1.0669112550130775,0.44514340517235484,-0.41769841881686,1.1240979681406054,1.302587033524245,-4.184288083152634,3.055512036979919,0.08278060568718386,1.5822744868307697,1.3490146191452141,-0.6148833523120439,0.21956073501105539,-3.8659639149264797,1.6258396397956982,2.520354104713097,-0.21485330811754927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8833571,0.0,1.0,0.0,1.0,10.370529334635592,0.815114626878953,0.5335412795802148,0.9969245747684699,-0.04917243283776021,-0.028360496253611932,-0.05402912477331634,0.8929756867673158,-0.013292569450436179,0.02560530261924842,-0.8125975054944024,-0.5414955338597454,0.8387998117169299,-0.3735887834173992,0.18742648580596913,-1.1414076117432226,0.27116772276772655,0.8350218607077587,-1.0143015479762796,-0.3916626725371359,-1.0141149371248621,1.007526185659684,0.4734447895391856,-0.37789829843757233,1.119419894053219,1.1039241531994743,-3.4536998999061783,3.5271735164368905,0.2522150474621726,1.2932469657320331,1.4552559245361354,-0.35867118556395733,0.179882712323069,-2.731377389600595,1.768595322049362,2.3511556393743245,-0.2829063738582916,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9000238,0.0,1.0,1.0,1.0,10.384978161292839,0.8134578027715483,0.5345980896650835,0.9967361453131418,-0.05705685505193732,-0.03213393738939067,-0.047212095756663214,0.8549215988162091,-0.019166176952055858,-0.021234797997520885,-1.0227658825804684,-0.516065631259932,0.800057041976242,-0.3557787476756425,0.13593539989551223,-1.0757014406073235,0.2756740610074251,0.8531183747043581,-0.987653620222218,-0.395990352116674,-1.0129331549734963,0.975865159934565,0.504096700480355,-0.3393264074273399,1.1146677368182374,2.2530278056520547,-2.627205953154813,4.209693783868071,0.7385549140107737,1.3179606819543894,1.313039439402205,-0.02841083981304278,0.09020250989635994,-1.3036032732806644,1.9500065001010798,2.3060052818354797,-0.2810447865327133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9166905,0.0,1.0,1.0,1.0,10.39881994304979,0.8118225362331727,0.5348892736488251,0.9962901014661265,-0.06699818523922779,-0.03538473673619563,-0.04080682910219381,0.8144989824046446,-0.030210379722276998,-0.039406625909416786,-1.1693156773402351,-0.4617836812623429,0.7370731948852959,-0.298487706360477,0.0998527788870785,-1.0010842049680346,0.29578626913841327,0.8789539713036172,-0.9705334791269101,-0.39260970242495996,-1.0111081807814828,0.9640726563101103,0.538445136209655,-0.30103130197603756,1.1100517157658094,3.42127632363499,-1.624177851800928,4.527767491742962,1.125608799397013,1.3998066732847272,1.1626187807590715,0.3527232972087147,0.27590995149852093,-0.14452811112835254,1.9574907020895909,2.239781095290971,-0.35494705298553897,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9333572,0.0,1.0,1.0,1.0,10.41196854985216,0.8102051678683698,0.5354938621368752,0.9956617701464587,-0.07722195000777853,-0.038192848300576676,-0.03515275585932919,0.7895830287125212,-0.008184748534498264,-0.0557909660767586,-1.0670358358266703,-0.4064100124708568,0.8161372496649809,-0.2417359754693879,0.08179602989029118,-0.9247755556980587,0.3131944293612455,0.8997786904676273,-0.9488995833556636,-0.384232885361497,-1.0037361381962155,0.9710475465950792,0.5693465210493882,-0.26466688826556783,1.1028361447222492,2.7247711663458856,-0.7396065799374866,4.175476680078045,0.816486465507206,1.3428827729572597,1.0543825613991296,0.3751322378076743,0.6134024577186026,1.2279362147706356,1.8030134830471676,2.038456308086884,-0.21577259361968873,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9500239,0.0,1.0,1.0,0.0,10.425108233626853,0.809575543530781,0.5352429995625467,0.9951426151522372,-0.08547181096870067,-0.040421011531168755,-0.027420555510314436,0.8106275620129116,0.009305889379620486,-0.12875886988200702,-0.7201278691413135,-0.2076529195240769,0.8956790497755246,-0.20766181916420307,0.07519917691539028,-0.8619013706003211,0.3230025390877512,0.9237168199277107,-0.9353873234547684,-0.38010526948922163,-0.9906613912973655,1.0050039453315458,0.5985457058454594,-0.2330826224760542,1.1028592815936469,1.6917253675832324,0.018091713983934506,3.212097621961489,0.541798881484892,1.6093151356896505,0.376399693392318,0.28267714162690266,0.5908334246678021,2.115439717580086,1.4250231876257229,1.7306283656449744,0.1605467376232671,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9666906,0.0,1.0,1.0,0.0,10.439204832794468,0.8084827756685183,0.533527021321174,0.994936954820367,-0.08988525214604767,-0.04001011573965125,-0.020500927245276614,0.8406134329639471,0.007396561389147023,-0.17948073812533433,-0.40015801239035576,0.03622404076409029,0.9985193301218749,-0.185345017101589,0.08239908822920326,-0.8177054208261676,0.33125442819733397,0.9534226356116247,-0.9363529018159401,-0.3748102951287908,-0.9840416513183938,1.0415623448770632,0.6168473889717915,-0.20697916070217764,1.1081877133461406,0.9505722210817757,0.7183028317560759,2.7718030996876943,0.48341001461803407,1.6471999069169976,-0.008050326498528807,0.30550799484139,0.3789011311204869,1.9798437050737017,1.0662602952954798,1.2169936461114335,0.4469670675676945,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9833573,0.0,1.0,1.0,0.0,10.453481568795034,0.8077964877238378,0.5316665527784422,0.9948930421572686,-0.09276831502655304,-0.03816596815893014,-0.01119076711763687,0.8654950203173662,0.01897344242527648,-0.1725984998650703,-0.11784795911287449,0.3321700490070952,1.1543406808129573,-0.1759760150899958,0.09914265252744826,-0.7695077491571913,0.33911623846901995,0.9786235933049378,-0.9356556682080744,-0.36992164929397564,-0.9780313283332739,1.0709988674902495,0.6340877867726618,-0.19251608647276336,1.1177582136437079,0.33779673160235274,1.176826050190716,2.2259312017537534,0.07273312093001413,1.3239037865180094,0.008774868936041638,0.2918868624231136,0.4785188968608253,1.5720108059788696,0.6972581178803329,0.2823356284950637,0.9345785886115973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.000024,0.0,1.0,1.0,0.0,10.46840698389504,0.80759915504335,0.5300241323675935,0.9951705724840012,-0.09254498567284485,-0.03266642888988175,-0.0019651239809874463,0.9339699798301663,0.025894319026315425,-0.1425170311392304,0.11475401690494727,0.6642258019541749,1.2053106287683535,-0.17408510352839512,0.12162670169063047,-0.743507565705629,0.3336788704105425,0.9975528500891441,-0.9360604055997475,-0.3650807135888962,-0.9680909895217732,1.0939628098770793,0.6400893727183438,-0.1975679542633003,1.1393403952717664,-1.2137060535325963,2.518385715272982,-1.96854036980132,-0.2225775493558981,1.0862742949964976,-0.15193527412501398,0.3052864979010725,0.7260078178728677,1.0730207122510627,0.023674202186287623,-0.7562097234169608,1.3029404811882193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0166907,1.0,1.0,1.0,0.0,10.48486301753849,0.8078356605850172,0.5288840793583476,0.9954520602041894,-0.09151193381936551,-0.02528605078184773,0.007834375516452944,1.0148521682784086,0.04022434062748903,-0.11054602060292511,0.2617785279793344,0.871611388964846,1.2252394529528003,-0.21643296445481924,0.18308901092892868,-0.8351258927199267,0.33169697198532005,1.014832808889774,-0.9407201874745932,-0.35974541234484003,-0.9538310193369904,1.106766296099999,0.6348769284238182,-0.21772312766731028,1.1611896498793473,-2.055282071521046,3.006700801332984,-4.537548926825394,-0.20949498687650622,1.3911314696102826,-0.6170191750674039,0.22820353584099498,0.9784521796738425,0.5300610388175212,-0.7530220641164255,-1.6459199356302847,0.9750530967414792,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0333574,1.0,1.0,1.0,0.0,10.502364125645894,0.80893165031946,0.5278153616754538,0.9957644301261973,-0.08885055543496845,-0.016286402345895814,0.01713276372844868,1.064404584018453,0.05216413141973086,-0.07965913323935542,0.5567929015174771,0.9488262922666281,1.1925704653235207,-0.24259464293123476,0.22185026218178336,-0.8947594991030706,0.3266956902149932,1.0439239918182515,-0.9566277525699393,-0.357473913847294,-0.9354758516358331,1.1116315465083992,0.6149885870463253,-0.2524320618456388,1.1718422301666889,-1.8608893951098282,2.5088452637378498,-3.673341618614816,-0.5580179648493689,1.553225030244637,-1.1162850197947587,-0.06751637734736278,1.2383938265273684,0.13148609660441815,-1.3276822801053647,-2.6251590869859167,0.6643429268046808,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0500241,1.0,0.0,1.0,0.0,10.520343502291393,0.810390905712473,0.5270062282435658,0.9961838693078139,-0.08286337604792512,-0.007583445439320215,0.026341047741528182,1.088527504358899,0.019071521583213992,-0.05334713265139124,0.7354571246544924,0.8827212997581487,1.1086919851502424,-0.2784627350177732,0.2667173536432079,-0.9575708582298618,0.3130963359558101,1.0666070801129306,-0.9779297625534198,-0.3619959627575106,-0.9125511425598231,1.1111491747525528,0.590620763908154,-0.30522860557744663,1.1833344583956984,-2.074484793067134,2.7840629832929187,-3.6715330074689936,-0.7878305681299378,1.2097230693416532,-1.5976272712049309,-0.23542295253045187,1.4712696961095995,-0.08532521237184526,-1.644574059706324,-3.7272049224291894,1.2019720129049574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0666908,1.0,0.0,1.0,0.0,10.538595989229151,0.8112147304555942,0.5263463614886821,0.9964238247560527,-0.07717090069914839,0.00022687882774269973,0.03441165601651427,1.1100869732839271,-0.028545166609183867,-0.03512253078015971,0.691766897619998,0.7364073319141556,0.9405777362926901,-0.31174427433245877,0.31465254722907954,-1.0171441774542376,0.3004346187552907,1.0842481747778445,-1.0098821014519217,-0.36532136129317255,-0.8864334303475334,1.1087873670743236,0.5601693420845105,-0.37667247440693996,1.211908044061655,-1.6647883949646551,2.9864151861326196,-3.364628131965049,-0.6929466661958882,0.5930125730314559,-2.2928151109381605,-0.15002316558933354,1.664779967592998,-0.12046598810144399,-1.5527499132534948,-4.410773183491062,1.9769212983916817,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0833575,1.0,0.0,1.0,0.0,10.557329810303608,0.8118091806943563,0.5257824778777982,0.9965566698504591,-0.07179327306964177,0.006258127780461246,0.04100445774783802,1.1149260265191867,-0.05755002338385049,-0.011390914319764762,0.6942317206313005,0.5265052567663031,0.7697240498184044,-0.333955792502488,0.366264725608641,-1.0697253536039055,0.2899980675528361,1.0863742054148173,-1.0543570857723659,-0.3669967449453661,-0.8570583659880586,1.1071336337847721,0.53886232994971,-0.4522546724120276,1.2492319668035077,-1.1959763355563267,3.0619287010333176,-2.7984695414234033,-0.10822803580510167,-0.9187384535112822,-2.6350108751687373,-0.10679378565182884,1.881500230867041,-0.1161961965791491,-1.3738641848921769,-4.541066883215904,2.189427426270942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1000242,1.0,0.0,1.0,0.0,10.57578838236569,0.8122720041216006,0.5255617544408064,0.9966880470569033,-0.06591501860411164,0.010376430449520392,0.046480930148202815,1.0935460659696352,-0.08135254936501057,0.020461694509720726,0.660489645203023,0.3086294412341297,0.6425691759121256,-0.35161023191609203,0.4167170413921035,-1.1104266820663204,0.29682701034658493,1.0536234984115715,-1.0977159729582713,-0.3688811612678192,-0.82371663055195,1.1049141527752722,0.5143737776638256,-0.528041673251929,1.2848891042325148,-0.8955730111713892,2.9296415593816554,-2.0284710787261355,0.48431567163070866,-1.7277441050511777,-2.6642493106965013,-0.026343480078992648,2.043111574059072,-0.1702421581315328,-1.4251839068144299,-4.630745122952843,1.8716795408009779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1166909,1.0,0.0,1.0,0.0,10.593880956472221,0.8125505042087475,0.5258348233063068,0.9967465967256033,-0.06094330248845271,0.0126019342019355,0.051218424927936705,1.0694654636012726,-0.10546809113960698,0.036205970225751685,0.6381356142703808,0.06511614618807769,0.5206081625506846,-0.3638082859130684,0.46391963956413346,-1.1373411914595153,0.30614195556157114,1.0287826200635044,-1.1431655737455366,-0.3678748627042312,-0.788954510645318,1.1014588838309105,0.49135610471030183,-0.6066131518934639,1.311621409608843,-0.6640462599280261,2.8460795242267656,-1.4347255338652911,0.7632032322565864,-1.401169970242719,-3.215289386244963,-0.04975135784343259,2.151592416393996,-0.13877567155718187,-1.3780775350789611,-4.852165322783661,1.3468528402928228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1333576,1.0,0.0,1.0,0.0,10.611626083056375,0.8125342596496493,0.5260637297066909,0.9968822065088134,-0.055252020404842485,0.012540316180546983,0.05491649167048298,1.0423802193589269,-0.12413410810493422,0.043017793224171055,0.7088496334110901,-0.16153908711845333,0.411218277575064,-0.3737451515167769,0.511586548604964,-1.1582509621768657,0.3222671689686866,1.006917739325483,-1.2048925001857291,-0.3705395431793575,-0.7519967398993224,1.100288287804988,0.4684377679560246,-0.6897808408224059,1.3297842886991316,-0.5452261617004722,2.7833561372336884,-0.9738908941059209,1.200605768124245,-1.8026574035468874,-3.9005554337923196,-0.21365551698298382,2.3153476413737772,-0.08977077302194661,-1.44276631786589,-4.655450891621473,0.5543317634622354,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1500243,1.0,0.0,1.0,0.0,10.62889246428797,0.8123790671748472,0.5266300738883368,0.9970543389041117,-0.04892641483073706,0.010951055319474616,0.058042446465369,1.0055448596911456,-0.12241444341313762,0.033249385254349964,0.7369775831456956,-0.3109114926035803,0.36842213421103576,-0.38198252765149493,0.5566983630289989,-1.1698042861891056,0.34616222787276385,0.9686939197681146,-1.2731843482423095,-0.3749967275140318,-0.7117761015763493,1.0984665187454608,0.443263797930351,-0.7617951586442391,1.330099172013035,-0.47088913129213483,2.6495300366510253,-0.5800770675919484,1.9255496246251889,-3.096083972337133,-3.9438396916216467,-0.27699737505353594,2.2427991242652143,0.007952090871804046,-1.3346936388610537,-4.312505248827828,-0.20374167994046172,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.166691,1.0,0.0,1.0,0.0,10.645405000492106,0.812453921447673,0.5266370685201441,0.9971822728229811,-0.042634181897105404,0.008387071825524346,0.061151437658911546,0.9739411651280769,-0.12164881028744165,0.009337385904787002,0.6505019178448814,-0.4197773872177935,0.30950096621908924,-0.38944148728579014,0.5999043931286673,-1.1775869031017352,0.3864522848261679,0.9037147338419803,-1.3363540861624301,-0.37977280748096703,-0.6772366195705403,1.1005533580308542,0.42394789101441355,-0.8335313032836834,1.3229928857850042,-0.35451322788115647,2.574518956143512,-0.3234539279159513,2.4361576949832675,-4.988527422340163,-2.9554753149014514,-0.3214095158487026,2.255149826993743,0.10543509096343878,-1.0156180789375704,-4.122401295355535,-0.6583699023954273,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1833577,1.0,0.0,1.0,0.0,10.66161088354585,0.8123320806708899,0.5265684574808096,0.9972672980366802,-0.03763930921041161,0.004858940041850999,0.06338461461941583,0.9512849595798198,-0.10134551955076895,0.02723347439710891,0.5455316818048876,-0.4971354663408563,0.1928537023828374,-0.39379965888174867,0.642515833201713,-1.1805861053498992,0.4273676467827191,0.802409339788281,-1.3717003891040456,-0.38571039946962293,-0.6366042903332361,1.1019810288065814,0.40940979425789337,-0.8992088099828432,1.3081534647085273,-0.2641226571847697,2.3704201371551408,-0.05635617329246621,2.4159739036355856,-6.956658076291087,-0.8017071761474149,-0.39358391351954014,2.4480622023751186,-0.06041268514606232,-0.6323427704903753,-3.6968557714936714,-1.2668000531841794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2000244,1.0,0.0,1.0,0.0,10.677291054159134,0.8131783695527376,0.5273351575367673,0.9973630478329171,-0.03302150890319347,0.0008255874076446741,0.06462081067754366,0.9496119194636047,-0.05909716901020315,0.03772780231816454,0.49449436726571094,-0.5618413569597853,0.17137048105531802,-0.39824559346679295,0.6789185557285145,-1.1794654459685623,0.4669849093456143,0.671825667521739,-1.3630777121478224,-0.3928922975038793,-0.5956343829538895,1.0985395978318064,0.40286975650854967,-0.9567600754571906,1.2807661328921947,-0.18133511847870898,2.3071465747324753,0.3224103640905549,2.0929071895241007,-7.949753709465829,1.0180253843701996,-0.4214448810863111,2.502462746003645,-0.17662175082157452,-0.17780592879794901,-3.1508261775917106,-2.025539439832,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2166911,1.0,0.0,1.0,0.0,10.693251005701319,0.814544363862194,0.5277656358857884,0.9973607800308798,-0.028813912668158425,-0.003857100140833746,0.06653086254852354,0.9545414779746692,-0.04241105126753797,0.0294160880008729,0.4901216579619478,-0.6124489087733705,0.17484068234890265,-0.39984417492004687,0.7194208728359005,-1.169839071719523,0.49713135929400176,0.5374170194891728,-1.33776614175668,-0.3997585902688254,-0.5531886986355982,1.0960936253377456,0.4034829181108998,-1.0042365592909788,1.2406353483448314,-0.15387551122983123,2.2803940760855808,0.6251467592912142,1.3027170746131072,-7.897648481429768,2.3222172788495623,-0.4658766441140091,2.6361824147195576,-0.25851564570412017,0.13512890965020802,-2.508279794810036,-2.417170196455278,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2333578,1.0,0.0,1.0,0.0,10.709002539512673,0.81606505302238,0.5285188296154829,0.9973635013476863,-0.024203404144211283,-0.008724228443239397,0.06785373420369752,0.9612923216294791,-0.03191072124543966,0.03812553736010794,0.5741025090343006,-0.6611231305355559,0.08133089745546179,-0.4033747874328214,0.7549318436243055,-1.1586271789824045,0.5104088986805229,0.40857019163084796,-1.2856703147050184,-0.4084215500327892,-0.5077614600510766,1.0899223924072927,0.4073740625054839,-1.0403695691695114,1.2001936318656723,-0.2522677999659551,2.0868465904693014,0.8312111493190056,0.27025186479332713,-6.743691431465424,3.6777728960133387,-0.6619137572674364,2.786206949792022,-0.4392028594856171,0.19490266834853295,-1.6761873558071967,-2.8548599461751056,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2500245,1.0,0.0,1.0,0.0,10.725111438971217,0.8179021241996501,0.5295398017960837,0.9973966962048337,-0.018529488653955963,-0.01415882970685865,0.06823500561469766,0.9737781719225734,0.018376784104252974,0.02888164491160098,0.5999126476777957,-0.6498593232232804,0.14013256397458598,-0.40825311840343204,0.7889825649746499,-1.142131977994813,0.5061397728039037,0.3126268555275632,-1.215173466704709,-0.42182242630532374,-0.4603149478954008,1.0814535007413677,0.4099796867160288,-1.0601095828970424,1.145473159814998,-0.40193936067245034,1.9197696826764599,1.081604863963407,-0.5709361825646507,-4.832832256754169,4.839091961301612,-0.7816425368516016,2.7668736068984052,-0.4020319257085233,0.216016030096513,-0.9329754632755455,-3.133510494509113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2666912,1.0,0.0,1.0,0.0,10.741033917354107,0.8211404393363113,0.5302913795664703,0.9972406340350994,-0.013535788936863278,-0.018812638543442624,0.07052648352330777,0.9803439182573667,0.06243835530625197,0.008742692994899909,0.6166832412656692,-0.5407175357396247,0.2289634871562319,-0.41677279291786046,0.818924294364833,-1.1225736114099667,0.49137765453262233,0.24747546088355854,-1.1243669267221672,-0.43447635337067836,-0.4155321553628893,1.0765213014148802,0.414574611243103,-1.0714688134770605,1.0957430731480022,-0.5657313809564423,1.8539247846927278,1.0651691877247562,-0.32882454066004874,-3.482759816931769,4.245737427292897,-0.7351988880641877,2.6613385787378028,-0.3876693621753935,0.21273655737026753,-0.4127006635705978,-2.746560100578086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2833579,1.0,0.0,1.0,0.0,10.757138230499914,0.8245823140979823,0.5309329436204785,0.9970975506299715,-0.007716505733108236,-0.0223652064365288,0.07236523756634716,0.9854339130497218,0.08142454911308888,-0.004456222312140323,0.7958911352363662,-0.44946278786525495,0.2076687985831876,-0.4271108688174055,0.8507801813927265,-1.1066262673927085,0.495178932860266,0.19653462944584976,-1.0736486027457839,-0.44632910492072253,-0.3716034845149021,1.0685311628242304,0.4170709194774749,-1.0738662991961065,1.0539209733583885,-0.7340293368458777,1.8083369076530649,1.0577094917334304,1.0350847515961379,-2.8863488592595883,1.8954030007171696,-0.7856064650817154,2.658775164131712,-0.5809394277320455,-0.07442367057500784,0.2676247118836016,-2.3164459738506227,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3000246,1.0,0.0,1.0,0.0,10.773120935005212,0.8285756677513569,0.5315208022103909,0.9969120075567555,0.0001535707135449533,-0.025292038485992176,0.07434203652321222,0.9871856020354106,0.09797255496790733,-0.005694552853243502,0.8678186786835256,-0.38224789563645944,0.2365299270217919,-0.44124048641467883,0.8792023118423957,-1.0873165578382196,0.525880548591477,0.15126363981831498,-1.0611867003380615,-0.4606632879138332,-0.3269061393068213,1.0571566150945169,0.41209381726235805,-1.0625479719059596,1.0185280529232499,-0.8430734382317618,1.645986686162078,1.2093058841484732,0.2209795370550507,-1.9146006456790479,1.9942128863850908,-0.820671234430491,2.689118052860798,-0.7777569134260485,-0.34343607240141677,1.1659129785025255,-1.976883955843203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3166913,1.0,0.0,1.0,1.0,10.789164130755546,0.8326900178746725,0.5323922303762756,0.996648644813952,0.007074101180880774,-0.027646452786723695,0.07666230841363413,0.9899638472013238,0.08524242644543453,-0.02196046559777903,0.800103666289179,-0.263729312393044,0.27931232544433415,-0.4552133729633601,0.9056465139972415,-1.0663159906340338,0.5025449321607368,0.1327144802831718,-1.007174706918755,-0.47368486744648786,-0.281966036811672,1.0426058805262346,0.4056230275016895,-1.0350024555184905,0.9880247097046847,-0.8314167798734529,1.535273978049698,1.202460828470369,-1.9839334129026014,-0.40686107683050965,2.6299966025269734,-0.7527679244381962,2.4965377553788715,-0.7936973820431308,-0.1633778806966068,1.1047620045562137,-0.4352036870472863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.333358,1.0,0.0,1.0,1.0,10.805285711018469,0.8364265035105316,0.5326722789928567,0.9963422665025461,0.0136482594454746,-0.028686718717679145,0.07932770741608003,0.9952532290253935,0.06534290999706599,-0.051636809178121336,0.6616338651512167,-0.13290494567379574,0.32660923007713033,-0.4689544345049126,0.9303782134623175,-1.0472344500584854,0.45974930256582947,0.13770157679989287,-0.9735199715873889,-0.4857556022463014,-0.2436880476916752,1.0306999827799204,0.4066478770139458,-1.0257224981032855,1.0040212343414279,-0.7585208305892793,1.4860335040691297,1.1548910565758033,-1.8380106806144765,0.5575767195352355,1.7898568669811203,-0.6250918018061676,2.146009990033217,-0.6252138445385736,-0.19056183124732964,0.646200542708076,1.4301180193704182,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3500247,1.0,0.0,0.0,1.0,10.821615823527168,0.8401127313427396,0.5326920462886299,0.9960135341726533,0.018078474528818833,-0.02906153300534265,0.08237497073135304,1.0145661197163691,0.0850039698069055,-0.10473553648610517,0.5630915124490736,-0.1099411380978619,0.3439467643895515,-0.4804974512177248,0.9551810632017794,-1.02781954508877,0.4412777869395422,0.1513004081061276,-0.9475126920289266,-0.49452130251281357,-0.21043222740989875,1.0217653773606925,0.39927095375598975,-1.013462394348185,1.0356954056915666,-0.7841598517407784,1.5925825040622068,1.0679121485086411,-1.5397619674081324,1.0826894881733944,2.1565898291477077,-0.7051230031710496,1.7243184535781555,0.019607955994523557,-0.32609992000786925,0.8810256452136234,2.3992503499531805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3666914,1.0,0.0,0.0,1.0,10.838312339137191,0.8448760326396194,0.5313362931858729,0.9956453075348088,0.02298128100396325,-0.029840175293079873,0.0852751209076316,1.030479688371224,0.12932921864046684,-0.18240625330770094,0.5267845174855081,-0.056934664749005236,0.3114702891434482,-0.49509314850692865,0.9834644031032247,-1.0116373072473874,0.4084238010014272,0.1737912985849719,-0.9016335001764767,-0.5092597493602032,-0.18621065095117312,1.0313535826202682,0.39577785794035547,-0.9963549178611217,1.0839964059565572,-0.9303747701438634,1.717486016980518,0.823106841967484,-2.454696003730166,1.4014090884027302,3.301803403320565,-0.9119318398295455,1.0013681829934953,1.1853641866127433,-0.3915742258644794,0.7240916017305009,2.4859678882176595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.383358099999999,1.0,0.0,0.0,1.0,10.855003984593123,0.8504513267333673,0.5289801053287998,0.9953465448713714,0.026742799873000808,-0.02937851898689923,0.08778941217317887,1.025327078992984,0.13866735260953944,-0.20548494696117967,0.2483785688361758,0.20669060651102955,0.3249129191218672,-0.5115100055808383,1.0124307116001978,-1.000382595482731,0.3594544231688031,0.19801413781349117,-0.8374523584646809,-0.5249190913025877,-0.17705322121890338,1.0612775959387297,0.3862184534555587,-0.9893259593510616,1.1185611676966811,-0.7842631554299686,1.573499359012617,0.46000936197335646,-2.178787164307549,1.9009548423805607,1.7265982419539065,-0.55495130821281,-0.27919500966656813,2.3834372297304873,-0.3733136275389964,0.6315932414066021,1.8750567949875827,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.400024799999999,1.0,0.0,0.0,1.0,10.871457532823007,0.8557396455744746,0.5268899447965035,0.9951596931232725,0.02663356331889015,-0.02620473138849892,0.09089087160210117,1.0276015024602123,0.11844341235034783,-0.16658951874764902,-0.12720184044965688,0.5232221333723189,0.355369127413203,-0.521235305972138,1.0359144866369359,-0.9963036311809848,0.33579741693869797,0.23715658672798007,-0.8440801103381304,-0.5277581632973841,-0.1955171698863927,1.1108016491737664,0.3833340454681471,-0.9753017677080189,1.1464984241265963,-0.3594465868658893,1.2338809463720035,-0.17707770152279842,-0.15963010047728943,2.765400936959481,-2.1802395643245167,0.4351296505750348,-1.5425598342226754,2.632464169768898,-0.11625608815191134,1.0256947125877367,1.314716192481862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.416691499999999,0.0,0.0,0.0,1.0,10.888187450267557,0.8607981280240137,0.5255854483294855,0.995080223097423,0.0236783694169586,-0.021059355835547813,0.09386792824990212,1.067657302961277,0.12240750965152128,-0.11578192674651641,-0.40995016662811035,0.7258830399005965,0.3366674104826666,-0.5234915824394737,1.0535601587379944,-1.006285197338671,0.3541334091775534,0.29019435340553634,-0.9101271559581358,-0.5104147406081099,-0.2284719851969815,1.1490265770953043,0.3823432427667558,-0.9551360672184895,1.162385128427156,-0.0261703231607579,0.8534465441254944,-1.0853052146934081,0.5961107927045844,2.729173605466592,-3.0039785094002758,1.432045331531614,-2.37811800468448,2.0583759912347035,0.060853934291298574,1.3378411475106973,0.6362704350939311,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.433358199999999,0.0,1.0,0.0,1.0,10.905765743203533,0.8665534554100055,0.5248642108362435,0.9950353400125416,0.01857661673383077,-0.014947250954327649,0.09662381241577347,1.1120903741533588,0.14133745906961767,-0.07906674231125049,-0.6286102867936179,0.7626508983891629,0.2796702198798807,-0.5221076518221848,1.0643627616708886,-1.032480544024446,0.35566781643623696,0.32812922218844015,-0.9442129275833735,-0.4800232234433082,-0.27478792858374235,1.1794143194399893,0.38536251400145266,-0.9307069736015858,1.1677074810477563,0.5152395486339837,-0.895427030783166,-1.2769186292444221,0.401551952464423,2.663996358463083,-2.547059342223777,1.8777425492233486,-3.3094573504048426,1.7008905048999394,0.2019982128705339,1.6007812407736302,0.21617722719963656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.450024899999999,0.0,1.0,0.0,1.0,10.92370886146222,0.8726307012322803,0.5243491988641539,0.9950100422955397,0.01195287254216189,-0.009518738019591086,0.09859786100891672,1.1426832782975975,0.16935671850396078,-0.06396287562072789,-0.7384182069661371,0.6768709465006099,0.24932611725489195,-0.5063168964690377,1.0237125313500868,-1.048849236774727,0.367518501029831,0.37899440962072967,-0.9950293038362178,-0.4478231971178283,-0.3387874508409663,1.205723040651336,0.38907652999565445,-0.9017765858072858,1.1695910504122924,0.8486891730409802,-2.16084772890392,-1.0311809921176498,0.4916885358196053,3.0525846468878606,-2.9394750390122315,1.8312623965970474,-4.1933902138407255,1.8235243944521549,0.25824704550619676,1.8062878517613363,0.07150535644332806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.466691599999999,0.0,1.0,0.0,1.0,10.942034198123244,0.8796069767729253,0.5236680790863758,0.9948824330221961,0.0051823321951497865,-0.004984430714174734,0.10078315011602942,1.1789751261572587,0.20631849102521682,-0.04931167800694919,-0.7988595927687245,0.5205882132266648,0.25128356057712276,-0.49381795614154056,0.9923343599842427,-1.0668533125071005,0.3720574670761262,0.42988224725701196,-1.0421956248487838,-0.4189810214725802,-0.41456788193778077,1.2401985874900208,0.3939707660681289,-0.8704972581236845,1.1700909976962244,0.2948322686819575,-0.39339113328668185,-4.249018612149636,0.26533926344118697,3.115947713780926,-2.6135903573190924,1.5985230307693319,-4.667571945356369,2.2658095181450517,0.33085213515824047,1.985937515257033,0.001612996242153264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.483358299999999,0.0,1.0,0.0,1.0,10.960842906884963,0.887265356511494,0.5232004646740754,0.9947014159483226,-0.002185476769940955,-0.0022529995588803664,0.10275816655953876,1.1972763833942777,0.216506246603394,-0.020616040025617725,-0.8911012677395602,0.3415632978465204,0.2897991160407139,-0.4964891345241545,1.0105994673477885,-1.1904834737809558,0.3763631608338215,0.4828595411432748,-1.082149156652878,-0.39453898952398186,-0.49437349352430826,1.2812501756434722,0.40010495655773815,-0.835578536236217,1.1696448170612306,0.1297141175066413,-0.3880898159139388,-6.992943301320671,0.263121701619995,3.1500490435324444,-2.149181012365921,1.5386373283261663,-4.76330009271609,2.3120628139082413,0.41599957513197106,2.256134188251065,-0.11349005960062936,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.500024999999999,0.0,1.0,0.0,1.0,10.979628391926356,0.8948276632296518,0.5231071238305647,0.9943612597838033,-0.010181496004571937,-0.0008325959104324239,0.1055524938801855,1.1759341379168324,0.20995676450931708,0.016498416322771384,-0.8674664795974111,0.12138829900770187,0.3546452284508498,-0.4894941435770447,0.979398006914457,-1.299951888747343,0.38082820800490613,0.5348840920446963,-1.113835135206382,-0.3676930079525528,-0.5733448692483233,1.3172675020911497,0.40783744630583296,-0.7952926347730365,1.1663079881435328,0.7509957850352211,-4.086980026537298,-4.220394982482878,0.16378717436450754,3.0454744756477,-1.4460265714807103,1.4985708336346968,-4.8596420394200655,1.931939357125681,0.4312116647139985,2.4985126295023297,-0.22903725264834054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.516691699999999,0.0,1.0,0.0,1.0,10.997696225760247,0.9023464436643459,0.52358801320448,0.9939403473938128,-0.016773342915416035,-0.001700974338421637,0.10862019828930859,1.1244565525661565,0.20266684928280213,0.04299269256274892,-0.7829152474563177,-0.1022102923573685,0.4233730564424309,-0.47145589162326146,0.8743665273312101,-1.3311635878900505,0.38182274423178336,0.5843755600298298,-1.1303501387706731,-0.34458652849810306,-0.6563618854811131,1.3456482830102854,0.41447870746231574,-0.7522946153519641,1.1620102267038024,1.0166878036664218,-7.553307032353411,-0.560900321941706,0.03493126607725632,2.811760548855965,-0.8280426618242006,1.2577141798268063,-5.0335013351547335,1.1568072575662773,0.4761088531613123,2.6180547173174333,-0.3016527837231678,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.5333584,0.0,1.0,0.0,1.0,11.014757311677537,0.9095626758333997,0.5243018120462949,0.993369624740891,-0.02297477030868996,-0.0038175723542789946,0.11258052545944373,1.0850721169469075,0.1832202849164548,0.057000640931433304,-0.760311387538487,-0.2483325002820605,0.4728033151894594,-0.4556044823423104,0.7276206022822078,-1.3186486035387546,0.38199258586956575,0.6286096311239318,-1.1414366124700328,-0.3257691181107139,-0.7411285826535701,1.3558278211305095,0.42370777315180025,-0.7080239696588075,1.156252875242575,0.6611381449476919,-8.445067688137415,0.49050271792832606,-0.022480884778808025,2.6404382768982417,-0.37412057058058623,1.066310277685935,-4.7409614639022575,0.12959044008998935,0.6468407016166332,2.700454890106701,-0.3877649052890284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.5500251,0.0,1.0,0.0,1.0,11.03155828274959,0.9164738605651741,0.5252891797968845,0.9927442189571679,-0.028920620965199737,-0.007057105971438701,0.11650197708802099,1.0489967045472017,0.1897173397420111,0.07174470856651591,-0.5744887445990675,-0.4058207246032886,0.5671861966202155,-0.44941790938246207,0.5928637080554504,-1.3148134645922585,0.38107337990709744,0.6723903452889897,-1.142820849398064,-0.3090427814878867,-0.8143942503419526,1.349967972985981,0.4360401073055836,-0.6622792723180814,1.149084704009841,0.3311440021621932,-6.652733212450904,0.30286203412642365,-0.29431600501420496,2.4851932695545664,0.0628888033158809,0.6825330534177193,-4.225562142401025,-0.7131512712080282,0.6755591014718448,2.7072998992027766,-0.4210332119358678,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.5666918,0.0,1.0,0.0,1.0,11.047261420685356,0.923940266404084,0.5265698588781634,0.9919434022463368,-0.03176013684485896,-0.011351834211355197,0.12210944397382126,1.0079890232497615,0.18393351067743113,0.07739484898656493,-0.31245255538532674,-0.5327813370048944,0.682502832199229,-0.44456632686063713,0.5058623850182968,-1.3085531822104048,0.37218203274802525,0.7114495724553019,-1.1393403148335832,-0.3030179708279197,-0.8819809357710804,1.3320560645468238,0.44622645490480184,-0.6177804591987217,1.1422184067758319,0.5382703962199827,-5.078429697970736,1.3221230692175348,-0.6353017289738706,2.138501515154904,0.7193607633896177,0.17590674809585752,-3.7803196305753075,-1.5116189483967457,0.5988653010972548,2.670126927277389,-0.4324504758042906,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.5833585,0.0,1.0,0.0,1.0,11.062588370009108,0.9307289806998742,0.5279559099211816,0.9910873861984917,-0.03312954513302776,-0.016130613965899546,0.12801573907377034,0.9926500221054722,0.13805433362239905,0.06770747163044237,-0.11548749220202974,-0.5846288149228205,0.7099183818136447,-0.4314755269571029,0.42358237956111267,-1.2707426074768027,0.3598966132545198,0.7436738716942541,-1.1188421093276926,-0.30317921149090826,-0.9404051567157715,1.299580573931493,0.45600232393317885,-0.5732748634003733,1.1346696593196663,0.5254439103218927,-6.097228828222696,2.710936569867459,-0.6981450950755858,1.9941805425579202,1.0190374478508144,-0.15824859076222136,-2.9959988776495132,-2.4382993433051063,0.5616095494263174,2.587724925811708,-0.1818592879403485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6000252,0.0,1.0,0.0,1.0,11.077993997349513,0.9369515754637097,0.5292767460713499,0.9902065601338074,-0.03261263119788517,-0.02085160009880739,0.13413648022683014,1.001426854413676,0.07197388135150562,0.052130062589770446,0.05001638458537691,-0.5480134953001614,0.6477690611206718,-0.42705149482031335,0.30262101759561844,-1.218188449152385,0.3489104830358327,0.7779223901526021,-1.1053723319693929,-0.30829293440323313,-0.9818477647593227,1.2507792572166974,0.46494681065964905,-0.5315227891566697,1.136156418387201,0.7409676072328032,-6.146347991929345,3.270193533524364,-0.5781578155269951,2.022563073061915,0.8672149069900139,-0.39506605781282034,-1.9818018692176578,-3.300172470731522,0.4914650819955429,2.5324186625474936,-0.01700505590802661,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6166919,0.0,1.0,0.0,1.0,11.094018067830373,0.9420520949349172,0.5306064091985014,0.9894853450738288,-0.031303909040127975,-0.024705435925496778,0.13902682690281282,1.0137284263607182,0.017642766077913097,0.0415371614755057,0.02981713415422789,-0.4602798637039717,0.6002121476450323,-0.406776557318169,0.21870370340693504,-1.1617359383464216,0.3406246475264323,0.8110927756338562,-1.0899348879470316,-0.31634810642240613,-1.0064653511431514,1.1895746048956108,0.4723845260973691,-0.48886073915421263,1.1341028229890617,1.4794387127619384,-4.177565305032204,4.1224824421718775,-0.32778635963003083,2.0333027682697504,0.789664023119152,-0.43263435063293487,-1.0722006623084166,-3.8643253097468744,0.5543422182601432,2.596567535926452,-0.23870147135992006,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6333586,0.0,1.0,0.0,1.0,11.110196868948236,0.9469412337607954,0.531974410335763,0.9886428379170981,-0.031305435652152644,-0.02806699317318154,0.14428289097489025,1.0231487612349965,-0.013355008702597648,0.024110387025249855,-0.19911496310996973,-0.37530084136098596,0.6073869309494219,-0.37773677243233456,0.16336856225685795,-1.0807720929144928,0.33798424919574105,0.845699284648445,-1.079050145221153,-0.322714108266621,-1.017587858316314,1.121968155936781,0.4834249215578017,-0.44497036485461894,1.1281996867617723,1.6968772294558374,-3.1141699097112276,4.774204797335566,0.015293663505941517,1.9420935934699084,0.767245788998159,-0.26005086037190467,-0.42757460531581554,-3.9002800142708565,0.8002877854404229,2.69863127497088,-0.49845080855480867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6500253,0.0,1.0,0.0,1.0,11.126723752788179,0.9514592772754606,0.5330230247566571,0.9877458327248847,-0.033966991015056965,-0.031065451522176414,0.14912863969650667,1.019655636159828,-0.028227990868986308,-0.007452160691937992,-0.4591612869581764,-0.3143624820669442,0.5894781620551072,-0.35021386987782577,0.1148978321385668,-1.0025954601549163,0.34113443732954124,0.875829358222426,-1.0643599771640404,-0.325016485771527,-1.0207178664919856,1.0595650110679147,0.4990608389645689,-0.3989061834130983,1.1174877628071809,0.4748553936214439,-2.405312253083021,3.8661962696673062,0.34920913349299265,1.7932374763135572,0.8657557886643342,-0.0736535751828371,-0.06894677707815841,-3.1738420736807194,1.0544522669529293,2.7145498052599266,-0.6843124518670204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.666692,0.0,1.0,1.0,1.0,11.142901064626582,0.9561148037715407,0.5335404425425524,0.9867495588569811,-0.03838786271561776,-0.034058241019859894,0.15392113665872248,1.0024518710860033,-0.007572248453527164,-0.019373855140277264,-0.6481103200566208,-0.28509437887717715,0.5996043132435452,-0.3619082276545935,0.08319132679994037,-0.9518986261791647,0.34962457692611637,0.9054739867413953,-1.0501915612152892,-0.3251692323496206,-1.0198860888153711,1.016173208557952,0.5185734007530505,-0.3544851903759677,1.1053892260787082,0.7476617219042022,-1.5293666866729476,4.283157987626547,0.5285056777180288,1.663549813371067,0.956069467400932,0.06640411890223791,-0.013133241451823126,-1.696971017175046,1.2052632400438719,2.631104704144498,-0.7971345069610576,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6833587,0.0,1.0,1.0,1.0,11.158605088427176,0.9614150816892552,0.5342534795688221,0.985623866840518,-0.044234654941531774,-0.037039281231105496,0.15879855182724947,0.9803736667632454,0.006151338018757113,-0.016132606372362246,-0.8127721990979424,-0.24926276650444057,0.5902962525783834,-0.32529176263690424,0.06391884062502277,-0.8598232416901656,0.3587513284871874,0.9312811295714492,-1.0324909311793782,-0.3228030107145111,-1.0211556420825958,1.002999197364012,0.5392363606502473,-0.3112025178679681,1.0909165594328452,2.489462665575673,-0.35343477538974827,4.534100901835443,0.6592269236177944,1.4522771833322339,1.0781434922357591,0.37223506697508063,0.09580156919590962,-0.23011164972210232,1.2578050853954974,2.5445649968965065,-0.8247358929131021,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7000254,0.0,1.0,1.0,1.0,11.173825750268787,0.966604832752493,0.5349128981988179,0.9844279932229862,-0.05144317515988196,-0.03987747294767716,0.16329394673331013,0.9499399557765863,0.018269466940841028,-0.048754301265826167,-0.8012627020732217,-0.28593003070638023,0.575682729400213,-0.2789259728378934,0.07141014405796374,-0.8007616271779231,0.37159885166183776,0.953883323004282,-1.0142533729311978,-0.31276137196811343,-1.0166926967887362,1.0085028048931053,0.5605003207865727,-0.2696661875084177,1.0778979746658786,1.956375870510692,1.001872688053953,3.1862982259535033,0.5733337973651015,1.3858472290871195,1.2282269628734277,0.20023646010165672,0.545503972029535,1.2588098765352025,1.1884619047391414,2.4306989653536792,-0.5414577126209174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7166921,0.0,1.0,1.0,0.0,11.188442042945823,0.9721551258287782,0.5345265943703569,0.9831864389549632,-0.05698308726900181,-0.043408893891299816,0.16796732405883516,0.9397402941792549,0.05646607439250351,-0.11950579217414121,-0.5081906316339375,-0.3029894058859114,0.6205048629022056,-0.26007910319482314,0.09731466368500041,-0.753613088405167,0.37786249328827726,0.9774761295975017,-0.9915499505351331,-0.31612844869535855,-1.0029721399813465,1.0449596105025105,0.578851836705679,-0.23017905697624777,1.072867932914967,0.7327536277665048,1.9054745912285898,2.1397916523043445,0.29129193340395476,1.5634282025708244,0.9262500275693113,-0.19139153029213285,0.7360174805073467,2.2868861248457395,0.8466898720473638,2.1676309499294324,-0.06034454768005684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7333588,0.0,1.0,1.0,0.0,11.203068832297728,0.978481448364172,0.532806080084374,0.9820010067843512,-0.05938075794564323,-0.04565706831637014,0.17338794760039108,0.969507708460837,0.06097324314285363,-0.15440633533778442,-0.24491648800323107,-0.10990977346136344,0.7371821297057318,-0.2545008030621014,0.13492609079722281,-0.7294350961150015,0.38130860219476514,1.0059977006518563,-0.9833783102622189,-0.3191411024039532,-0.9921587317039926,1.0847324948470383,0.5887233729674763,-0.19741167800203996,1.0758864857202401,-0.7931397541072622,2.995846563880838,-1.1699151778571752,0.21257362974661256,1.7062770865237404,0.3150180079861549,-0.11908128995394815,0.6031316332161802,1.9259371064051225,0.6520365380477923,1.6321309908837989,0.28826523498060036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7500255,0.0,1.0,1.0,0.0,11.218567592820103,0.9847125478048374,0.5314006673369451,0.9807269265163409,-0.061252340536664666,-0.04518009787450952,0.17994889591392882,1.0115752610132067,0.029232725482916777,-0.14381304350999152,-0.06670829899425143,0.15775391493210825,0.9058164535224835,-0.28651714787438215,0.19717641553746593,-0.7926103389947514,0.384948295118073,1.0343521462334322,-0.9810493292677274,-0.3200978329659095,-0.9828677119986983,1.109157642445155,0.6005864314430412,-0.17577458180472175,1.0824767932986694,-1.32769172440521,2.9453278788227335,-2.840880918871406,0.10366376546137124,1.6612128244682114,-0.09422712746629486,0.02641759318670541,0.8046614123523058,1.4559702713837568,0.6252781350867281,0.8023684339557196,0.8792251966931949,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7666922,1.0,0.0,1.0,0.0,11.234658603899538,0.9909756830807916,0.5301797565454028,0.979322765322798,-0.06164062889420184,-0.04234062013176245,0.18797506770019518,1.0498024833686763,0.023683848305403876,-0.11348323585314507,0.40302211552083433,0.3754544977526805,0.9630414614583794,-0.29875728238839,0.2331038831131725,-0.8241313161361096,0.3847640679543952,1.061371572214985,-0.9865192207929039,-0.3182605142032235,-0.9653366309814883,1.1332649342911816,0.6095660191555763,-0.17066601004562038,1.105194050891693,-1.0549722121310845,2.4583433739252585,-2.2613573101471234,-0.4233762163339649,1.4969263609042311,-0.33844932822513063,-0.021542629842620904,1.1707184141751097,1.0878727953706164,-0.09907573463682358,-0.432770762052941,1.608060566689769,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7833589,1.0,0.0,1.0,0.0,11.251077475415949,0.9981101711019451,0.5296434008631198,0.9783724056275704,-0.056552844522342466,-0.036754661824095286,0.19554617489776943,1.1074601444602505,0.037637657687655646,-0.12142180846510213,0.8105801454657082,0.4948119968814665,0.9017496731044543,-0.32168295861023244,0.27912135855786613,-0.8679890667568095,0.3708357263485264,1.0842497913919973,-0.9923309961051869,-0.3208159220635055,-0.9438436868116337,1.145420141482362,0.5972839003500982,-0.19020030272453725,1.1360789193923662,-1.6697765479668523,3.082126935341779,-3.073995885529931,-0.9199580115267485,1.363520603397174,-0.5837827845683692,-0.1646575161628762,1.3617974123763648,0.8629516448252179,-0.9580556305699169,-1.4582624954435957,1.6733232189627787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.8000256,1.0,0.0,1.0,0.0,11.26855688315745,1.0060151519364553,0.5278507780296242,0.9774476349323652,-0.0505934300302715,-0.030771781102126094,0.20270550878232374,1.1343544505453957,-0.005298249587478876,-0.10423640856689462,0.849176697236941,0.603327823780733,0.8294258116948252,-0.3544166119723883,0.33584165309969416,-0.926598050586833,0.3540987395729695,1.1068223498962644,-1.0059786858640352,-0.3237491090524871,-0.9199432931157819,1.1620300466487985,0.577630767599537,-0.21927485711123992,1.160971603078667,-1.7207992728593269,3.0918490009104556,-3.178081781923498,-0.976847656600286,0.8905100486523828,-1.308361669244455,-0.24342886955556034,1.5655038360743,0.45056613807232515,-1.1733194656826003,-2.517812947757378,1.6251737932889654,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.8166923,1.0,0.0,1.0,0.0,11.2860601280007,1.0127500543393135,0.5277119179417675,0.976592119512726,-0.04519838833510907,-0.023356856333871485,0.20899616039475247,1.1326244400423442,-0.06195196671751313,-0.05952933996701143,0.8479439906598394,0.6683835038808539,0.7341380687212253,-0.3790430490921615,0.3821831980448147,-0.9739253380263783,0.33827407267200643,1.1139335190477466,-1.03594313897078,-0.3289302339439488,-0.8916601212422346,1.160439042789182,0.5581731732727138,-0.27412756883731304,1.1902514875135846,-1.4411328016522857,2.8971780031109073,-2.781589318339929,-0.7684722818675273,0.26061003529902355,-3.1710631745146785,-0.24058525581760762,1.7969653684343596,-0.07822473704134066,-1.102138994575096,-3.7690078846046853,2.2274148043008988,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.833359,1.0,0.0,1.0,0.0,11.303938381900304,1.0194744076175262,0.5270882847058048,0.9757961592689528,-0.039409421742664485,-0.01637974481174389,0.21447717126484958,1.1412057629840902,-0.09056114319803305,-0.0684328785716951,0.8308854573969525,0.5720992080294685,0.6157736405067381,-0.4024544681029846,0.4324144463485913,-1.0193178799707852,0.32848294561256647,1.1155093684469009,-1.1116810030854027,-0.33176863361875775,-0.860044327703612,1.1594225501991047,0.5408927276377675,-0.34490870453192174,1.2352189117163506,-1.216909209964335,3.0333579068438237,-2.5710636262449444,-0.15124080777061988,-0.6243160477951947,-4.189711202850387,-0.11808410693704308,1.9204326321591774,-0.070002218638869,-1.0126046488229383,-4.4117214391501,2.8378570665638527,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.8500257,1.0,0.0,1.0,0.0,11.321951375837124,1.0258307321485882,0.5262654620987672,0.975108894981326,-0.03389999218354319,-0.010673743956235729,0.21885955461941745,1.1397562023177956,-0.11305839339475832,-0.06434743231024712,0.7973595520667529,0.5042798262698212,0.5470075343795262,-0.4196067705515867,0.4832953304968026,-1.0596276303054515,0.33323270233026525,1.0931229425001703,-1.1756004583798731,-0.33286637871412406,-0.8276455721414199,1.158105630834405,0.5244196174716392,-0.421185244257079,1.284846912256184,-1.0291360886439491,3.0528469431987943,-2.418580182919614,0.2849848330922608,-1.3431828704380935,-3.83515964734893,-0.06586457399283058,1.9439214458886394,-0.07901500385196684,-0.9883846331984311,-4.576583230342974,2.977674077041857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/walking.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/walking.txt new file mode 100644 index 000000000..c167e9cb6 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/config/motions/walking.txt @@ -0,0 +1,1610 @@ +time,contactflag_LF,contactflag_RF,contactflag_LH,contactflag_RH,base_positionInWorld_x,base_positionInWorld_y,base_positionInWorld_z,base_quaternion_w,base_quaternion_x,base_quaternion_y,base_quaternion_z,base_linearvelocityInBase_x,base_linearvelocityInBase_y,base_linearvelocityInBase_z,base_angularvelocityInBase_x,base_angularvelocityInBase_y,base_angularvelocityInBase_z,jointAngle_LF_HAA,jointAngle_LF_HFE,jointAngle_LF_KFE,jointAngle_RF_HAA,jointAngle_RF_HFE,jointAngle_RF_KFE,jointAngle_LH_HAA,jointAngle_LH_HFE,jointAngle_LH_KFE,jointAngle_RH_HAA,jointAngle_RH_HFE,jointAngle_RH_KFE,jointVelocity_LF_HAA,jointVelocity_LF_HFE,jointVelocity_LF_KFE,jointVelocity_RF_HAA,jointVelocity_RF_HFE,jointVelocity_RF_KFE,jointVelocity_LH_HAA,jointVelocity_LH_HFE,jointVelocity_LH_KFE,jointVelocity_RH_HAA,jointVelocity_RH_HFE,jointVelocity_RH_KFE,contactForcesInWorld_LF_x,contactForcesInWorld_LF_y,contactForcesInWorld_LF_z,contactForcesInWorld_RF_x,contactForcesInWorld_RF_y,contactForcesInWorld_RF_z,contactForcesInWorld_LH_x,contactForcesInWorld_LH_y,contactForcesInWorld_LH_z,contactForcesInWorld_RH_x,contactForcesInWorld_RH_y,contactForcesInWorld_RH_z +0.0,1.0,1.0,1.0,1.0,-4.1399177600865628e-22,7.794371290226094e-22,0.5873290440786716,1.0,4.971475164066711e-22,-2.234647375162433e-21,3.3485581254605336e-23,-0.0011516928631436765,-0.005888308075735951,0.009411731662396505,-0.04792597737654187,-0.04444079720599194,-0.01801584899080429,-4.872120305816547e-22,0.49999999999999994,-1.000000000015507,1.3364837633393094e-21,0.49999999999999994,-1.000000000015507,-3.797325942399921e-22,-0.49999999999999994,1.0000000000155072,-2.84300089838222e-22,-0.49999999999999994,1.0000000000155072,0.07875903612703329,-0.006628352090005674,0.12329430881656389,0.08203744316877765,0.5159462027080619,-1.0232690939297129,0.04466653259199681,0.02355943165866181,0.055613454387861694,0.04460176404955183,0.03207182049204338,0.00729761041156074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.008333333333333333,1.0,0.0,1.0,1.0,-9.597440526197304e-06,-4.906923396446626e-05,0.5874074751758582,0.999999960100221,-0.00019969156974637453,-0.0001851699858955525,-7.506603646331176e-05,0.0008920030827181299,-0.006640138744367704,0.007360419042443622,-0.04715794099237662,-0.041420528901944385,-0.02327384439670533,0.0006563253010586108,0.49994476373258323,-0.9989725474420356,0.0006836453597398137,0.5042995516892338,-1.0085272424649212,0.0003722211049333067,-0.49980367140284443,1.0004634454687393,0.00037168136707959855,-0.4997327348292329,1.0000608134356035,0.08495365794419878,0.004097076485726214,0.10756530189451663,0.09203347825791355,0.5322014711209844,-1.0486486553144792,0.04061550305624256,0.02516010799766044,0.05914334777839425,0.04056918839358901,0.029561296397324632,0.01050655724744054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.016666666666666666,1.0,0.0,1.0,1.0,1.4804666434536605e-05,-0.00011062220267488248,0.5874517674136143,0.9999998444026621,-0.00039296281547751143,-0.00034518951982773037,-0.00019395636760221124,0.004533082635684161,-0.0075703825797357035,0.004898150342268435,-0.04663162149860843,-0.03757265775136991,-0.03078387164423391,0.0014158942990699795,0.5000682846080954,-0.9982072449839317,0.0015338913042985591,0.508870024518683,-1.0174774776040816,0.000676925050937376,-0.4995806648667056,1.0009857224784804,0.0006761531398931501,-0.4995073117267112,1.0001751093029645,0.09402449909584056,0.020636223669205922,0.08691973538340392,0.10869508742324342,0.5563176241485412,-1.077210052617814,0.035103364248213594,0.030448260042328368,0.062126171324288215,0.035088542933835606,0.029337197957716166,0.012236275611128278,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.025,1.0,0.0,1.0,1.0,6.584858747438264e-05,-0.0001752073447204314,0.5874892622865427,0.9999996478404751,-0.0005882567023283878,-0.0004983042366970876,-0.0003316110154591577,0.007357768179335914,-0.007810198893892082,0.004388466358319944,-0.04698647043657845,-0.0365275714665943,-0.03400198055092146,0.002223400285989287,0.5002887007937367,-0.9975238851856455,0.002495230150127204,0.5135715120917095,-1.0264807433418848,0.0009572771757368667,-0.49929620040213896,1.0014988816574775,0.0009564904159768587,-0.49924378152993765,1.0002647513624556,0.09807922070582155,0.030150367801906608,0.08006852012705012,0.12034098989608438,0.5704495174913671,-1.0792862713876827,0.032975240632576085,0.03735970831957314,0.0605848010400134,0.03297856240055733,0.03425587291426946,0.009328148826077687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.03333333333333333,1.0,0.0,1.0,1.0,0.00013727477585301297,-0.0002407872485325345,0.5875251837976666,0.9999993673751956,-0.0007844748580323574,-0.0006496241219583595,-0.00047732264331663376,0.009523563871683715,-0.007900880757671114,0.004250608014008243,-0.0471582347848631,-0.03625143062525323,-0.035394867052206604,0.0030505479775003387,0.5005707907381272,-0.9968727696484808,0.0035395744692332987,0.5183775164768725,-1.0354655821272096,0.0012265123948136441,-0.4989580030613794,1.0019954691624806,0.0012257958465691056,-0.4989363805114734,1.0003305784500658,0.09978114215082994,0.03649809898585987,0.07700552077520184,0.1296658905897751,0.5821589061353261,-1.0756272848487392,0.0320332311794645,0.04309097987572175,0.05872980777027692,0.03204568096363263,0.03911727446594071,0.006868221437650313,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.041666666666666664,1.0,0.0,1.0,1.0,0.00022435661245929204,-0.00030692864011849937,0.5875605184693705,0.9999990019685314,-0.0009811937128689967,-0.0008004437260605289,-0.0006265865304671876,0.011191561912174972,-0.007959960370502969,0.004185027450543833,-0.04726559967475394,-0.03616909270712095,-0.03601994228168346,0.0038864193218364524,0.500897002443501,-0.9962404598393921,0.004656328326623455,0.5232741605272982,-1.0444078647560304,0.001491164362061275,-0.49857801740421026,1.002477711786982,0.0014905850987040692,-0.4985918269555053,1.0003792217197498,0.10057324261770544,0.0411265516596071,0.0750722493573619,0.13811866054947985,0.5924089230121199,-1.0697443716216437,0.031668693402941456,0.04752421704647958,0.057177402192962745,0.031689045120795865,0.04312375444169292,0.005090734921489037,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.05,1.0,0.0,1.0,1.0,0.00032352238379659284,-0.00037354940401244073,0.587595493076498,0.9999985512633214,-0.0011783027719092655,-0.0009510809117121217,-0.0007775081578191668,0.012482817341649405,-0.008013080899248747,0.004137752608969315,-0.04735620908387651,-0.03613320877037328,-0.03632203898100171,0.004726768687795429,0.5012562332657873,-0.9956215654925248,0.005841552145057963,0.5282509985270745,-1.0532946549875704,0.001754323951529335,-0.4981659327772714,1.0029484258656967,0.00175394659858237,-0.4982176512707785,1.0004154240320906,0.10100871008480507,0.044618917580667716,0.07365635378711932,0.146249010059312,0.6015206984888799,-1.0625150015855933,0.03157286118340393,0.05094067680833203,0.05593184697479714,0.03160089450147466,0.04629692514759087,0.003785271424399106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.058333333333333334,1.0,0.0,1.0,1.0,0.0004320639153118912,-0.0004406398864987353,0.5876301913460779,0.9999980150653734,-0.0013757743030016777,-0.001101603294422552,-0.0009292903540099731,0.013488057672993242,-0.008065520288053027,0.004098274559138687,-0.047442606235229605,-0.0361061918734568,-0.03648818438059915,0.00556989782324987,0.5016406510698455,-0.9950128539429401,0.007093811827611989,0.5332995055021129,-1.0621164481157903,0.002017378715118007,-0.4977290061240714,1.003409909236562,0.002017266673728647,-0.4978202115363788,1.0004423095768231,0.1013007400309371,0.04729542278672838,0.07257479263176325,0.15426457419863973,0.6096968827037097,-1.0542315962698323,0.031596672320757795,0.05359696150503246,0.05493164471883194,0.03163224803181489,0.04878627220772036,0.002796055765119654,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.06666666666666667,1.0,0.0,1.0,1.0,0.0005479218496982617,-0.0005082030467709198,0.5876646626868185,0.9999973931868482,-0.0015736015846607677,-0.0012520162215812296,-0.0010815974028438092,0.014275571469564659,-0.008118212120042243,0.00406378863865522,-0.04752801892241178,-0.03607890958142127,-0.03659703920712992,0.006415114354977714,0.5020444903122327,-0.9944119856153287,0.008412628381701958,0.538412613238803,-1.0708651815920676,0.0022809351568752983,-0.49727265008552085,1.0038639532776772,0.0022811507324459516,-0.49740454673398315,1.0004620249615093,0.10153414451479603,0.049366525156446794,0.07174080555206741,0.16224372977715873,0.6170937377440056,-1.045028720177248,0.031672633794798684,0.05568431476665969,0.05412234481524614,0.03171563358698943,0.05073836681449784,0.0020283289662126336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.075,1.0,0.0,1.0,1.0,0.0006695262169407225,-0.0005762428346705541,0.5876989426523612,0.9999966854143004,-0.0017717833699492853,-0.0014023116327423113,-0.0012342877246918728,0.014896687605676185,-0.008171269499041553,0.004033014931852052,-0.0476133416629559,-0.036049679529614465,-0.03668175424851711,0.007262133565163137,0.5024634264891196,-0.9938171738504057,0.009797873990564634,0.5435844011311797,-1.0795335934520778,0.0025452559450313186,-0.49680093421129373,1.0043119483168161,0.0025458605668451373,-0.4969745720894705,1.0004761150595933,0.10174337259585305,0.050981378217305195,0.07109662175095899,0.17021380907941858,0.6238336389128318,-1.0349865932449998,0.03177109994707051,0.05734166272075569,0.05346202570849279,0.03182141867872527,0.052273359702741384,0.0014231329258773684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.08333333333333333,1.0,0.0,1.0,1.0,0.0007956731544483452,-0.0006447628397483674,0.5877330584437924,0.9999958916890833,-0.0019703201802194208,-0.0015524810907410415,-0.001387301886809537,0.015390801628247653,-0.008224608746829933,0.0040050464995519995,-0.04769874321122953,-0.0360184683166062,-0.036756162050217686,0.008110837231575265,0.5028941799491878,-0.9932270419194794,0.011249525199692268,0.5488098405540168,-1.088114958146151,0.0028104534893264735,-0.4963169557068416,1.0047549870394854,0.002811507710424706,-0.4965333240722708,1.0004857438436072,0.10194286058109778,0.05224959219409353,0.07059981733438025,0.17818186173250353,0.6300096656500909,-1.0241579019832558,0.031879625504868586,0.05867338050629556,0.052915814965937,0.031937212040998274,0.05348812179214679,0.0009379542950327391,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.09166666666666666,1.0,0.0,1.0,1.0,0.0009254492897950333,-0.0007137648786476778,0.5877670300283862,0.9999950113840324,-0.0021692120699415315,-0.0017025163765523313,-0.0015406135880698974,0.015787723382768515,-0.008278194971072923,0.003979266467279207,-0.047784302719035325,-0.03598573072035105,-0.0368261143742277,0.008961181241514767,0.5033342530256878,-0.992640510228166,0.01276757168610636,0.5540845622253479,-1.0966028918184654,0.0030765830367791283,-0.4958230445361888,1.0051938785662484,0.0030781474341951085,-0.4960831033929347,1.0004917476311772,0.10213853112279754,0.05325332215450729,0.07021725342138518,0.1861458682751801,0.6356930166036001,-1.0125821210909258,0.03199283569209431,0.05975702417422735,0.052457496927336145,0.032057653530766055,0.05445699644723523,0.000543433519051284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1,1.0,0.0,1.0,1.0,0.0010581475882864711,-0.0007832515387893625,0.5878008741043833,0.9999940444326966,-0.0023684601714819378,-0.0018524129029087518,-0.0016942121594333945,0.01610962949021016,-0.008332034083361934,0.003955222904478714,-0.047870099382501974,-0.03595211269580484,-0.03689417925464794,0.00981314608362189,0.5037817353184296,-0.9920567543624563,0.014351956337611936,0.5594047241640768,-1.1049913268309997,0.0033436674175280454,-0.4953210053039378,1.005629278654941,0.0033458019359374736,-0.4956257074648169,1.0004948010689247,0.10233263786809908,0.05405409167883679,0.06992297894717003,0.1940996449976075,0.6409368554037442,-1.000290230659382,0.03210816745720651,0.060649365256136845,0.0520687628543115,0.032180163004516434,0.05523518056332111,0.00022017692772990927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.10833333333333334,1.0,0.0,1.0,1.0,0.00119322428077092,-0.0008532244963152554,0.587834603017308,0.9999929905650649,-0.002568065179442444,-0.002002167863974788,-0.001848092694925107,0.0163737668959055,-0.008386059688881854,0.003932505798818092,-0.047956079364297834,-0.03591802921841699,-0.03696135365263765,0.010666725205983085,0.5042351545536684,-0.9914751272457132,0.016002565769399818,0.5647668431487436,-1.1132743956627884,0.0036117191610659035,-0.49481222178191986,1.006061691280487,0.0036144834842703824,-0.4951625170502127,1.0004954172466394,0.10252623934621681,0.05469834742873214,0.06969799551431288,0.20203571880896154,0.6457786187422099,-0.987304067571193,0.032224702926069965,0.061394757436232794,0.051733751018905316,0.03230384755532744,0.05586663310053641,-4.846246056455783e-05,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.11666666666666667,1.0,0.0,1.0,1.0,0.0013302597830770985,-0.00092368514955786,0.5878682266536434,0.9999918495059021,-0.002768027770209236,-0.0021517801436370236,-0.0020022528272753714,0.016593302614809305,-0.008440238550746899,0.003910847482445224,-0.048042232287468456,-0.035883855360757534,-0.03702807206736596,0.01152191673939217,0.5046933744422418,-0.9908951211038844,0.017719218317761295,0.5701677011431137,-1.1214463946238529,0.0038807457996292115,-0.49429775934666725,1.0064915078385894,0.003884199395192931,-0.49469459691314127,1.0004939933612487,0.1027197066512723,0.0552216862314725,0.06952752768976334,0.20994556553466867,0.6502453314259093,-0.9736412159350616,0.032341990387933534,0.06202692794649245,0.05144054071734683,0.032428260210951666,0.05638488426103594,-0.00027470226224401983,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.125,1.0,0.0,1.0,1.0,0.0014689297737463926,-0.0009946346148862223,0.5879017529753686,0.9999906209754249,-0.0029683485514353865,-0.0023012500675571074,-0.0021566912646616447,0.01677835784634565,-0.008494534286339549,0.0038900385744822293,-0.04812853882252131,-0.03584990938288517,-0.037094521626436304,0.012378720316837623,0.5051555159908596,-0.9903163351175505,0.019501658528310963,0.5756042653391754,-1.129501749261706,0.004150752334198129,-0.4937784396494783,1.006919033625776,0.0041549544877862435,-0.4942227689791954,1.000490838875602,0.10291314098601817,0.05565142399236889,0.06940023742881163,0.21782012098180226,0.6543555032664194,-0.9593156319299467,0.03245978525702019,0.06257176828517452,0.051179983694003006,0.03255315997120426,0.05681575423602481,-0.00046784349487793975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.13333333333333333,1.0,0.0,1.0,1.0,0.0016089833538080415,-0.001066073729041845,0.5879351884870061,0.9999893046894727,-0.0031690280411811,-0.00245057917437198,-0.0023114071918219426,0.01693675267218497,-0.008548909028556975,0.003869918477737966,-0.04821497539790678,-0.03581645862139325,-0.037160789923718844,0.013237135755825807,0.505620898175448,-0.9897384504800709,0.021349553667458,0.581073626197554,-1.137434988489352,0.004421742220579548,-0.49325489654191434,1.0073445075668228,0.004426752061379669,-0.4937476676758742,1.0004861959696674,0.10310653225421185,0.0560086324213116,0.06930741900476489,0.22564995769426346,0.6581210495191425,-0.9443385757093647,0.032577922869668416,0.06304928592908432,0.05094500908908284,0.03267838486487616,0.0571792257495185,-0.0006350469788563018,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.14166666666666666,1.0,0.0,1.0,1.0,0.0017502265356308805,-0.001138003051560996,0.587968538596137,0.9999879003594492,-0.003370066654894846,-0.002599770018773208,-0.0024664000390384284,0.0170745665334247,-0.008603324145869501,0.0038503640329586126,-0.048301515496255755,-0.03578372668479228,-0.03722692798182473,0.014097162521074487,0.5060889931978815,-0.989161211467471,0.023262491156548687,0.5865729494978278,-1.1452407255235288,0.004693717715359269,-0.4927276182173269,1.007768117110594,0.0046995942355341795,-0.4932697818833701,1.0004802547592877,0.10329982588351043,0.056309670410421564,0.06924236004013595,0.23342536897119134,0.6615487744388315,-0.9287193304317043,0.03269626377367061,0.06347504821988426,0.050730116530148806,0.032803797562853246,0.05749085454813452,-0.000781874906632396,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.15,1.0,0.0,1.0,1.0,0.0018925097438403469,-0.001210422866259622,0.5880018078821478,0.9999864076921723,-0.0035714646944585457,-0.002748826003655941,-0.002621669408081676,0.017196560091369356,-0.008657740592493697,0.0038312800327980653,-0.04838812998814371,-0.035751899655648886,-0.037292977127503055,0.01495879952055098,0.5065593926822883,-0.9885844111460687,0.02523997648364452,0.5920994391048678,-1.152913643996547,0.004966679950140725,-0.49219697907158294,1.008190009508992,0.004973482020760556,-0.4927894867667386,1.0004731647212235,0.103492951447032,0.05656733282298099,0.06919985172005205,0.24113641525806412,0.664641504215675,-0.9124657492358379,0.032814670564245974,0.06386126136287085,0.05053099521736382,0.03292926246892375,0.05776283475528721,-0.0009126871396647473,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.15833333333333333,1.0,0.0,1.0,1.0,0.0020357183351674994,-0.0012833331819099702,0.5880350002936047,0.9999848263897056,-0.0037732223374611715,-0.0028977512353983693,-0.0027772150652584093,0.01730649250749131,-0.00871211906765576,0.003812591832497953,-0.048474787129648894,-0.03572113091726908,-0.03735898045466207,0.015822045045191687,0.5070317820782645,-0.9880078806054702,0.027281431410849755,0.5976503079014224,-1.1604484880107928,0.0052406288914300355,-0.49166326386127907,1.0086103003642168,0.0052484152766829086,-0.492307067970782,1.00046504330696,0.10368583494963755,0.05679171228668345,0.06917581740496725,0.24877295529248902,0.6673989501942734,-0.8955846734020545,0.03293299812959231,0.06421757917257853,0.05034423627097606,0.03305463615314329,0.058004802203511785,-0.0010309358195392804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.16666666666666666,1.0,0.0,1.0,1.0,0.002179765387411565,-0.0013567337321408264,0.5880681192913886,0.9999831561492049,-0.0039753396259268005,-0.0030465503965222294,-0.0029330369629693913,0.017407359728793,-0.008766420045531792,0.00379423969415917,-0.048561452404583275,-0.03569154473454689,-0.03742498764020394,0.016686896769711607,0.5075059212203997,-0.9874314808559859,0.029386192405186005,0.6032227549414391,-1.1678400552199146,0.0055155632523005965,-0.4911266860853733,1.0090290801135082,0.005524392623312944,-0.49182274006334675,1.0004559824575645,0.10387840393194236,0.05699084536490373,0.06916703235205546,0.2563246714339335,0.6698183668193902,-0.878082254529251,0.03305108950834029,0.06455170936676802,0.050167115783446015,0.03317976335033819,0.058224438729518324,-0.0011393855114461005,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.175,1.0,0.0,1.0,1.0,0.0023245861907958574,-0.0014306239744316558,0.588101167950864,0.9999813966627997,-0.004177816454066323,-0.003195228630993699,-0.0030891352729743083,0.017501573040431376,-0.008820603713340685,0.003776174486053133,-0.04864808827456104,-0.035663238829032,-0.037491056845118824,0.017553351777390726,0.5079816295010129,-0.9868550967329359,0.03155350926808198,0.6088139473484122,-1.175083192252947,0.005791480383235707,-0.4905874020384996,1.0094464189606076,0.005801411332521878,-0.49133666065862336,1.0004460535484359,0.10407058930477019,0.05717119628883882,0.06917091288293209,0.26378109323091614,0.6718950540915891,-0.8599642049491552,0.03316877406087441,0.06486986737654243,0.049997431695079086,0.03330447524096307,0.05842792540457831,-0.0012402778015285776,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.18333333333333332,1.0,0.0,1.0,1.0,0.0024701340129163734,-0.0015050030879902373,0.5881341490331824,0.9999795476175262,-0.0043806525547571,-0.003343791438471754,-0.0032455104238786328,0.017591092400892544,-0.008874629846364841,0.003758354429455102,-0.04873465386412024,-0.03563628617879202,-0.037557255301528904,0.018421406591457776,0.5084587744918804,-0.986278632307937,0.03378254395903461,0.6144210058429656,-1.1821727919690672,0.00606837615331517,-0.4900455216290976,1.0098623706417595,0.006079467210662329,-0.4908489413066038,1.0004353111608724,0.10426232562478974,0.05733801802693561,0.06918535831329065,0.2711316210001058,0.6736227425767116,-0.8412359943033332,0.033285866578690766,0.06517711494066991,0.049833381657697906,0.03342858864850251,0.05862028114851814,-0.0013354540935228698,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.19166666666666665,1.0,0.0,1.0,1.0,0.0026163768124753753,-0.0015798699702802212,0.588167065033389,0.9999776086953164,-0.004583847484524203,-0.0034922445747109904,-0.003402163139380234,0.017677525507461222,-0.008928457642240775,0.003740742655552903,-0.04882110459595409,-0.03561073623647099,-0.037623659279939964,0.019291057204470555,0.5089372631347951,-0.9857020074277144,0.036072369618083744,0.6200409930580241,-1.1891037921580025,0.006346244826213886,-0.48950111678948843,1.0102769753215692,0.006358554476663587,-0.4903596559728147,1.0004237959802105,0.10445355058192725,0.057495620546377246,0.06920863293651935,0.27836555020482295,0.6749938899166996,-0.8219030056197951,0.033402166768107464,0.06547761144183872,0.04967347212681439,0.03355190559626679,0.058805614360268876,-0.001426446791032987,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2,1.0,0.0,1.0,1.0,0.0027632946554552516,-0.0016552232319709866,0.5881999182111676,0.9999755795730567,-0.004787400606842858,-0.0036405939560498137,-0.003559094475576731,0.017762200856710673,-0.008982045531320173,0.003723305391611159,-0.048907391786985804,-0.03558661572160637,-0.037690353743382574,0.020162299101156564,0.50941703483432,-0.9851251550923283,0.038421969795781656,0.6256709040082439,-1.1958711753960638,0.006625078932783628,-0.48895422810506695,1.0106902618438731,0.006638665637266775,-0.48986884773393263,1.0004115370476885,0.10464420406166915,0.057647568738432575,0.06923927842817701,0.28547209698066806,0.6759999108347703,-0.8019706608560906,0.03351745888586692,0.06577479903719818,0.04951645126921811,0.03367421300471778,0.0589873084894843,-0.0015145464820820465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.20833333333333334,1.0,0.0,1.0,1.0,0.0029108776466657414,-0.0017310611900991507,0.5882327106086801,0.9999734599227219,-0.0049913110736208985,-0.0037888455664970076,-0.0037163058564267685,0.017846221046654072,-0.0090353509756347,0.003706010638998144,-0.04899346221447569,-0.03556392911161603,-0.037757431827939454,0.02103512727216504,0.5098980559471024,-0.9845480194539115,0.04083023790109488,0.6313076582386036,-1.2024699698389374,0.006904869140978335,-0.48840487013886846,1.0111022495093895,0.00691979136007555,-0.48937653416465665,1.0003985535388424,0.10483422696461818,0.05779682695738364,0.06927604938618215,0.2924404249503389,0.6766313573374028,-0.7814445233648382,0.033631511445842824,0.06607153747567263,0.04936126006179986,0.03379528245103082,0.05916815739441583,-0.0016008508539577804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.21666666666666667,1.0,0.0,1.0,1.0,0.0030591242344270774,-0.0018073818592562064,0.5882654440589263,0.9999712494115939,-0.005195577804755966,-0.003937005366386781,-0.0038737991068279326,0.017930501048479472,-0.009088330265936603,0.0036888272387023044,-0.04907925766093773,-0.035542658930804605,-0.037824994216194376,0.021909536217233534,0.5103803152836097,-0.9839705542692253,0.043295976878287304,0.6369480932972006,-1.2088952507854778,0.007185604123547675,-0.48785303581380574,1.0115129495115698,0.007201920344783955,-0.48888271177735904,1.0003848562001225,0.10502355988383914,0.05794586298651483,0.06931786649838845,0.2992596733660831,0.6768780618079218,-0.7603303828603991,0.033744076973321845,0.06637020062343901,0.04920699732067213,0.033914869969860935,0.05935046249559095,-0.0016862996620403692,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.225,1.0,0.0,1.0,1.0,0.003208039780118224,-0.0018841829406438775,0.5882981201872701,0.9999689477025732,-0.005400199465699376,-0.004085079201944165,-0.004031576482957887,0.018015795033868923,-0.009140938324149568,0.0036717242452206523,-0.04916471444687817,-0.03552276591754787,-0.03789314843797997,0.022785519936895694,0.5108638203302109,-0.9833927216789383,0.04581789912386293,0.6425889592687356,-1.2151421428866107,0.007467270423867032,-0.4872987001284778,1.0119223661314007,0.0074850391929065655,-0.48838735978973014,1.000370448544475,0.10521214170205247,0.05809672113953779,0.06936378317249137,0.30591898656068556,0.676729252654289,-0.7386343270627682,0.03385489180820201,0.06667274382026744,0.04905289541877966,0.03403271589715809,0.0595361008421158,-0.001771699024621931,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.23333333333333334,1.0,0.0,1.0,1.0,0.003357635310117267,-0.0019614618088695922,0.5883307404082031,0.9999665544545896,-0.005605174442997172,-0.004233072715399123,-0.004189640699626578,0.01810271448519655,-0.009193128517304822,0.003654670549213772,-0.04924976296061529,-0.0355041891342544,-0.03796200811806014,0.02366307191226774,0.5113485939692687,-0.9828144912163504,0.04839462665429873,0.6482269141747721,-1.2212058229031906,0.0077498523203510415,-0.4867418234168013,1.0123304977685494,0.007769132276403257,-0.48789044342999044,1.0003553278830455,0.10539990815303539,0.05825107187195977,0.06941296247738649,0.31240754465015164,0.6761736498747517,-0.7163628031287139,0.0339636759673174,0.06698074900620354,0.04889830422678543,0.03414854476802164,0.05972657103020085,-0.0018577375336059632,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.24166666666666667,1.0,0.0,1.0,1.0,0.003507926387316,-0.0020392154963883974,0.5883633059189854,0.9999640693231203,-0.0058105008178185955,-0.004380991255529474,-0.00434799495444829,0.018191739670552997,-0.009244852488260546,0.0036376347028540344,-0.04933432719500271,-0.03548684607325345,-0.038031692183873186,0.024542185072779617,0.5118346715280769,-0.9822358389709819,0.05102469153469879,0.6538585200999815,-1.227081522938756,0.008033331689988989,-0.48618235431170775,1.0127373378685138,0.008054181605706926,-0.4873919169392268,1.0003394862522483,0.1055867903824944,0.05841024352944091,0.0694646620008621,0.31871459540452535,0.6751995461720917,-0.6935226711881137,0.03407013307950539,0.06729545292039507,0.04874268139640314,0.03426206528333724,0.05992302227516899,-0.0019449960758910478,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.25,1.0,0.0,1.0,1.0,0.003658932054432981,-0.002117440675534587,0.5883958176914674,0.99996149196082,-0.006016176337525676,-0.004528839788713638,-0.004506642948689166,0.018283226081644538,-0.009296060008120288,0.0036205849132167024,-0.04941832430136197,-0.0354706328023691,-0.03810232404343188,0.02542285175197598,0.5123220980280927,-0.9816567468496694,0.053706536577707485,0.6594802399443069,-1.2327645340896591,0.008317687871676131,-0.4856202325347947,1.0131428757918228,0.00834016669779221,-0.48689172639207096,1.0003229112817806,0.10577271353921239,0.05857524054573737,0.06951822480178338,0.3248294871810639,0.6737948779307423,-0.670121251699074,0.0341739504092051,0.06761776244688988,0.04858558753785491,0.03437297036082053,0.06012627070975496,-0.002033952822766416,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2583333333333333,1.0,0.0,1.0,1.0,0.0038106738129391423,-0.0021961336381269773,0.5884282764631652,0.9999588220182684,-0.006222198385381537,-0.004676622810737585,-0.004665588904681456,0.018377407069709677,-0.009346698855092669,0.0036034891770732893,-0.04950166417126225,-0.03545542418630276,-0.03817403074206943,0.02630506363176649,0.5128109255371726,-0.9810772018909522,0.056438516321049854,0.6650884347321605,-1.2382502104670738,0.008602897530142407,-0.4850553916042596,1.0135470976608114,0.008627064445053935,-0.48638981242739754,1.0003055870385356,0.10595759542610064,0.05874675142090613,0.06957307505821353,0.33074170279478565,0.6719472893718903,-0.646166367875658,0.034274798984325616,0.06794826026051637,0.04842668517269555,0.034480937286395855,0.06033680605795344,-0.002124984513698358,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.26666666666666666,1.0,0.0,1.0,1.0,0.003963174610403695,-0.0022752902726753807,0.5884606827284693,0.9999560591448378,-0.006428563948541347,-0.004824344259737587,-0.0048248375797308035,0.01847439364316422,-0.009396714724473584,0.003586315535517316,-0.049584249057288206,-0.035441074213943775,-0.03824694210630155,0.027188811675744325,0.5133012105517745,-0.9804971955986992,0.05921889829095391,0.6706793614338384,-1.2435339735542534,0.008888934521414892,-0.48448776153045275,1.0139499872113678,0.008914848985898808,-0.48588611295777173,1.000287494873219,0.10614134523912071,0.058925149073703054,0.06962871733031673,0.33644089418447726,0.6696441924478647,-0.6216663841053949,0.034372333844441966,0.06828720323728166,0.04826574058812927,0.03458562798234879,0.06055479114438156,-0.002218364913311177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.275,1.0,0.0,1.0,1.0,0.004116457816133936,-0.0023549060392630498,0.5884930367307243,0.9999532029896825,-0.006635269584517934,-0.004972007430773664,-0.004984394276475054,0.018574172188328183,-0.009446051174423925,0.0035690324320109515,-0.049665973244044405,-0.03542741645611901,-0.03832118988282988,0.0280740860524185,0.5137930113550676,-0.9799167232687802,0.06204586455745781,0.6762491712729582,-1.2486113168688304,0.009175769760883107,-0.4839172715503049,1.0143515266706136,0.009203491578093081,-0.4853805659083245,1.0002686142899804,0.10632386242222347,0.059110485613831365,0.06968473859479074,0.34191691771577537,0.6668728244542588,-0.5966302410034929,0.0344661944251734,0.06863451557971079,0.04810262789701536,0.034686689407799585,0.060780056183060704,-0.0023142611383253353,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2833333333333333,1.0,0.0,1.0,1.0,0.004270546170603256,-0.0024349759422294852,0.5885253384558142,0.9999502532028519,-0.006842311386361382,-0.005119614892619081,-0.005144264849686092,0.018676600723459096,-0.009494649612154933,0.0035516091595657966,-0.04974672278072455,-0.03541426467381046,-0.03839690688081885,0.02896087604944805,0.514286385312005,-0.979335783288786,0.06491751358621684,0.6817939085080761,-1.2534778109043117,0.009463371095167782,-0.4833438529374576,1.014751697676318,0.009492960476028801,-0.4848731120213874,1.000248923854247,0.10650503566586964,0.05930248317209674,0.06974081237612229,0.3471598699488601,0.6636203048962086,-0.5710674875538491,0.03455600509418729,0.06898977822426655,0.04793733474520945,0.03478375410687032,0.06101208940501035,-0.002412728415124299,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2916666666666667,1.0,0.0,1.0,1.0,0.004425460698708697,-0.0025154945008300936,0.588557587627789,0.9999472094365197,-0.00704968494684052,-0.005267168407427145,-0.005304455709539274,0.01878140418452666,-0.009542449325020413,0.0035340163849248447,-0.04982637528649,-0.0354014135923318,-0.03847422612551866,0.029849169980182996,0.5147813860746026,-0.9787543763958448,0.06783186238993881,0.6873095096878951,-1.2581291083280612,0.009751703179119562,-0.4827674419132338,1.0151504822497004,0.009783220813207587,-0.48436369775157434,1.0002284021497283,0.10668474207594723,0.0595005221205569,0.06979670443093333,0.35216012368457367,0.6598736927992488,-0.5449883106342179,0.03464137585338294,0.0693522158137505,0.04776996920333065,0.03487644091930805,0.06125002529774548,-0.0025137037290079434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3,1.0,0.0,1.0,1.0,0.004581219580656749,-0.002596455718102612,0.5885897837070033,0.9999440713463329,-0.007257385321960853,-0.005414668853989272,-0.0054649738214077835,0.018888169157513825,-0.009589387560802597,0.003516226738727796,-0.049904799839469056,-0.035388639852640666,-0.03855328003130086,0.03073895508404717,0.5152780606806809,-0.9781725048816038,0.07078684898095973,0.6927918033880636,-1.262560949414882,0.01004072735939083,-0.48218798267389507,1.0155478638297069,0.010074234491350602,-0.48385227826642496,1.0002070287920968,0.10686284653926605,0.059703627789899905,0.06985227953384632,0.35690836409012383,0.6556200453832584,-0.5184035621007199,0.03472190322102681,0.0697206823048524,0.04760076745264019,0.0349643558667467,0.0614926315171227,-0.002616998753315336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.30833333333333335,1.0,0.0,1.0,1.0,0.00473783697742895,-0.0026778530482245056,0.5886219258911652,0.9999408385928673,-0.007465406994198323,-0.005562116155338126,-0.005625826702272259,0.01899633841027979,-0.009635399661124934,0.003498215460890315,-0.04998185695963741,-0.03537570314721146,-0.03863419960209109,0.031630217422504096,0.5157764465377676,-0.9775901717369474,0.07378033512477421,0.6982365104442827,-1.2667691676964066,0.010330401566136675,-0.48160543054148625,1.015943828373911,0.010365960077653365,-0.4833388205596223,1.0001847855038397,0.10703920130985645,0.05991045662359973,0.06990750897626574,0.36139562469528513,0.650846478802527,-0.4913247835181789,0.0347971713059652,0.07009364612425073,0.04743010192556962,0.03504709322687958,0.06173829537245101,-0.0027222923923231335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.31666666666666665,1.0,0.0,1.0,1.0,0.004895321810507093,-0.0027596793626991976,0.5886540131196363,0.9999375108431843,-0.007673743835870152,-0.005709509211471192,-0.0057870224138682844,0.019105205530487012,-0.009680419251450481,0.0034799610908541855,-0.05005739869495445,-0.03536234754338734,-0.038717113666765696,0.03252294177254478,0.5162765682910743,-0.9770073797319994,0.07681010939254782,0.703639244701439,-1.2707496958068516,0.01062068021449025,-0.4810197552384909,1.0163383655284663,0.010658352711798595,-0.4828233066768841,1.0001616572522247,0.10721364583839876,0.06011928258104593,0.06996247844063941,0.36561332304005656,0.6455402314730252,-0.4637642285474408,0.03486675308441999,0.07046917566802535,0.047258489598807074,0.03512423680567027,0.06198501066737472,-0.002829123235255082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.325,1.0,0.0,1.0,1.0,0.005053676497915234,-0.002841926915761519,0.5886860440812638,0.9999340877724774,-0.007882389073101376,-0.005856845837972386,-0.005948569552724196,0.01921390994069243,-0.00972437849049671,0.003461446191580478,-0.05013126881901873,-0.03534830299318176,-0.03880214815672686,0.03341711151981074,0.516778434580785,-0.9764241304296034,0.07987389050877515,0.7089955143021665,-1.2744985715055306,0.010911514117543675,-0.4804309442803525,1.0167314698672245,0.010951364024414536,-0.4823057370484994,1.0001376334499188,0.10738600686427693,0.060327984506294285,0.07001739594608258,0.3695532957470532,0.6396887303585275,-0.43573488294309737,0.03493021188751628,0.07084492584748636,0.047086600163241954,0.035195361415570475,0.062230365586493086,-0.002936882189747969,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3333333333333333,1.0,0.0,1.0,1.0,0.005212895650774223,-0.002924587309442461,0.5887180172259645,0.9999305690657952,-0.008091335250878014,-0.006004122711298013,-0.006110477237271087,0.019321432534073153,-0.009767208381093823,0.003442658095982733,-0.050203303147084224,-0.03533328702438082,-0.03888942543223362,0.03431270855361606,0.5172820346995125,-0.975840423132898,0.08296933098833204,0.7143007235407478,-1.2780119438559032,0.011202850412615522,-0.4798390064743661,1.0171231421978537,0.01124494206872477,-0.4817861339171092,1.000112709215729,0.10755609878598721,0.060534035103518846,0.07007259958401013,0.3732078327861482,0.6332796604524993,-0.4072504820691014,0.034987103105061125,0.07121812631646796,0.04691526381165545,0.03526003456538505,0.06247153224623547,-0.0030448055405774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3416666666666667,1.0,0.0,1.0,1.0,0.00537296473648162,-0.0030076514587788297,0.5887499307802182,0.9999269544198254,-0.008300574199703085,-0.00615133532146133,-0.006272755092231776,0.019426592151452128,-0.009808839143611454,0.0034235896637127175,-0.050273329975608065,-0.03531700660352903,-0.03897906366312367,0.03520971316624386,0.5177873351658436,-0.9752562537698699,0.08609402105521095,0.7195501753097081,-1.2812860795400156,0.011494632502628027,-0.47924397550841136,1.017513390930752,0.011539031267170954,-0.48126454484439546,1.0000868866909092,0.1077237243217595,0.06073449209808901,0.07012856478183283,0.37656971069471773,0.6263010375733136,-0.378325525802925,0.03503697610822705,0.07158557195459436,0.046745478402190344,0.035317818363807436,0.06270525847199226,-0.003151968668522187,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.35,1.0,0.0,1.0,1.0,0.0055338587163888025,-0.0030911095576944174,0.5887817827665623,0.9999232435447213,-0.008510097004389868,-0.006298477932803117,-0.006435413230517396,0.019528043100877718,-0.009849200651985503,0.003404240035350212,-0.050341170648609115,-0.03529916015717992,-0.03907117626872227,0.03610810395897872,0.5182942762344807,-0.9746716137198674,0.089245492833244,0.7247390741669697,-1.284317369285952,0.011786800014419306,-0.4786459136084562,1.0179022335045569,0.011833572374788227,-0.48074104627590936,1.0000601764045869,0.10788867546703731,0.06092599210953065,0.07018591084809511,0.3796322245148695,0.6187412844752616,-0.3489752906662025,0.03507937639018084,0.07194361613076516,0.046578415763001146,0.03536827163576752,0.06292786230808645,-0.0032572806459274517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.35833333333333334,1.0,0.0,1.0,1.0,0.005695540667441244,-0.0031749510461127547,0.5888135710271087,0.9999194361659537,-0.008719893975535955,-0.006445543553468706,-0.006598462232878487,0.01962427390231083,-0.009888222931164054,0.003384615370416244,-0.050406640251873025,-0.03527943973373399,-0.039165871420417914,0.03700785775736115,0.5188027683676691,-0.9740864885890683,0.09242122479712545,0.7298625300509625,-1.2871023343844523,0.012079288775797708,-0.47804491523956527,1.0182896978601355,0.012128502461100412,-0.4802157471392607,1.0000325986801437,0.10805073475027363,0.06110474771121144,0.07024540656467515,0.3823892182097466,0.6105893101709148,-0.3192158389979527,0.0351138479200486,0.0722881672241682,0.04641542691763423,0.035410952247022544,0.06313522972354546,-0.0033594799181724255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.36666666666666664,1.0,0.0,1.0,1.0,0.0058579603986958564,-0.0032591645788878046,0.5888452932510286,0.9999155320261653,-0.008929954624220889,-0.0065925239141312346,-0.006761913125568747,0.019713607422165935,-0.009925836713516574,0.0033647295549555107,-0.05046954843376818,-0.03525753328431722,-0.03926325160912651,0.037908949538149946,0.5193126886963342,-0.9735008569437895,0.09561864647007311,0.7349155626698183,-1.2896376332692512,0.012372030813086783,-0.47744111082138674,1.0186758239531841,0.012423754912238603,-0.4796887924471836,1.0000041850726173,0.10820967678239563,0.061266548103608987,0.07030797460372495,0.3848351133238931,0.601834592251902,-0.28906402496537087,0.03513993570150628,0.07261468883387856,0.0462580460142048,0.03544541962769505,0.06332281592919764,-0.0034571312690179212,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.375,1.0,0.0,1.0,1.0,0.006021053074927459,-0.003343737997156125,0.5888769470058755,0.9999115308870067,-0.009140267640459948,-0.006739409456401795,-0.006925777356287762,0.01979420254344016,-0.009961974050318586,0.0033446048637218286,-0.05052970034887415,-0.0352331270371843,-0.039363413278452455,0.03881135237040108,0.5198238775027293,-0.9729146890123396,0.09883514335252366,0.7398931065884942,-1.2919200681338752,0.012664954370822813,-0.4768346704256673,1.0190606652937055,0.01271925945489533,-0.47916036687377406,0.9999749798256601,0.10836527008878091,0.06140676377605514,0.07037469456405487,0.38696493565752943,0.592467261891334,-0.25853749719593644,0.03515718852307819,0.07291820405760929,0.04610799275702515,0.03547123748224981,0.0634856506700654,-0.0035486242515614386,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3833333333333333,1.0,0.0,1.0,1.0,0.006184737860668358,-0.0034286583027204743,0.5889085297725299,0.9999074325309295,-0.009350820875924317,-0.006886189331253451,-0.007090066768668858,0.0198640574967026,-0.009996568973006017,0.0033242725618358275,-0.05058689771794433,-0.035205907936919266,-0.03946644652270714,0.03971503737296296,0.5203361347592684,-0.9723279453677219,0.10206806206436526,0.7447900170346738,-1.2939465915558501,0.012957983955138086,-0.4762258074204266,1.0194442904991345,0.013014942203609433,-0.4786306982693492,0.9999450413350913,0.10851727920623638,0.06152035547714707,0.07044680443606177,0.38877433973294295,0.5824781911055554,-0.22765469780345882,0.0351651618825238,0.07319330416857395,0.04596717315051624,0.035487976668208826,0.06361834780941544,-0.003632173259440208,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.39166666666666666,1.0,0.0,1.0,1.0,0.006348916598983034,-0.0035139116360711313,0.5889400389834734,0.9999032367629161,-0.009561601331404875,-0.007032851407660329,-0.007254793575573093,0.019921014955287204,-0.010029558197402413,0.0033037734304953554,-0.05064093999509432,-0.03517556611652722,-0.03957243484751662,0.04061997369050502,0.5208492167606817,-0.9717405756050719,0.10531471568140605,0.7496010764402534,-1.2957143130972661,0.01325104040219821,-0.47561478202285773,1.0198267848462141,0.01331072573269881,-0.47810006107695047,0.9999144436046694,0.10866546702031812,0.06160188775411024,0.0705257003250237,0.3902596308418027,0.5718590817492952,-0.19643485757805834,0.03516342106365682,0.0734341619623935,0.04583767837683883,0.03549521822166248,0.06371511946206998,-0.0037058193935912698,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4,1.0,0.0,1.0,1.0,0.006513472540047442,-0.0035994832586344052,0.5889714720640045,0.9998989434121182,-0.00977259514945227,-0.007179382291512863,-0.007419970331438678,0.019962768973599065,-0.010060881862680974,0.0032831582014118507,-0.05069162563039232,-0.03514179736805776,-0.039681454989024756,0.04152612848996826,0.5213628328885036,-0.9711525170289715,0.10857238924506198,0.7543210017304954,-1.2972205058488178,0.0135440409728657,-0.47500190472105336,1.0202082518054152,0.013606529173970474,-0.477568779611648,0.9998832776785315,0.10880959731209588,0.06164554725675009,0.07061293428574533,0.3914177844749281,0.5606025556187721,-0.16489798711385006,0.035151544339148896,0.07363454998170815,0.04572178165170193,0.03549255650354532,0.06376979487205614,-0.003767434260446567,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4083333333333333,1.0,0.0,1.0,1.0,0.006678269135154198,-0.0036853575398100606,0.5890028264759362,0.9998945523333858,-0.009983787612570003,-0.007325767354724206,-0.007585609903915984,0.019986873820787822,-0.010090484295449896,0.003262487885284454,-0.05073875341340752,-0.03510430557536144,-0.039793576786249896,0.04243346697903995,0.5218766425482942,-0.9705636933669761,0.11183834542265485,0.758944452367233,-1.298462612882497,0.013836899474517357,-0.4743875395231626,1.0205888145404092,0.013902268341091232,-0.4770372311624162,0.999851653033662,0.1089494374764674,0.061645165930019896,0.07071021014765089,0.39224646295217713,0.5487022449358214,-0.13306486365261438,0.035129126268600326,0.0737878637590017,0.045621932919206465,0.0354796024359794,0.06377584416512261,-0.0038147258202081424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4166666666666667,1.0,0.0,1.0,1.0,0.006843148912089176,-0.003771517949317856,0.589034099763224,0.9998900634086628,-0.010195163147270501,-0.007471990774285781,-0.0077517254449948215,0.019990754733606474,-0.0101183147880268,0.003241833980056729,-0.050782123880818764,-0.035062805071406244,-0.03990886309972036,0.043341952447909386,0.5223902523206706,-0.9699740135265107,0.11510983029426493,0.7634660391460925,-1.2994382535763613,0.014129526410675705,-0.47377210699173666,1.0209686173540686,0.014197855881236798,-0.47650584887556263,0.9998196989148613,0.10908476136874137,0.061594249143153146,0.07081937724096932,0.39274402908802686,0.5361528823976425,-0.1009570134400839,0.03509578105739944,0.07388715014300273,0.04554075127392032,0.035455986794404,0.06372640703262489,-0.0038452463773364087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.425,1.0,0.0,1.0,1.0,0.007007932447903977,-0.0038579470553201703,0.5890652895988996,0.9998854765482296,-0.010406705334227509,-0.00761803558087417,-0.007918330361799862,0.01997172058147662,-0.01014432837888367,0.0032212785462922304,-0.05082154076902723,-0.0350170228819328,-0.04002736976814105,0.04425154633518564,0.5229032133673468,-0.96938337041296,0.11838407924078863,0.767880333740527,-1.300145229773165,0.014421829158807348,-0.4731560870207792,1.0213478270616412,0.014493201454331299,-0.4759751243785391,0.9997875655940397,0.10921535223026468,0.061486008722200225,0.07094242196853617,0.3929095567491672,0.5229503898894161,-0.06859668940907504,0.03505114593798358,0.07392514069511025,0.045481015025172766,0.03542136351740055,0.06361432632578934,-0.003856402777973056,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.43333333333333335,1.0,0.0,1.0,1.0,0.007172417454920517,-0.003944626528722351,0.5890963938326176,0.9998807916917745,-0.010618396924673104,-0.007763883716449288,-0.008085438287195452,0.01992697840467403,-0.01016848662223122,0.0032009141381432243,-0.05085681249063814,-0.03496670081755307,-0.04014914559388548,0.0451622083184138,0.5234150191327073,-0.9687916398270351,0.12165832290675105,0.7721818789775827,-1.3005815317331793,0.014713712176308765,-0.4725400213134848,1.0217266342711548,0.01478821193986014,-0.47544561010346614,0.9997554255352284,0.1093410056398203,0.06131340076741765,0.07108145720476688,0.39274283818316297,0.5090919648830594,-0.036006844034042196,0.03499488453229952,0.0738942900583317,0.04544564935101025,0.03537541299332949,0.0634321864594567,-0.0038454688499967027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.44166666666666665,1.0,0.0,1.0,1.0,0.007336377995348772,-0.004031537153974873,0.5891274105380525,0.9998760088092814,-0.010830219863093503,-0.007909516100130813,-0.008253063050302375,0.0198536497531886,-0.0101907583330536,0.0031808435801073207,-0.05088775361228293,-0.03491159737755462,-0.040274232347174116,0.046073896429182644,0.5239251033801371,-0.9681986794595472,0.12492979321050801,0.7763651998219113,-1.300745343840399,0.015005077234345673,-0.471924515519807,1.0221052545508247,0.01508279167088679,-0.4749179212708815,0.9997234744465398,0.1094615324339375,0.061069168050154055,0.07123870954307776,0.39224438802199446,0.49457616348266953,-0.0032110972359111756,0.034926690151803434,0.07378681911580975,0.04543771152420106,0.03531784528040087,0.06317235643954366,-0.003809600087749665,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.45,1.0,0.0,1.0,1.0,0.007499563839155234,-0.004118658846615543,0.5891583380593355,0.9998711279017184,-0.011042155316181043,-0.00805491270148734,-0.008421218646986858,0.01974878872005031,-0.01021112029345368,0.0031611795826879383,-0.05091418631007319,-0.034851489430604114,-0.040402664778314244,0.046986567192312756,0.5244328386002098,-0.9676043280013171,0.1281957293737843,0.7804248150356272,-1.3006350500204444,0.015295823678838822,-0.471310240994888,1.0224839294632249,0.015376842694533488,-0.4743927374961404,0.9996919322004326,0.10957676153682566,0.06074588669412906,0.07141650445623648,0.3914154438907491,0.4794029790295462,0.029766300743210294,0.034846288989282166,0.07359476266792786,0.045460373727927994,0.03524840321522265,0.06282703724377892,-0.0037458505491017036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4583333333333333,1.0,0.0,1.0,1.0,0.00766169997880216,-0.004205970677693146,0.5891891750556829,0.9998661490015239,-0.011254183707895627,-0.00820005262023604,-0.008589919210339397,0.019609401529296893,-0.01022955790599276,0.003142044191918908,-0.0509359417782968,-0.03478617364041392,-0.04053447062718002,0.04790017578812974,0.5249375348250392,-0.9670084043852766,0.1314533839420205,0.7843552494724038,-1.3002492388280122,0.015585848717500376,-0.4706979361420082,1.0228629274462901,0.015670265057807168,-0.4738708039834852,0.9996610436040547,0.10968654264008199,0.0603360167598499,0.0716172494746048,0.39025796357965603,0.4635739151514717,0.0629005115231962,0.03475344315654376,0.07331002126757635,0.045516903523572516,0.03516686536396689,0.062388313199338574,-0.0036511918940473898,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4666666666666667,1.0,0.0,1.0,1.0,0.007822486313174488,-0.004293450905111966,0.5892199205433367,0.9998610721728829,-0.01146628476038641,-0.008344914171222151,-0.00875917898111694,0.019432467505814215,-0.010246065779944856,0.0031235680705986512,-0.05095286156701495,-0.034715467608194335,-0.04066967061917975,0.04881467623631412,0.5254384388795407,-0.9664107071767404,0.13470002876677856,0.7881510469548184,-1.2995867081617245,0.015875047731447885,-0.47008840730709506,1.023242544521951,0.01596295711726627,-0.47335293227615144,0.9996310790021985,0.10979074867233596,0.059831956265086195,0.07184341553216678,0.38877461876691555,0.4470920521293298,0.09616615580195997,0.0346479535215179,0.07292441677036021,0.045610642070750274,0.035073048770583176,0.06184820691881865,-0.003522534457263138,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.475,1.0,0.0,1.0,1.0,0.007981597511444867,-0.004381077011828605,0.5892505739339305,0.9998558975117965,-0.01167843754042094,-0.008489474973442289,-0.008929012278079811,0.019214961223442836,-0.010260648236872554,0.003105889612577954,-0.05096479882457691,-0.034639210708120725,-0.04080827843753731,0.04973002159933534,0.525934734096124,-0.9658110141264071,0.1379329609214691,0.7918067836745593,-1.2986464695646462,0.016163314609525675,-0.46948252919583555,1.023623104814136,0.01625481587065022,-0.4728400005348382,0.9996023346964337,0.10988927800155479,0.05922609809543289,0.07209751667051734,0.38696878530918855,0.4299621054657754,0.12953736551722272,0.03452966229958901,0.07242975107324301,0.0457449802431098,0.034966811457575186,0.06119873727687852,-0.0033567502072751054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.48333333333333334,1.0,0.0,1.0,1.0,0.008138683065809947,-0.0044688257507221035,0.5892811350684032,0.9998506251459492,-0.011890620510869419,-0.00863371204178414,-0.009099433468115096,0.018953875599054752,-0.010273319722846227,0.0030891538941701653,-0.050971619422229233,-0.034557264597357855,-0.040950300662587355,0.0506461642030067,0.5264255405144646,-0.9652090818988984,0.1411495085219317,0.7953170820459147,-1.2974277520697708,0.0164505421031077,-0.4688812447892077,1.0240049608593362,0.016545737308225856,-0.4723329533215368,0.9995751331654106,0.10998205631596134,0.05851088918665592,0.0723820883296078,0.38484453014717923,0.41219047557881083,0.16298784079819661,0.034398455356185395,0.07181786743963525,0.0459233328278108,0.03484805463658251,0.06043197983554904,-0.003150697404734615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.49166666666666664,1.0,0.0,1.0,1.0,0.008293367539986236,-0.004556673195848165,0.5893116042456026,0.9998452552343835,-0.012102811586698086,-0.00877760188009404,-0.009270456936003205,0.018646245675107545,-0.010284105115816426,0.0030735114702569954,-0.05097320293955335,-0.034469513387894835,-0.04109573666991796,0.051563055871268026,0.5269099155825683,-0.9646046459875803,0.14434703642392208,0.7986766249342061,-1.295930005551343,0.01673662219879543,-0.4682855647385083,1.0243884936945995,0.01683561678125993,-0.4718328008709124,0.9995498230730214,0.1100690381345662,0.05767889129687953,0.0726996644918887,0.38240659490361206,0.3937852875987047,0.19649091148326914,0.03425426418016832,0.07108071374327452,0.04614911103632657,0.03471672458954994,0.059540129064837855,-0.002901246740329988,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5,1.0,0.0,1.0,1.0,0.00844525101811598,-0.004644594799679309,0.5893419822447703,0.9998397879669978,-0.012314988194839413,-0.008921120574140242,-0.00944209705365358,0.018289172812082966,-0.010293039918218306,0.003059117025886093,-0.050969443491757534,-0.03437586347360528,-0.041244578480825946,0.05248064817191614,0.5273868553694125,-0.9639974208240336,0.14752295177032523,0.8018801701725597,-1.2941529035450496,0.017021446506110507,-0.46769656622681977,1.0247741127099417,0.017124349384718355,-0.47134061783712283,0.9995267790530717,0.11015020790488883,0.05672284263536165,0.0730527539756265,0.3796603762804357,0.374756420332909,0.2300196029053403,0.034097067491991734,0.07021040690535107,0.046425693595568696,0.03457281418486925,0.05851556164613525,-0.0026053086901245415,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5083333333333333,1.0,0.0,1.0,1.0,0.008593909756336168,-0.004732565455830174,0.5893722703411538,0.999834223563885,-0.012527127337232467,-0.009064243883030114,-0.009614368148613637,0.01787984899591508,-0.010300170326721867,0.003046127897416163,-0.05096025038249441,-0.03427624301284718,-0.04139681056038589,0.05339889266968284,0.5278552962931576,-0.9633871000879866,0.15067470936192934,0.8049225652730879,-1.2920963455029206,0.017304906656995293,-0.4671153912900858,1.0251622552545256,0.01741183035100775,-0.4708575415101435,0.9995064012615194,0.11022558065307206,0.05563571957615476,0.07344381619882379,0.37661190339124184,0.35511552357240905,0.26354670557244386,0.03392689245517978,0.06919929775555111,0.04675639672247822,0.03441636399808275,0.05735090010584254,-0.002259861799052132,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5166666666666666,1.0,0.0,1.0,1.0,0.00873889703675309,-0.004820559566670316,0.5894024703140773,0.9998285622745358,-0.012739205656262863,-0.009206947327653401,-0.009787284471639058,0.017415580954581324,-0.010305553173141836,0.003034702480232189,-0.05094554856901905,-0.03417060107326756,-0.0415524095604298,0.05431774118280067,0.5283141173623485,-0.9627733572207199,0.15379981682684593,0.8077987622320999,-1.2897604584521756,0.017586894713696836,-0.4665432445975606,1.0255533859886496,0.017697955451353067,-0.47038476950202546,0.9994891146897542,0.11029520216029348,0.05441079766158152,0.07387523675434382,0.3732678121917238,0.33487602304228314,0.2970448482987553,0.03374381546568141,0.06804003551658444,0.0471444433195467,0.034247463012060664,0.056039075997208476,-0.0018619815752440871,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.525,1.0,0.0,1.0,1.0,0.008879744220984068,-0.004908551115141415,0.589432584446893,0.9998228043769349,-0.012951199501784139,-0.009349206274767095,-0.009960860163107748,0.016893813773056085,-0.01030925573283996,0.0030249985428160665,-0.05092527893013686,-0.03405890645230464,-0.041711344007014414,0.055237146039021065,0.5287621429208507,-0.9621558461420808,0.15689583956512473,0.8105038323237926,-1.2871455980312747,0.017867303581423317,-0.4659813906981427,1.025947995976518,0.01798262140120876,-0.46992355691019,0.9994753682352653,0.11035914864947274,0.053041711090509036,0.07434930314895061,0.3696353171971084,0.3140531124542667,0.3304865742701457,0.03354796249951539,0.06672563109594298,0.04759293175585544,0.03406624887825886,0.05457339183090326,-0.001408869650036948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5333333333333333,1.0,0.0,1.0,1.0,0.00901596199783281,-0.004996513740020872,0.5894626155183484,0.999816950176578,-0.013163084998868924,-0.00949099601540827,-0.010135109218062027,0.016312153697192817,-0.010311355399411032,0.0030171714692829683,-0.05089939833111494,-0.033941146193464,-0.041873573934246955,0.05615706032695855,0.5291981458805236,-0.9615342021682374,0.15996040544679774,0.8130329807730043,-1.2842523488810065,0.018146027422022093,-0.46543115074596153,1.026346601517914,0.018265726265990715,-0.4694752129715104,0.9994656335289203,0.11041752597603385,0.05152250989748364,0.07486818106068771,0.36572218069887363,0.29266373228814535,0.3638444194628798,0.03333950900635735,0.06524951836936244,0.04810480461756583,0.03387290772746229,0.05294758095893304,-0.0008978828471595257,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5416666666666666,1.0,0.0,1.0,1.0,0.009147041817105205,-0.005084420813814209,0.5894925667850264,0.9998110000054427,-0.013374838115422385,-0.009632291836419702,-0.01031004544967644,0.015668389824575815,-0.01031193922699368,0.0030113724546042392,-0.050867879483800324,-0.033817323824304274,-0.04203905046874793,0.05707743813862163,0.5296208514191421,-0.9609080431244027,0.1629912092434393,0.8153815611952617,-1.28108152437356,0.018422962064862606,-0.46489389872532,1.0267497427201442,0.018547169863333133,-0.4690410972275411,0.999460403521146,0.11047046832727975,0.04984771405278199,0.07543389146539514,0.36153667971378145,0.27072653511701184,0.39709099277438487,0.03311867934424069,0.06360561265742914,0.04868281782667516,0.03366767352533093,0.051155864630902936,-0.00032656178865053676,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.55,1.0,0.0,1.0,1.0,0.0092724574990999,-0.005172245522413023,0.5895224419546494,0.9998049542209504,-0.0135864347287913,-0.009773069083992569,-0.010485682450970228,0.01496051439451257,-0.010311103344106879,0.0030077466782114466,-0.05083071060422246,-0.03368745734764223,-0.042207715371229,0.05799823479907988,0.5300289411147366,-0.9602769706438141,0.16598601677536076,0.8175450896916212,-1.2776341656681,0.01869800541109277,-0.46437105720167104,1.0271579818150252,0.018826854158079564,-0.468622615227662,0.9994601908324428,0.11051813644582464,0.04801236375486129,0.07604828897050053,0.3570875709170701,0.24826183748772435,0.43019905717580187,0.03288574575721917,0.06178836562991785,0.049329510533180354,0.033450826976261366,0.04919300547568284,0.0003073413362075783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5583333333333333,1.0,0.0,1.0,1.0,0.009391667006981992,-0.0052599609456276415,0.589552245150183,0.999798813204952,-0.01379785069052022,-0.009913303218275544,-0.01066203355461389,0.014186741409717917,-0.010308952245424724,0.0030064314822151592,-0.05078789487407033,-0.03355157702229335,-0.04237950054378064,0.05891940707938537,0.5304210574817231,-0.959640571641561,0.1689426687587238,0.8195192584867238,-1.2739115400872967,0.018971057827482925,-0.46386409263148803,1.0275719012290305,0.019104683646270822,-0.4682212138029464,0.9994655258767494,0.11056071540253842,0.04601206524629031,0.0767130416727646,0.35238405382627735,0.22529155857327288,0.46314161115286634,0.032641026906193374,0.05979281592159991,0.05004717618484644,0.033222693985518886,0.047054356710211076,0.0010058362092291162,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5666666666666667,1.0,0.0,1.0,1.0,0.009504114367113604,-0.0053475401376920735,0.5895819808648128,0.9997925773627739,-0.01400906188844194,-0.010052969858258994,-0.010839111790718151,0.013345523347991512,-0.010305597970282356,0.003007554581131101,-0.050739449716259745,-0.0334097229735762,-0.04255432751353132,0.05984091338912219,0.5307958088688415,-0.958998419949268,0.17185908433913205,0.8212999490011758,-1.2699151388155523,0.019242022526195994,-0.4633745102696444,1.027992101418106,0.01938056572450488,-0.4678383759491585,0.9994769547692632,0.11059841195409828,0.04384303155673175,0.07742961282632521,0.3474357325144434,0.20183914602029507,0.49589196967335436,0.03238488596977028,0.05761463480950524,0.050837835167105716,0.03298364369768256,0.04473590644012759,0.0017706693916097471,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.575,1.0,0.0,1.0,1.0,0.009609231720516283,-0.005434956206845786,0.5896116539080221,0.9997862471223615,-0.014220044305339848,-0.010192044816320687,-0.011016929842540645,0.012435565753564299,-0.010301159178890162,0.003011232329814364,-0.05068540589841768,-0.033261942676582584,-0.04273210690477279,0.06076271394528701,0.5311517746743353,-0.9583500780944556,0.17473326430063119,0.8228832442537287,-1.265646673926074,0.019510805926979097,-0.4629038487179963,1.0284191984818156,0.0196544110412322,-0.4674756153622776,0.9994950370332762,0.11063145152961917,0.04150211766001277,0.0781992445759494,0.34225257613930915,0.17792948961607546,0.528423843905701,0.03211772833923668,0.05525016638005864,0.05170320938673534,0.03273408613586305,0.042234316495515234,0.0026033012405979328,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5833333333333334,1.0,0.0,1.0,1.0,0.009706441487026768,-0.0055221823931199225,0.5896412693431398,0.9997798229335523,-0.014430774073485973,-0.010330504122001628,-0.011195500000095981,0.011455839533392203,-0.010295760139167547,0.0030175680748962433,-0.050625806481449036,-0.03310828835723146,-0.04291273791300143,0.06168477091461584,0.5314875108298417,-0.9576950992063356,0.17756329394145387,0.824265440494777,-1.2611080747504573,0.019777317998516605,-0.46245367416331007,1.0288538215745515,0.019926133826769263,-0.46713447067423325,0.9995203431232732,0.11066007489796553,0.03898684963113519,0.07902294396611165,0.3368448785804651,0.1535888235966576,0.5607114189062967,0.03183999893803753,0.05269646170288689,0.05264469915076564,0.03247446947230781,0.03954695533217478,0.003504885051939244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5916666666666667,1.0,0.0,1.0,1.0,0.009795158622400723,-0.0056091921434965,0.589670832416863,0.9997733052675116,-0.014641227524437117,-0.010468324034775111,-0.011374834111712865,0.010405590822771595,-0.010289529638721859,0.003026650613953055,-0.05056070563311057,-0.0329488143569877,-0.04309610779527203,0.06260704852691977,0.5318015555015209,-0.9570330290283537,0.1803473456103056,0.8254430579803397,-1.2563014836109692,0.02004147257594639,-0.4620255743562815,1.0292966101343284,0.020195652199103995,-0.4668164994400747,0.9995534517841419,0.11068453457394184,0.03629544749401248,0.07990147139075976,0.3312232174778085,0.12884461859814733,0.5927294285063045,0.03155217920155065,0.049951306632309844,0.05366336265303584,0.03220527696716248,0.03667192462729396,0.004476248713018993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6,1.0,0.0,1.0,1.0,0.009874792947655735,-0.0056959591836636325,0.5897003484813941,0.9997666946163603,-0.014851381233561063,-0.01060548104576138,-0.011554943533639795,0.009284348326626425,-0.010282599837774768,0.0030385527845007807,-0.05049016732878233,-0.03278357450670766,-0.043282091391567024,0.06352951315751487,0.5320924349547419,-0.9563634080164896,0.18308368089941734,0.8264128508047461,-1.2512292509420189,0.020303187651875783,-0.4616211523861049,1.0297482109521021,0.020462888442888637,-0.466523271930445,0.9995949472684902,0.11070509102665022,0.03342684155994036,0.08083533160112788,0.3253984129618043,0.10372546441706154,0.624453226654258,0.031254783758276686,0.047013242962408164,0.05475989834339057,0.03192702361606424,0.033608079305961214,0.005517879108762891,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6083333333333333,1.0,0.0,1.0,1.0,0.00994475152933636,-0.005782457585660004,0.5897298229099419,0.9997599914930184,-0.015061212058862536,-0.010741951868530945,-0.011735839077861382,0.008091928085898195,-0.010275105079707888,0.0030533302021011556,-0.05041426396339094,-0.03261261955379435,-0.04347055069205863,0.06445213337736394,0.5323586695275199,-0.9556857735016683,0.18577065249300234,0.827171815720624,-1.2458939298333982,0.020562385638584334,-0.46124202030690803,1.0302092751067182,0.020727769259371732,-0.46625636478497534,0.9996454164359546,0.1107220087559252,0.030380682171868845,0.0818247673354855,0.3193814863613387,0.07826094488699642,0.6558588545086197,0.03094835685687823,0.04388158277481291,0.05593463040760138,0.03164025255171336,0.030355040841776315,0.006629909485418306,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6166666666666667,1.0,0.0,1.0,1.0,0.010004441089137926,-0.005868661830781655,0.5897592610064455,0.9997531964312893,-0.015270697173782993,-0.010877713419318069,-0.011917530958346455,0.006828435661991924,-0.01026718067641053,0.0030710201645200233,-0.05033307489953962,-0.032435994684426865,-0.043661334464581716,0.06537487997011363,0.5325987796576064,-0.9549996618942315,0.18840670567210632,0.8277171998861961,-1.2402982700335419,0.02081899359949042,-0.46088979267319136,1.0306804547922288,0.020990225985417194,-0.4660173545830821,0.9997054457599138,0.11073555230492749,0.02715734288073479,0.08286975558701615,0.31318361916548965,0.05248150629505677,0.6869231026269951,0.030633468586487647,0.04055641593234127,0.057187497534818554,0.03134553124713717,0.026913203788538897,0.00781210992386816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.625,1.0,0.0,1.0,1.0,0.010053270421441869,-0.005954546867215782,0.5897886679104617,0.9997463099861978,-0.015479814093755538,-0.01101274278713631,-0.012100028736005129,0.0054942657753571135,-0.010258961685676015,0.0030916407349441503,-0.05024668497735927,-0.032253737179646656,-0.04385427795585584,0.0662977259157794,0.5328112919088654,-0.9543046109085513,0.19099037947909384,0.8280465074922083,-1.2344452114562816,0.021072943448359128,-0.460566080041369,1.0311624000656319,0.021250194780157352,-0.4658078113884997,0.9997756182680191,0.11074598227643478,0.0237579171934299,0.08397000647050401,0.306816112504289,0.02641832085130913,0.7176235676601417,0.03031071093978502,0.03703861078413251,0.058518045096001,0.031043447569531202,0.02328373560990138,0.009063881027966403,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6333333333333333,1.0,0.0,1.0,1.0,0.010090652797787944,-0.006040088161963075,0.5898180484982225,0.9997393327345977,-0.01568854069640435,-0.01114701719444128,-0.012283341262684686,0.004090099475177542,-0.010250581697572822,0.0031151900142786103,-0.050155183011504414,-0.03206587423977988,-0.04404920267879814,0.06722064634138754,0.5329947449441635,-0.9536001617863897,0.1935203075471778,0.8281575052337179,-1.2283378772392062,0.021324172115153504,-0.4602724824934558,1.0316557555438288,0.021507616778242714,-0.46562929232291705,0.9998565104437133,0.11075355141861948,0.020184209134257447,0.08512496460362895,0.30029034739858573,0.00010314677968414898,0.7479387030344542,0.029980693768684313,0.033329808256484794,0.059925420800457374,0.030734605735071516,0.019468569979255168,0.010384250880532964,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6416666666666666,1.0,0.0,1.0,1.0,0.01011600833810616,-0.006125261746713286,0.5898474072809217,0.9997322652760532,-0.015896855235384585,-0.011280513949119967,-0.012467476624580424,0.0026168989553921724,-0.010242171646065475,0.0031416456086676174,-0.050058660300016516,-0.031872421007278356,-0.04424591629659366,0.06814361843942306,0.5331476953944364,-0.9528858614984909,0.1959952186024036,0.828048226605203,-1.2219795664057074,0.0215726216778372,-0.46001058323709426,1.0321611570789728,0.02176243820907521,-0.4654833352221788,0.999948689116028,0.11075850084287658,0.01643871795889984,0.08633381287276087,0.2936177460126943,-0.026431813370597634,0.7778478631850749,0.029644040682096293,0.029432409605538723,0.0614083738419291,0.03041962221407249,0.015470393823747708,0.011771875266888276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.65,1.0,0.0,1.0,1.0,0.01012876632964173,-0.006210044257443192,0.5898767483013082,0.9997251082340005,-0.01610473634796093,-0.011413210388702607,-0.01265244208547675,0.001075900167086104,-0.010233858661097155,0.003170964294867666,-0.04995720916852502,-0.03167337881297505,-0.04444421261238807,0.06906662135543548,0.5332687235768119,-0.952161264905177,0.19841393664738938,0.8277169750108746,-1.2153737461861216,0.02181823945985511,-0.4597819423333635,1.0326792284411943,0.02201461048181059,-0.4653714524258546,1.000052708364828,0.11076105643165468,0.01252461744611022,0.08759547841284299,0.28680973412474997,-0.053154054600430545,0.8073313409921079,0.029301384934331612,0.025349558202087952,0.06296525748903825,0.030099121634351092,0.011292628476732292,0.013225041117006509,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6583333333333333,1.0,0.0,1.0,1.0,0.010128367475884588,-0.006294412967610731,0.5899060750296815,0.9997178622571794,-0.01631216305651894,-0.011545083817784237,-0.012838244030265311,-0.0005313965927457234,-0.010225764975054012,0.0032030818826295554,-0.04985092157155424,-0.031468733665125447,-0.044643871671399576,0.0699896360466173,0.5333564390185382,-0.9514259368582768,0.2007753808378161,0.8271623256951959,-1.208524044055839,0.022060978093409393,-0.4595880906003928,1.0332105780371235,0.022264090236314395,-0.46529512474756657,1.000169106467978,0.11076142548831908,0.008445730264883267,0.08890864059819314,0.2798777050084622,-0.08003090996163476,0.8363703981621562,0.02895336535003845,0.021085115799053256,0.06459403502440342,0.02977373272907223,0.006939405383684649,0.014741673066280825,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6666666666666666,1.0,0.0,1.0,1.0,0.010114266059425697,-0.0063783458149211355,0.5899353902603611,0.9997105280213362,-0.016519114764291347,-0.01167611143971298,-0.013024887909209446,-0.002203237910502064,-0.010218006895945243,0.0032379132694311205,-0.04973988777062171,-0.03125845499549107,-0.044844659979961385,0.07091264511357413,0.5334094857478933,-0.9506794542285405,0.20307856506419708,0.826383126511514,-1.2014342395500857,0.022300795549022416,-0.4594305237367126,1.033755795691601,0.02251083936062846,-0.46525579566945985,1.0002984029159327,0.11075979367424521,0.004206497976784185,0.09027174080949774,0.27283298489928887,-0.10702968818320668,0.8649472883895681,0.02860062232880288,0.016643633803612445,0.06629228888588745,0.029444084371529136,0.002415536874689206,0.01631934299383353,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.675,1.0,0.0,1.0,1.0,0.01008593200446775,-0.006461821421738391,0.5899646960096768,0.999703106231177,-0.016725571245659637,-0.011806270283650045,-0.013212378183437118,-0.003937630078086707,-0.010210693857892698,0.003275352680438561,-0.04962419510635025,-0.031042494670932428,-0.045046330843715364,0.07183563260785472,0.5334265473181513,-0.9499214078447852,0.20532259725280425,0.8253784975588091,-1.1941082559160128,0.022537655132222775,-0.4593106967036659,1.034315449518555,0.02275482497583988,-0.4652548657996551,1.0004410955178753,0.11075632227108362,-0.00018805272204769352,0.09168299372354749,0.2656868001948215,-0.134117807011791,0.8930452732270355,0.028243793968854985,0.012030320130634875,0.06805723281998244,0.029110801736090958,-0.00227351742700721,0.017955282353732116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6833333333333333,1.0,0.0,1.0,1.0,0.010042852826657794,-0.006544819109306115,0.5899939934164783,0.9996955976225609,-0.01693151263145887,-0.011935537128128088,-0.013400718272148426,-0.005732353268063271,-0.010203927557633281,0.0033152740832703754,-0.049503926879169054,-0.03082078627376431,-0.04524862482485947,0.07275858381809219,0.5334063515358591,-0.949151404333148,0.20750667840077744,0.8241478297279842,-1.1865501516629684,0.022771525448503332,-0.45923001840120203,1.0348900829052674,0.022996019389563308,-0.46529368762657664,1.0005976576218283,0.11075114579804174,-0.004732346884022132,0.09314039985692357,0.25845024651615867,-0.1612629209623173,0.9206486306830497,0.027883512344983735,0.00725100225673847,0.06988572681786209,0.028774502620036863,-0.00712168795163115,0.019646397080506084,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6916666666666667,1.0,0.0,1.0,1.0,0.009984535459957996,-0.0066273189060251925,0.590023282646096,0.9996880029649092,-0.01713691938976934,-0.012063888422238801,-0.013589910502017884,-0.007584976813350302,-0.010197801183749586,0.0033575317647090482,-0.04937916135039848,-0.030593244649259634,-0.045451270316095145,0.07368148503782208,0.5333476748700843,-0.9483690678471698,0.2096301013614069,0.8226907822094371,-1.1787641120712953,0.023002380337972504,-0.4591898466660536,1.035480211632186,0.023234400019507162,-0.46537356059884893,1.000768535469217,0.11074437000587689,-0.009420300665197168,0.09464175908487693,0.25113425973451897,-0.18843304230321545,0.9477426566479208,0.027520399971380158,0.0023120871204429516,0.07177429457378981,0.028435793956593652,-0.012122335648706573,0.02138928482307456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7,1.0,0.0,1.0,1.0,0.009910507952357709,-0.006709301550108544,0.5900525627986113,0.9996803230638065,-0.017341772302722838,-0.012191300205561416,-0.013779956059257203,-0.009492664920484098,-0.010192418184856033,0.003401969120389987,-0.04925002219283081,-0.030359788151356946,-0.04565395711499837,0.07460432331819014,0.5332493465247725,-0.9475740416817334,0.21169224939635276,0.8210072790229306,-1.1707544407188364,0.02323019878135967,-0.4591914836158613,1.036086321148164,0.02346994928883987,-0.4654957265540551,1.0009541457022129,0.11073608478635394,-0.01424546018692796,0.09618539514240076,0.24374961628367608,-0.21559718418358687,0.9743148408542668,0.027155252060977464,-0.0027785668899549254,0.07371813446250819,0.028095427106525142,-0.017267366165398812,0.023179296243815983,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7083333333333334,1.0,0.0,1.0,1.0,0.009820324516670248,-0.006790748901136258,0.590081832054796,0.9996725585542391,-0.017546052869245574,-0.012317748202387012,-0.013970854718075873,-0.011452894123419847,-0.010187820101543017,0.003448405498258381,-0.049116493707699466,-0.03012026411149306,-0.04585641234656348,0.07552708645092798,0.5331102505336355,-0.9467659779281298,0.21369259496613482,0.8190974958063774,-1.1625255313903908,0.023454967872322128,-0.45923615611421953,1.036708847206561,0.023702657137949248,-0.4656613500349389,1.0011548570732807,0.11072630895061719,-0.01920041276173068,0.09776739276396995,0.23630680543650862,-0.24272319033953993,1.0003503948070058,0.026788368295473236,-0.008014907552671424,0.0757148626427595,0.027753733497047836,-0.02255052457518114,0.025014088480412866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7166666666666667,1.0,0.0,1.0,1.0,0.009713555315615813,-0.006871642433965074,0.5901110870324732,0.9996647107261224,-0.017749741739770515,-0.012443207163423085,-0.014162605428295937,-0.013462862584377216,-0.010184060133667697,0.003496607998615092,-0.048978604788771585,-0.029874512574588074,-0.04605838333659923,0.07644976180070043,0.5329293396454103,-0.9459445851356673,0.2156306961536279,0.8169618925172716,-1.1540819341387196,0.023676671586284222,-0.45932506540840584,1.0373482355255432,0.023932511513790666,-0.4658715686303081,1.0013710471768864,0.11071505011464866,-0.024278039901373116,0.09938489704006903,0.22881612854221023,-0.2697809456773559,1.025837247159962,0.02642020952145087,-0.01338959096576664,0.07776054650150854,0.02741116126036558,-0.027964298175277014,0.02688986230292123,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.725,1.0,0.0,1.0,1.0,0.009589801329446503,-0.006951965158735476,0.5901403227464687,0.999656780315867,-0.017952820644169153,-0.012567651454032252,-0.014355205897599775,-0.015519176858515034,-0.010181228048216664,0.0035463712876166406,-0.04883649450852276,-0.029622407369305416,-0.04625952653534485,0.07737233728617213,0.5327056165352793,-0.945109562977462,0.217506197108505,0.8146011467117548,-1.1454282439377248,0.023895304697679642,-0.459459315963649,1.0380048563149196,0.024159509825622007,-0.46612742167119353,1.001603021444996,0.11070231507967543,-0.02947110777162365,0.10103648631119455,0.22128768259103482,-0.2967421819017235,1.0507668269112935,0.02605164870957591,-0.018892902333469408,0.07984879909134435,0.027068511875597903,-0.0334987672654119,0.02880050206035545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7333333333333333,1.0,0.0,1.0,1.0,0.0094486893131097,-0.007031700640108742,0.5901695334494109,0.9996487683024714,-0.018155271387720995,-0.012691054715398617,-0.014548652253758584,-0.017618646785802727,-0.010179358939709168,0.0035974918403796903,-0.04869018540027338,-0.029363768545531566,-0.04645949365243278,0.07829480038536168,0.5324381545158833,-0.9442606436971474,0.2193188241968118,0.8120161894855762,-1.136569153690198,0.02411086573144382,-0.45963994711396366,1.0386790488437323,0.024383653378383965,-0.46642988141806496,1.001851055544559,0.11068803774920172,-0.03477127975922922,0.10271861488953649,0.21373121694676367,-0.3235775263901486,1.0751285004708055,0.02568315178785953,-0.024516564134727803,0.08197535672920697,0.026726250349193986,-0.03914545715385742,0.030741922086177098,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7416666666666667,1.0,0.0,1.0,1.0,0.009289873478488904,-0.007110833053785105,0.5901987117785455,0.9996406757163845,-0.018357075888752118,-0.012813389773377445,-0.01474293934805336,-0.019757931239968884,-0.010178480678290951,0.003649712404100695,-0.04853970552395045,-0.029098399227123803,-0.04665796630438071,0.07921713791532549,0.5321260952059588,-0.9433975860626364,0.22106838405761772,0.8092081879385856,-1.1275094355965447,0.0243233572274773,-0.45986792536589444,1.0393711122604063,0.024604947331441907,-0.46677984595709116,1.002115386813099,0.11067212663999987,-0.04017026840339222,0.10442810339787334,0.20615621736068124,-0.3502591517274589,1.0989132466232165,0.025315199580916853,-0.030251669063299236,0.08413526631632529,0.026384836884966387,-0.04489530177764989,0.032709395847820844,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.75,1.0,0.0,1.0,1.0,0.009113036352525238,-0.007189347196123588,0.5902278488484957,0.9996325036422079,-0.018558216178731553,-0.01293462858839241,-0.014938060702617504,-0.021933594700031225,-0.010178612715132294,0.0037027735578851924,-0.04838507972208342,-0.028826089824278898,-0.04685461572593328,0.08013933582936168,0.5317686500424934,-0.9425201753071828,0.22275476115282317,0.8061785369567852,-1.1182539329131445,0.024532785724459102,-0.460144141598352,1.0400813032823377,0.02482340065980007,-0.46717813644769246,1.0023962121420227,0.11065446277858715,-0.04565960157473459,0.10616173882580071,0.19857186760634082,-0.3767602140335291,1.1221129633332971,0.024948261303197675,-0.03608901611663051,0.08632334940024577,0.02604471815364509,-0.05073894941820645,0.03469799460953382,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7583333333333333,1.0,0.0,1.0,1.0,0.008917889497041556,-0.007267228468841015,0.5902569342336369,0.9996242532217883,-0.018758674374843843,-0.013054742196850745,-0.015134008479395342,-0.02414212356387808,-0.010179764058649576,0.0037564066057880073,-0.04822632575674991,-0.02854661717235229,-0.047049106829946556,0.08106137896163527,0.5313651018463799,-0.941628223748873,0.22437791518439007,0.8029288510380268,-1.108807552874323,0.024739161582530596,-0.4604694089678383,1.0408098347504104,0.025039025967335992,-0.46762549511406126,1.0026936867232579,0.11063489647998997,-0.051230633643324364,0.10791623125933736,0.19098703584982057,-0.4030548652437971,1.1447203662655392,0.02458278177207847,-0.04201917755958906,0.08853427443677564,0.02570631546661671,-0.05666683285404872,0.03670265882743884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7666666666666666,1.0,0.0,1.0,1.0,0.008704174099200402,-0.007344462855836964,0.5902859559353543,0.999615925657298,-0.018958432647302775,-0.013173700654936954,-0.015330773461092446,-0.026379941288352683,-0.01018193282110136,0.0038103332549511235,-0.04806345365393708,-0.02825974538486514,-0.047241100633406766,0.08198325077069485,0.530914806148438,-0.9407215714528605,0.22593787841698684,0.7994609558693886,-1.0991752601420521,0.024942498753993743,-0.46084446122434514,1.0415568745229506,0.02525183925091035,-0.4681225836619266,1.00300792312248,0.11061324790839877,-0.05687457636231796,0.10968821525087602,0.18341026446033082,-0.4291182810516925,1.1667289304723472,0.024219176966263842,-0.048032544377274444,0.09076259168618872,0.025370020582957883,-0.06266921613916066,0.03871823157576948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.775,1.0,0.0,1.0,1.0,0.008471661439737507,-0.007421036897216115,0.5903149003528401,0.9996075222142194,-0.019157473186224412,-0.013291472987613509,-0.015528345040197752,-0.02864342258055374,-0.01018510622556912,0.0038642665999107277,-0.04789646578574364,-0.027965227167677263,-0.047430256011735235,0.08290493309344192,0.5304171922403412,-0.9398000868280251,0.22743475292539558,0.7957768796871653,-1.089362070699784,0.025142814531968326,-0.4612699513741262,1.042322544611847,0.025461859643718623,-0.46866998204971394,1.003338990582854,0.11058930851146814,-0.06258253119894475,0.11147425836673275,0.17584976193269042,-0.4549266825453091,1.188132836812339,0.02385783200063961,-0.054119366243570166,0.09300276094550863,0.025036193815653682,-0.06873623534568774,0.04073948497004043,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7833333333333333,1.0,0.0,1.0,1.0,0.0082201532468608,-0.007496937662203299,0.5903437522607754,0.999599044224206,-0.01935577816951337,-0.013408027143668002,-0.015726711214398587,-0.030928906592976053,-0.01018926077436135,0.0039179123280855006,-0.04772535719788153,-0.027662805288931336,-0.04761623116354083,0.08382640591255265,0.5298717639617889,-0.9388636671467483,0.22886870778253168,0.7918788444936334,-1.0793730461951798,0.025340129287337736,-0.461746450661738,1.0431069205387091,0.02566910914783791,-0.46926818758435473,1.0036869145386473,0.11056284271629441,-0.06834551971248048,0.113270870025457,0.1683133966414363,-0.4804573486724406,1.2089269170022332,0.023499099997634776,-0.060269788472898655,0.09524917739204941,0.024705163005049394,-0.07485793611891611,0.04276114484156324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7916666666666666,1.0,0.0,1.0,1.0,0.007949481944322458,-0.007572152721740372,0.5903724947943705,0.9995904930877898,-0.01955332973240456,-0.013523329957201196,-0.015925858587646346,-0.033232709065445135,-0.010194362497594546,0.003970969940141742,-0.047550116059885954,-0.027352214129704008,-0.047798684942900016,0.0847476471387135,0.5292781002451332,-0.9379122389942675,0.23023997620275286,0.7877692572092913,-1.0692132887497467,0.025534466198595573,-0.4622744478486745,1.0439100309017144,0.025873612360469447,-0.46991761431836254,1.0040516763302134,0.11053358976921307,-0.07415451123161443,0.11507450936423913,0.1608086923131702,-0.505688619427791,1.2291065965200154,0.023143301399413188,-0.06647388623174488,0.09749619638192542,0.024377222924918743,-0.08102430844523112,0.04477791445999024,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8,1.0,0.0,1.0,1.0,0.007659510802624861,-0.007646670121291477,0.590401109441683,0.9995818702769168,-0.019750109939069213,-0.013637347115805864,-0.01612577237650087,-0.0355511333714088,-0.010200367255412835,0.004023133940434192,-0.047370724199994066,-0.02703318128687662,-0.04797727811954314,0.0856686324087062,0.528635855441262,-0.9369457586573443,0.23154885265441785,0.7834507008365036,-1.0588879362531796,0.025725850977327956,-0.4628543487656004,1.0447318571450745,0.026075396196586557,-0.4706185927251086,1.0044332131129805,0.11050126568957597,-0.08000044762572767,0.11688159190099467,0.15334282513133957,-0.5305998901954934,1.2486678355352288,0.02279072356572022,-0.07272169594757849,0.09973815725202506,0.024052634971533857,-0.08722531861755756,0.046784497331224806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8083333333333333,1.0,0.0,1.0,1.0,0.007350134002604167,-0.007720478354287707,0.5904295760429811,0.9995731773372827,-0.019946100756601956,-0.013750043135605718,-0.016326436421514625,-0.03788048044426615,-0.010207221081331024,0.0040740949838758995,-0.04718715770771039,-0.02670542921140172,-0.04815167458685797,0.08658933490020643,0.5279447594513711,-0.9359642124625842,0.23279568995494185,0.778925925706033,-1.048402158157493,0.025914311591357576,-0.46348647611446747,1.0455723335225815,0.02627448960999501,-0.47137136962865517,1.0048314179524005,0.11046556531676716,-0.08587426511097673,0.1186884949641942,0.1459226223836413,-0.5551715978111393,1.26760706819943,0.02244162059495819,-0.07900324383864898,0.10196940604191518,0.02373162707476721,-0.093450938337164,0.04877561898158245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8166666666666667,1.0,0.0,1.0,1.0,0.007021276620767686,-0.007793566336588066,0.5904578727968799,0.9995644158904476,-0.020141284031652856,-0.013861381343267908,-0.016527833203451487,-0.04021705757657936,-0.010214860558164228,0.004123540972404075,-0.04699938759297037,-0.026368676869881976,-0.048321542521016614,0.08750972516398565,0.5272046176894124,-0.9349676170746077,0.23398089636081187,0.7741978408729846,-1.037761151783189,0.026099877987243926,-0.46417106949624454,1.0464313472457731,0.026470923314499344,-0.4721761083640613,1.0052461400960069,0.11042616442769909,-0.09176691309494611,0.12049156191112909,0.13855456255646437,-0.5793851989532905,1.2859211406264137,0.022096213336896403,-0.0853085715253088,0.104184317050664,0.023414393800263028,-0.09969117091984336,0.050746047647014514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.825,1.0,0.0,1.0,1.0,0.00667289454575382,-0.007865923382293524,0.5904859762729355,0.999555587635709,-0.020335641469927845,-0.01397132386505837,-0.016729943864129564,-0.04255718610050039,-0.010223213219429997,0.004171158096985341,-0.046807380492705934,-0.026022641420326943,-0.04848655548850312,0.08842977097400141,0.5264153108997887,-0.9339560197640654,0.23510493266421625,0.7692695057234782,-1.0269701391470527,0.026282581813639183,-0.4649082856398893,1.0473087388067592,0.02666472950666606,-0.4730328891439859,1.005677185413184,0.1103827219005385,-0.09766937010990295,0.12228710517915076,0.13124477677507462,-0.6032231414997113,1.3036072478687055,0.02175468957674974,-0.09162775872599838,0.10637731316228916,0.023101096621909525,-0.10593607460835819,0.052690613802326425,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8333333333333334,1.0,0.0,1.0,1.0,0.006304974335156382,-0.00793753918121207,0.5905138614303806,0.9995466943517104,-0.02052915461874466,-0.014079831622976996,-0.016932748231660837,-0.0448972079720715,-0.01023219796988286,0.0042166318229863164,-0.046611099416849516,-0.025667039895765176,-0.04864639349731343,0.0893494371956613,0.5255767948542474,-0.9329294986549552,0.23616830930706312,0.7641441218479894,-1.0160343643187106,0.02646245614685642,-0.4656981988083445,1.0482043024651446,0.02685594159153117,-0.47394170960753396,1.0061243169927123,0.11033488190159035,-0.10357265691870676,0.12407140823238016,0.12399905148664347,-0.6266688294892764,1.3206628701562861,0.021417204375197285,-0.09795094307808117,0.10854288489397401,0.022791864349073418,-0.11217578303070574,0.05460422849027591,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8416666666666667,1.0,0.0,1.0,1.0,0.005917533021708259,-0.008008403778237277,0.5905415016426645,0.9995377378977713,-0.020721804852801808,-0.014186864337988318,-0.017136224849837973,-0.047233491293795435,-0.010241725519574196,0.004259647818096535,-0.04641050452685926,-0.025301590891959744,-0.04880074398697319,0.09026868567236125,0.5246890999511435,-0.9318881629601924,0.23717158352232698,0.7588250252319902,-1.0049590913111146,0.02663953521989247,-0.4665408013578573,1.0491177868883255,0.02704459391248395,-0.474902485527831,1.006587255888022,0.11028227607350422,-0.10946784690786915,0.12584072647883415,0.11682283228326984,-0.6497065823294079,1.3370857086275745,0.021083880551097667,-0.10426833715738937,0.11067560814601585,0.022486793695181348,-0.11840052287426017,0.056481900428435594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.85,1.0,0.0,1.0,1.0,0.005510617877496295,-0.008078507554868929,0.5905688687274766,0.9995287202149168,-0.020913573363290753,-0.014292380540352428,-0.017340351011400693,-0.04956243482009601,-0.010251698826455649,0.004299892823725045,-0.04620555394087527,-0.024926016257836588,-0.04894930275318702,0.0911874751302197,0.5237523307391162,-0.9308321532136413,0.23811535651178428,0.753315678809166,-0.9937496025082511,0.026813854156041383,-0.46743600442763433,1.0500488959342449,0.027230721486450858,-0.4759150516554383,1.007065681999853,0.1102245257058504,-0.11534607390858431,0.12759128724864288,0.1097212287630317,-0.6723215888772405,1.3528736207455028,0.020754809295545976,-0.11057024279693017,0.11277016064801693,0.02218594997590473,-0.12460062887247436,0.05831875189027613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8583333333333333,1.0,0.0,1.0,1.0,0.005084306144461331,-0.008147841213071823,0.5905959329819331,0.9995196433265946,-0.02110444115046081,-0.014396337587059249,-0.017545102794896923,-0.05188047149888765,-0.010262013543266345,0.004337055471823573,-0.04599620456074739,-0.024540042789715392,-0.04909177480372856,0.09210576110079209,0.5227666653860005,-0.9297616415060483,0.2390002706683775,0.7476196654173696,-0.9824111976320229,0.02698544870815157,-0.46838363873780614,1.0509972895657924,0.027414359745415697,-0.47697916267570556,1.0075592350861933,0.11016124387192239,-0.12119853760365729,0.1293192889318262,0.10269902032982003,-0.6944998570028527,1.3680245555551318,0.020430050907663325,-0.11684706282977575,0.11482133711693265,0.021889367926755735,-0.1307665562257243,0.06011003337481835,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8666666666666667,1.0,0.0,1.0,1.0,0.004638704738970486,-0.008216395761640185,0.590622663222633,0.9995105093390618,-0.021294389019728514,-0.014498691686378901,-0.01775045510484223,-0.05418407110893578,-0.010272558465156833,0.004370827050756745,-0.04578241291732853,-0.02414340393276114,-0.04922787514322768,0.0930234958614184,0.5217323551123886,-0.9286768317314442,0.23982700685061462,0.7417406811924517,-0.9709491932489989,0.027154355004502438,-0.46938345547479726,1.0519625848861938,0.02759554428523012,-0.47809449425920036,1.0080675158894332,0.11009203751857849,-0.127016506698161,0.13102089938789918,0.09576066283509099,-0.71622815921764,1.3825364889064606,0.020109635643651216,-0.12308931039781035,0.11682406315498106,0.02159705263166556,-0.13688889059279008,0.06185113708880863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.875,1.0,0.0,1.0,1.0,0.004173949937722218,-0.008284162505207967,0.5906490268303128,0.9995013204414305,-0.021483397581412378,-0.014599397929558871,-0.017956381714872408,-0.05646974205800338,-0.01028321597520877,0.0044009022245268085,-0.045564136031634166,-0.023735841495349807,-0.04935732948548398,0.0939406283927684,0.5206497236076978,-0.9275779598495834,0.24059628171562902,0.7356825294304089,-0.9593689228169152,0.027320609302212424,-0.4704351272444363,1.052944357285042,0.027774310622610123,-0.4792606441855854,1.0085900873710067,0.11001650949888836,-0.132791320040746,0.13269225374482607,0.08891029596898525,-0.7374939749199272,1.3964073587341908,0.019793564672675457,-0.1292876159831391,0.11877340793016611,0.021308980555662105,-0.14295835580630412,0.06353760928193175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8833333333333333,1.0,0.0,1.0,1.0,0.0036902070516888694,-0.008351133036022699,0.5906749897988642,0.9994920789053542,-0.021671447254166632,-0.014698410329727123,-0.018162855313580098,-0.05873403241054807,-0.010293862485764688,0.004426979711030355,-0.045341332290710835,-0.023317107384279535,-0.04947987489283468,0.09485710435306655,0.5195191664450428,-0.9264652941690305,0.24130884511676437,0.7294491149437863,-0.9476757372700957,0.02748424774904703,-0.47153824907451625,1.0539421416850299,0.027950693961157822,-0.48047713352263877,1.009126476044132,0.10993426054041522,-0.13851438589167264,0.13432945171242272,0.08215175131189412,-0.7582854297758312,1.409635000458973,0.019481811134796564,-0.135432732328572,0.12066459569166632,0.02102510067617712,-0.1489658194731447,0.06516516148087792,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8916666666666666,1.0,0.0,1.0,1.0,0.0031876700942111446,-0.008417299228580217,0.5907005167885181,0.9994827870843461,-0.0218585182721871,-0.014795681868097012,-0.018369847552724673,-0.06097353021615728,-0.010304368874149875,0.00444876292571828,-0.04511396233820555,-0.0228869653707546,-0.04959526034293216,0.09577286606844199,0.5183411505095032,-0.9253391356543763,0.24196547757082726,0.723044438934145,-0.935875006142599,0.027645306154459034,-0.4726923394499125,1.0549554338799032,0.028124728967213075,-0.48174340784347114,1.009676173395688,0.10984489114502283,-0.1441771795414426,0.13592855454492625,0.07548856096283418,-0.7785912327170319,1.4222170825499125,0.019174321297545233,-0.1415155374201449,0.1224930161813731,0.020745335709735357,-0.15490229662869948,0.06672968067780616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9,1.0,0.0,1.0,1.0,0.0026665614487621937,-0.008482653237201309,0.5907255711830425,0.9994734474127128,-0.022044590696265253,-0.014891164547614922,-0.018577329097507603,-0.0631848632115544,-0.01031460091212436,0.004465960598008184,-0.044881989980927246,-0.022445192899259434,-0.04970324722426755,0.09668785253881693,0.5171162134526854,-0.9241998182599483,0.24256698779947827,0.7164725943985024,-0.9239721192275971,0.027803819770672783,-0.473896841364852,1.0559836919547194,0.028296449556320078,-0.4830588384664504,1.0102386373887622,0.10974800341861435,-0.14977123948424653,0.1374855817893761,0.06892396666505762,-0.7984006110004316,1.4341510422707393,0.018871015809925687,-0.1475270357097347,0.12425423401092317,0.02046958343231403,-0.16075895161804743,0.06822723853479484,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9083333333333333,1.0,0.0,1.0,1.0,0.0021271315412804853,-0.008547187496618772,0.5907501151508552,0.9994640624040926,-0.022229644428776865,-0.01498480945424638,-0.018785269678611282,-0.06536469796974426,-0.010324419689040961,0.004478287368563406,-0.04464538311388012,-0.021991582953333026,-0.04980360976231744,0.09760199945875223,0.5158449631847658,-0.92304770929122,0.24311421034857822,0.7097377620841379,-0.91197248877142,0.027959823084624462,-0.4751511233784081,1.0570263377800853,0.028465888691084976,-0.48442272370377193,1.0108132940379346,0.10964320283225443,-0.15528816235491405,0.1389965079657296,0.06246092935542513,-0.8177032437368204,1.4454340216137762,0.0185717910546105,-0.15345835775502747,0.12594399707594128,0.020197718093330277,-0.16652709837685742,0.06965409966813496,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9166666666666666,1.0,0.0,1.0,1.0,0.0015696585213609395,-0.008610894725633332,0.5907741097100043,0.9994546346495805,-0.022413659232704893,-0.015076566826157295,-0.018993638145706666,-0.06750973856982267,-0.01033368202938836,0.004485464376104854,-0.04440411466736868,-0.02152594599415616,-0.049896135378947486,0.09851523925268783,0.5145280774134369,-0.9218832097938529,0.24360800328873536,0.7028442070028887,-0.8998815522007009,0.028113349621582958,-0.4764544806607691,1.0580827585726518,0.028633078191208916,-0.4858342901060647,1.0113995390498978,0.10953009991849477,-0.16071959683706005,0.14045725932912534,0.0561021390688865,-0.8364891942623198,1.456062803419258,0.01827652060037023,-0.15930075845573932,0.1275582440852041,0.019929591925565218,-0.17219819928550484,0.07100672908018524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9249999999999999,1.0,0.0,1.0,1.0,0.0009944479559753513,-0.008673767933892192,0.5907975147970316,0.9994451668154296,-0.0225966147548164,-0.01516638613111749,-0.019202402522146788,-0.06961672486087436,-0.010342240906038249,0.004487219843254462,-0.04415816358101727,-0.021048111989896107,-0.04998062498841637,0.09942750112406047,0.5131663032374815,-0.920706754969068,0.24404924599972633,0.6957962755130992,-0.887704775381099,0.0282644317612973,-0.4778061360193371,1.0591523085148387,0.028798048556511063,-0.4872926936918637,1.0119967395226044,0.10940831190921818,-0.16605723674888884,0.14186371086968297,0.04985002513479775,-0.8547488416906424,1.4660337476713226,0.017985056759079812,-0.16504561406194274,0.12909311128338263,0.019665036754702298,-0.17776386276743605,0.07228179880838681,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9333333333333333,1.0,0.0,1.0,1.0,0.00040183253878432035,-0.008735800431840383,0.590820289339797,0.9994356616403077,-0.022778490553137187,-0.015254216152531558,-0.01941153006057609,-0.07168243039253196,-0.010349945851110957,0.0044832896713651715,-0.04390751581065233,-0.02055793255536174,-0.050056893233613495,0.10033871111784147,0.5117604568009554,-0.9195188146126915,0.244438837040982,0.6885983929747114,-0.8754476564061788,0.02841310056756762,-0.47920524089513483,1.0602343104273748,0.028960828803787288,-0.48879702115218865,1.0126042356967042,0.10927746432371405,-0.17129281351496273,0.14321168371498105,0.043706766608225256,-0.8724728119567837,1.4753427279636,0.01769723225369682,-0.17068441812657764,0.13054493844624648,0.01940386571423154,-0.18321583979929001,0.0734761938594497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9416666666666667,1.0,0.0,1.0,1.0,-0.00020782818250198546,-0.008796985843896807,0.590842391334412,0.9994261219320976,-0.022959266128897496,-0.015340005084585743,-0.019620987299199366,-0.0737036600844102,-0.010356643367036615,0.004473418054857381,-0.04365216537505157,-0.02005528322345613,-0.05012476866687448,0.10124879219612237,0.5103114230122321,-0.9183198935738183,0.24477769210986342,0.6812550619804861,-0.863115729915039,0.028559385632192246,-0.4806508763214467,1.0613280574889428,0.02912144631841492,-0.49034629102185184,1.0132213427535952,0.10913719251780502,-0.1764180882293176,0.14449694310484373,0.03767430288394713,-0.8896519086367816,1.4839850681364841,0.017412862004915625,-0.17620877657342993,0.13191027423007817,0.01914587507348832,-0.18854601949755523,0.07458701749798902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.95,1.0,0.0,1.0,1.0,-0.000834148058860449,-0.008857318124910266,0.5908637779264981,0.9994165505642139,-0.023138920963155396,-0.015423700637093524,-0.019830740118472294,-0.07567724770593828,-0.01036217734094784,0.004457358126271377,-0.04339211545063674,-0.019540065871676258,-0.05018409388008431,0.10215766432647155,0.5088201553304668,-0.9171105322276107,0.24506674208904777,0.6737708611640983,-0.8507145719372374,0.028703314934316215,-0.48214205383802533,1.0624328149978761,0.02927992672167876,-0.49193945481048124,1.013847352655004,0.10898714320675296,-0.18142484351630683,0.14571519711716663,0.03175434444703529,-0.9062770438068224,1.4919554791025402,0.01713174504655607,-0.18161040204589196,0.13318588095298178,0.018890846188104604,-0.19374642394176078,0.07561159595557143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9583333333333334,1.0,0.0,1.0,1.0,-0.0014767145715293521,-0.008916791579957829,0.5908844054970694,0.9994069504714229,-0.023317434558343415,-0.01550525015072073,-0.020040753797992413,-0.07760005323791805,-0.010366389466121178,0.00443487264359755,-0.04312737952318971,-0.01901221132855759,-0.05023472558908525,0.10306524458290159,0.5072876756202936,-0.9158913069551988,0.24530693118398067,0.6661504445837058,-0.83824980526333,0.028844914716301514,-0.4836777163555449,1.0635478221714925,0.02943629375488333,-0.49357539808754786,1.0144815360195214,0.10882697597694807,-0.18630487539694096,0.14686209633317793,0.02594838371924091,-0.9223391691919569,1.4992479958991578,0.016853666581441232,-0.18688110769964794,0.13436873888660994,0.018638547584298587,-0.198809202391369,0.07654748262571953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9666666666666667,1.0,0.0,1.0,1.0,-0.002135089041761659,-0.008975400887556873,0.5909042297534091,0.9993973246451371,-0.02349478648502619,-0.015584600723378703,-0.020250993073389477,-0.0794689601873016,-0.010369119674757132,0.004405734731951997,-0.04285798260663574,-0.018471682186654452,-0.05027653467784023,0.10397144725942069,0.5057150740738511,-0.9146628306220578,0.24549921515103512,0.6583985416775657,-0.8257271053389181,0.028984209377340236,-0.4852567389663528,1.0646722939793196,0.02959056918141707,-0.49525294151700405,1.0151231440320994,0.10865636480285296,-0.19104998537133433,0.14793323464181496,0.020257705966116313,-0.9378292078446981,1.5058559150378459,0.01657840019122496,-0.19201280060090142,0.1354560501348745,0.018388737190031812,-0.2037266250510894,0.07739246180614501,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.975,1.0,0.0,1.0,1.0,-0.0028088068186960065,-0.009033141126374157,0.5909232058253994,0.9993876761281579,-0.02367095643420409,-0.01566169934868592,-0.020461422193034227,-0.08128087292734815,-0.010370206586952674,0.004369728692387837,-0.0425839625397321,-0.017918475850173598,-0.05030940620808828,0.10487618399628247,0.5041035091974381,-0.9134257530445019,0.24564455961674928,0.6505199577862941,-0.8131522066793659,0.029121221386155263,-0.48687792969889326,1.0658054230070737,0.02974277270805053,-0.49697084183839935,1.0157714103829572,0.10847499958740209,-0.1956519729308548,0.1489241513919226,0.014683400234662414,-0.9527379865942898,1.5117717322599633,0.016305710215563304,-0.19699747488946429,0.13644524217270249,0.01814116472789798,-0.20849107653647225,0.07814455204788295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9833333333333333,1.0,0.0,1.0,1.0,-0.003497377445896864,-0.009090007805528537,0.5909412883678496,0.9993780080088409,-0.023845924275547464,-0.01573649306751898,-0.020672004974406792,-0.08303271413673001,-0.010369487981253672,0.0043266508908865985,-0.04230537137237768,-0.017352627846933394,-0.050333239400497866,0.10577936391921072,0.5024542078583368,-0.9121807614321924,0.2457439384882795,0.6425195752343276,-0.8005309098012521,0.02925597121426629,-0.48854003021451053,1.0669463813488647,0.029892921926882036,-0.4987277927926119,1.0164255532328974,0.10828258774582739,-0.20010262872131923,0.1498303351164476,0.009226370296833153,-0.9670561695132207,1.516987080857497,0.01603535431769665,-0.20182720486733197,0.13733397111831191,0.017895574286395516,-0.2130950491921535,0.07880200916649649,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9916666666666667,1.0,0.0,1.0,1.0,-0.004200284807736878,-0.009145996898599427,0.5909584316694538,0.9993683234146475,-0.02401967012200087,-0.01580892913379836,-0.020882704859987812,-0.0753557930241695,-0.011667138773803331,0.009128420237499192,-0.049574123828430856,-0.03432719123470952,-0.04725857782670054,0.10668089379204626,0.5007684653854161,-0.9109285807925611,0.24579833245502983,0.6344023549610738,-0.7878690886650743,0.029388477291450207,-0.49024171644668213,1.0680943225257122,0.030041032279490454,-0.5005224259916019,1.0170847772023988,0.11285599093073057,-0.19465001342874433,0.2023323837262403,0.04942170145055047,-0.6026070209100243,0.8931738002444978,0.029540759317588233,-0.16783872396685995,0.13347139203968794,0.031014750576175212,-0.17556641154010455,0.07250233762620795,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0,1.0,1.0,1.0,1.0,-0.004764502784218823,-0.009225194112463718,0.5910614395080162,0.9993553103977431,-0.024258560083211853,-0.016023185655353066,-0.021065217040855365,-0.057308545719931485,-0.012423992922685234,0.01626023028255098,-0.04844493383053753,-0.026437318615510345,-0.039875911359079065,0.10766029710138957,0.49921004096785776,-0.9088085550367551,0.24656763351245534,0.6324761248858272,-0.7856446797971771,0.02974831720289276,-0.49133734228062487,1.0691709045495261,0.030409834436484956,-0.5016538996516137,1.0176339255266675,0.10568898586183484,-0.17256962446516755,0.2090671878210837,0.08385839434323195,-0.20428301492185552,0.20672435186403382,0.026759889057655847,-0.6201525523596496,1.1682140442184608,0.03770203984894277,-0.11016796083523461,0.003196785535113378,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0083333333333333,1.0,1.0,0.0,1.0,-0.005171370379977258,-0.009299841080473478,0.5912073121105419,0.999348043330298,-0.024422403775027773,-0.016028661796949985,-0.021215948877044703,-0.04551655774801821,-0.011280882842454579,0.012818816256993652,-0.04349341888811551,-0.01149709382018539,-0.03757700860275003,0.10844237688974351,0.4978923049776633,-0.9074441276622097,0.24719597236075036,0.6309976380457095,-0.7844236828006738,0.029834475442411138,-0.500577592319343,1.08756455659602,0.030669399610306167,-0.5023585586721891,1.0171380569613173,0.09838286607179142,-0.13502136176828938,0.14899761482874307,0.08011282303219291,-0.15736534461103346,0.1370684317998716,0.0071401909983326295,-1.0969992387144845,2.2430654713390163,0.032304007545375865,-0.08996736629109492,-0.017235677692899465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0166666666666666,1.0,1.0,0.0,1.0,-0.0055367822578159444,-0.009370666920243074,0.5912586822193664,0.9993382672432543,-0.024617794782844652,-0.01611888785744584,-0.021381610264880755,-0.0413383353993447,-0.010471294057353116,0.0058656928084864415,-0.04700600658304972,-0.02450564468200079,-0.04025788572559642,0.10930001153591942,0.49695968493838627,-0.906325261456276,0.24790284722965855,0.6298533691423099,-0.7833602059338459,0.029867320386198305,-0.5096206629258663,1.106555329071843,0.03094823456224122,-0.5031533557564652,1.0173466642317859,0.10299943749091434,-0.10363358039821469,0.13172094497814868,0.08492069498907573,-0.13051533451112984,0.12712449510684953,-0.0011215817255882249,-1.0578266271851655,2.2656167590798315,0.03247709547538988,-0.09333723502799929,0.034510778872780534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.025,1.0,1.0,0.0,1.0,-0.005869997943909963,-0.00944021760147998,0.5912904495106974,0.9993279320658319,-0.02481282344185405,-0.01623262469605028,-0.021552491302605104,-0.03802619178614364,-0.01016439683827486,0.0043434296018620665,-0.04682446910550628,-0.028019068067102016,-0.04118080059419813,0.11015903418125875,0.49616507863769305,-0.9052487785792406,0.24861131727723496,0.628822382470524,-0.7823049412155596,0.029815782413651334,-0.5182080361057624,1.125324835914017,0.031210684534895998,-0.5039141792559891,1.017713236609197,0.10297257733375503,-0.09097148358022777,0.12789913000508912,0.084905285541228,-0.12040625048790998,0.1270002039264284,-0.010713132115375695,-1.002336615371513,2.2307389119639964,0.031046422335569077,-0.08825580255727994,0.04520915363242839,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0333333333333332,1.0,1.0,0.0,1.0,-0.006179334339896419,-0.009509277147258249,0.5913179886317045,0.9993173978834236,-0.02500719898173007,-0.016352328831854206,-0.021725092137128737,-0.03557477154541707,-0.010013363303956245,0.003956049178746935,-0.04669361401397064,-0.02887894373166629,-0.041465318740186136,0.11101622115814867,0.4954434935453825,-0.9041936092895245,0.24931793532201235,0.6278465983008448,-0.7812435358684054,0.029688768184275377,-0.5263262731820582,1.1437343109379097,0.031465674934500705,-0.5046242857990866,1.0181001501256597,0.10275017271498849,-0.08378048282066008,0.12559090691192099,0.08469626554787446,-0.11502083772464644,0.1275799572975389,-0.01957838269509321,-0.9465372152475959,2.1859199101084137,0.03041237145329237,-0.08271440912048567,0.045997200624969814,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0416666666666667,1.0,1.0,0.0,1.0,-0.006471500184956922,-0.009578138795459334,0.5913444665194147,0.9993067589605767,-0.025201249298477862,-0.016473305994859046,-0.0218981441931409,-0.03381933159612631,-0.009928088742691778,0.0038223192316922715,-0.04662991826298153,-0.02903368129386855,-0.04152199858519408,0.11187153705984189,0.4947687372573487,-0.9031555967973752,0.25002292170303286,0.6269053685084466,-0.780178608593934,0.02948947603539978,-0.533983656359889,1.161756834415824,0.03171755739245087,-0.5052927527413306,1.0184798566196132,0.10253673294564974,-0.07906985557797341,0.12376740699417077,0.08451808767656055,-0.11154681068991534,0.1278957272306669,-0.028225786830258295,-0.8917126697223177,2.139232177786634,0.030151875665284517,-0.07838018789956713,0.04493185494879981,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.05,1.0,1.0,0.0,1.0,-0.0067515497311157295,-0.009646920872216766,0.5913706135194401,0.9992960423556877,-0.02539511041676451,-0.01659431928663054,-0.02207117275075521,-0.03258788283591204,-0.009878564762034258,0.003761235390114403,-0.046593198967034954,-0.029005336844291008,-0.04149501366876363,0.11272516670724284,0.4941256626190829,-0.902130819172955,0.2507265701166217,0.6259874847893462,-0.779111940414561,0.029218338403771072,-0.5411881510107635,1.179388180567687,0.03196820619558878,-0.5059306222640794,1.0188490143748063,0.10234927393323434,-0.07588598283535863,0.12241095980730421,0.0843724750862418,-0.10920092363754907,0.1280783701182009,-0.03688230375109569,-0.8376720208098809,2.0922723225824935,0.03005921235471984,-0.07524591926881374,0.04375126255980355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0583333333333333,1.0,1.0,0.0,1.0,-0.007023213415635148,-0.009715680748312472,0.5913966521959949,0.9992852556615734,-0.025588849269615622,-0.01671505865990205,-0.022243997492283035,-0.03174302013798227,-0.009852139170252034,0.003731202615630638,-0.04656996113515769,-0.02893312791929083,-0.0414367773579849,0.11357735829206246,0.4935039708767594,-0.9011154141339202,0.2514291296211369,0.6250853531144874,-0.7780439690919639,0.02887477097288152,-0.5479448567067203,1.196628039792199,0.032218544265029535,-0.5065468513958108,1.0192090443289432,0.10219150064910532,-0.07376266343493754,0.1214818733362999,0.0842543552864039,-0.10764002488110158,0.12824057643308073,-0.045632807557292945,-0.784093034985236,2.0452702718998417,0.030053425486984836,-0.07305287680996919,0.04277259997304661,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0666666666666667,1.0,1.0,0.0,1.0,-0.007289227802930658,-0.009784452125269731,0.5914226835858898,0.9992744007069091,-0.025782507436726384,-0.016835459791817557,-0.022416549594462543,-0.031181717392778308,-0.009841927231282676,0.003719544246140398,-0.046555179179473896,-0.028853465150135114,-0.04136677691576684,0.11442835838472792,0.4928962848951673,-0.9001061212840167,0.2521308093713951,0.6241934843746612,-0.7769745974740097,0.028457791611149523,-0.5542563682605174,1.2134760184326843,0.03246909662037186,-0.5071481702109122,1.0195618910410238,0.10206129238652245,-0.07240386791392717,0.12090118316867571,0.0841589767166484,-0.10664975234975227,0.12842242022751638,-0.05451123929837223,-0.7307136711773943,1.9981717617030137,0.030099137799188685,-0.07156130591320142,0.042008922925713676,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.075,1.0,1.0,0.0,1.0,-0.007551597113666533,-0.009853257342496584,0.5914487687714732,0.9992634776717947,-0.02597611395424177,-0.016955520791368663,-0.02258880275270367,-0.03082806712421981,-0.009843476098824862,0.00372044314969796,-0.04654632836193538,-0.02877524282301834,-0.041292328838743536,0.11527837983183783,0.4922972397448606,-0.8991003944144422,0.25283177923308103,0.6233078572419916,-0.7759035954215053,0.02796625031790865,-0.5601234178930102,1.2299309024872491,0.03272019656168268,-0.5077395398276975,1.0199091930443718,0.10195411245545877,-0.0716020538434381,0.12058853032703265,0.08408179540270844,-0.10607777633933724,0.12863172448750682,-0.06353189306978146,-0.6773423180955485,1.950876775404664,0.03017847613191016,-0.07058564829569791,0.04141862415226516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0833333333333333,1.0,1.0,0.0,1.0,-0.007811788377352977,-0.00992211207914159,0.5914749492027148,0.99925248633635,-0.02616969000867329,-0.01707525338243956,-0.022760746855014658,-0.030626342608427535,-0.009853659663093439,0.0037303085922176992,-0.04654181414296103,-0.02870012324118719,-0.04121618924444817,0.1161275935923189,0.49170291733111,-0.8980963124452328,0.2535321726281069,0.6224255214356722,-0.7748307353992179,0.027398926726653165,-0.5655454068954432,1.2459906313560953,0.032972071222570364,-0.5083245976825072,1.0202522014435615,0.10186512448611462,-0.07120707315905195,0.1204767833284981,0.08401876275585307,-0.10581251289358828,0.12886615024966241,-0.0727002936921304,-0.6238433966927293,1.9032901430381521,0.03028111230867145,-0.0699878392328257,0.04095904136153461,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0916666666666666,1.0,1.0,0.0,1.0,-0.008070874257198067,-0.00999102758112671,0.591501253867005,0.9992414264492554,-0.02636325129187266,-0.017194670381234116,-0.022932377972200487,-0.030535567276412476,-0.009870203563350206,0.003746632966766598,-0.04654051121019866,-0.028627977311946204,-0.04113941397152071,0.11697613190660641,0.49111045519220975,-0.8970924480256339,0.2542320919456786,0.6215443153604318,-0.7737558262506776,0.026754578756373142,-0.570520807837889,1.2616524048712183,0.033224881766827204,-0.5089060038149112,1.0205918437337307,0.1017900873260491,-0.07110902152456355,0.12051378801518631,0.08396651963698876,-0.10577167760790873,0.12912120297550844,-0.08201732280183748,-0.5701236224926998,1.855329912303585,0.030400404675555298,-0.06966595805177,0.04059587805112397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1,1.0,1.0,0.0,1.0,-0.008329636878611504,-0.010060011921564672,0.5915277030161533,0.9992302978232698,-0.026556809455623564,-0.017313782862047638,-0.023103694651789727,-0.030525480726281386,-0.009891420998556295,0.003767592151446607,-0.04654158501012629,-0.0285583164772965,-0.04106244702337417,0.11782409504775306,0.49051776697236726,-0.8960877493116464,0.2549316146220567,0.6206626601422071,-0.7726787153496261,0.02603197134662254,-0.5750474672703215,1.276912796561155,0.03347874463382962,-0.50948569698337,1.0209287994110803,0.10172557805944477,-0.07122685690520658,0.12066007421697833,0.08392240251864025,-0.105894357628884,0.12939259635724953,-0.09148095341795129,-0.5161217229918824,1.8069266829532138,0.030531729323479417,-0.0695446587549764,0.04030308371681279,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1083333333333334,1.0,1.0,0.0,1.0,-0.008588643119536893,-0.010129070791651953,0.5915543105755393,0.9992191003473216,-0.026750373094014887,-0.017432599818393898,-0.023274696646612067,-0.030573590583322867,-0.00991604158347048,0.003791837607576393,-0.0465443983799629,-0.028490649124559942,-0.04098553508472388,0.11867155820759716,0.4899233409104563,-0.8950814467886843,0.2556307986543226,0.6197794093999504,-0.7715992829780568,0.025229896199407287,-0.5791228365544204,1.2917678495871052,0.03373374392221853,-0.5100650814608275,1.0212635617956776,0.10166893790760356,-0.07150036372927548,0.12088595754593978,0.08388434945125645,-0.10613520726198145,0.1296767605856708,-0.10108705780064231,-0.46180103162903663,1.7580214979520115,0.03067167083125419,-0.06956794069460592,0.04006110653975714,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1166666666666667,1.0,1.0,0.0,1.0,-0.008848299143950042,-0.010198208022549678,0.5915810858217371,0.9992078339750745,-0.026943948429519946,-0.017551128400720862,-0.023445384571994732,-0.030663029381030372,-0.009943092835036225,0.0038183605663563956,-0.046548452823032944,-0.02842455480606634,-0.040908883107094896,0.11951857734621311,0.489326094243546,-0.8940729833525474,0.256329687112911,0.618893740021174,-0.7705174360065316,0.02434718704994517,-0.5827441511308055,1.3062131548603553,0.033989939147683855,-0.5106451626616134,1.0215964845200762,0.10161813554780214,-0.07188437527520741,0.12116903365974929,0.08385077940643582,-0.10646018618066355,0.1299708218301454,-0.11082982078978648,-0.40714416703081513,1.7085639302512678,0.03081758474902968,-0.06969383885941927,0.03985523233287491,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.125,1.0,1.0,0.0,1.0,-0.009108889870047985,-0.010267425937356517,0.5916080345703486,0.9991964987087057,-0.027137539798831916,-0.01766937423918555,-0.02361575990574207,-0.030780999527256048,-0.009971815846883392,0.003846395867126155,-0.04655334852088725,-0.02835968898587544,-0.04083271036728654,0.12036519380006053,0.48872526798920285,-0.8930619628943551,0.25702831164442985,0.618005072963606,-0.769433102614221,0.023382732519577513,-0.5859085726716007,1.320243915091293,0.034247370334702355,-0.5112266454418178,1.0219278156678921,0.10157162632578265,-0.07234459727763487,0.12149223116990404,0.08382048014450638,-0.10684344425702541,0.13027246562322903,-0.12070196865407029,-0.35214919673356215,1.6585106193981947,0.0309673377444801,-0.06989055724956339,0.039674291552556085,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1333333333333333,1.0,1.0,0.0,1.0,-0.009370607513685738,-0.01033672558971084,0.5916351600148995,0.9991850945833798,-0.027331149999210873,-0.017787341740187874,-0.02378582510532,-0.030917646019797407,-0.010001604578799941,0.0038753523225151373,-0.046558756240663725,-0.028295773907896133,-0.0407572686991816,0.12121143778497616,0.4881203509555854,-0.892048112833049,0.2577266951153194,0.6171130159502236,-0.7683462282461444,0.02233548757237733,-0.5886133044096982,1.3338549985169919,0.03450606144342519,-0.5118100052824395,1.0222577227126188,0.10152823275672795,-0.07285458430171587,0.1218423575454497,0.08379251597453341,-0.10726505293209732,0.1305797993378932,-0.13069490340211695,-0.2968268597728785,1.6078242114187713,0.031119141624066787,-0.07013366227286211,0.03950970612601523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1416666666666666,1.0,1.0,0.0,1.0,-0.009633572215811417,-0.010406106924280421,0.5916624633128978,0.9991736216536508,-0.02752478053625301,-0.017905034342250097,-0.02395558375746677,-0.031065240090830077,-0.010031961920775802,0.003904762034413794,-0.046564397345802366,-0.028232589125503225,-0.04068284675147597,0.12205733101267266,0.4875110249175076,-0.8910312569352643,0.25842485357733874,0.6162173220814043,-0.7672567726252562,0.02120448412954223,-0.5908556870011487,1.3470409852816059,0.03476602269510347,-0.5123955398130322,1.0225863107699924,0.1014870506434501,-0.07339355080710819,0.12220903112618142,0.08376615613740368,-0.10770935753217525,0.13089123961999016,-0.1407987844594845,-0.241198546372956,1.55647261042545,0.031271441903980984,-0.07040404963791325,0.03935479933971031,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.15,1.0,1.0,0.0,1.0,-0.009897846941504989,-0.010475568882452886,0.5916899439880079,0.9991620799817466,-0.02771843180150895,-0.01802245473840298,-0.024125040729853126,-0.031217589065077562,-0.010062467857780751,0.003934243510606788,-0.04657002950997242,-0.028169964298430477,-0.04060976936432107,0.12290288862903366,0.4868971251088003,-0.8900112956476126,0.2591227977176095,0.615317859991354,-0.7661647075858112,0.019988841164719256,-0.5926332801825808,1.3597962086907494,0.03502725214182487,-0.512983406109738,1.0229136360349473,0.10144737799830689,-0.07394478858054554,0.12258390322533064,0.08374082085554457,-0.10816378372395796,0.1312054260716855,-0.15100257908369996,-0.18529481840551476,1.5044284611632364,0.03142284078606922,-0.07068647483556179,0.03920429987462004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1583333333333332,1.0,1.0,0.0,1.0,-0.010163448243542397,-0.010545109469312789,0.5917176001985747,0.9991504696273557,-0.027912103200115203,-0.018139605074720382,-0.024294202314832553,-0.031369230496583175,-0.010092677348279178,0.0039634257143853525,-0.046575385391983165,-0.028107890591117506,-0.04053873272240517,0.12374812064597777,0.4862786117744985,-0.8889881918815088,0.25982053392493115,0.6144145923526717,-0.7650700155240614,0.01868777447814723,-0.5939439339745739,1.3721147929676598,0.03528973670820462,-0.5135736477269582,1.0232397157679027,0.101408800484028,-0.07449303775116767,0.1229591425083032,0.08371609877055208,-0.10861685729200099,0.13152061946365867,-0.16129492278059931,-0.1291536722016562,1.451669305261194,0.03157154832669817,-0.07096820190240383,0.03905460670055039,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1666666666666667,1.0,1.0,0.0,1.0,-0.01043034762749113,-0.01061472482647522,0.5917454282575525,0.9991387907069286,-0.028105792793684553,-0.018256488193816076,-0.024463079139518607,-0.03151664875908938,-0.01012238554085162,0.0039921275578707165,-0.0465802934021276,-0.028046002668487315,-0.04046957245742266,0.12459303530376746,0.48565557447961416,-0.8879619766058076,0.260518066030452,0.6135075790364873,-0.7639726972614169,0.017300592451709267,-0.5947858413859417,1.3839906971117693,0.03555344461393651,-0.5141662094747781,1.0235645461466232,0.10137051825397786,-0.07502972798608787,0.12333114864893524,0.0836914067688721,-0.10906218998385064,0.13183693752127912,-0.1716612232816655,-0.07282188589019745,1.3981750290430783,0.03171700228565888,-0.07123921007274214,0.038900647236519426,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.175,1.0,1.0,0.0,1.0,-0.010698502878723922,-0.010684412542306235,0.5917734253444694,0.999127043051342,-0.028299498497857026,-0.018373103194195006,-0.024631676177339204,-0.03165633276246244,-0.010151345901611965,0.00402013929326263,-0.0465846583905788,-0.027984253529549006,-0.040402490741258214,0.12543762928354407,0.4850281163080637,-0.8869326727373599,0.26121539070441235,0.6125968891862742,-0.7628727332320401,0.015826754090119473,-0.5951576320727439,1.3954177101183778,0.0358183534129656,-0.5147609678948373,1.0238880598885114,0.10133224329062912,-0.07554517663639015,0.12369473057174396,0.0836664919239416,-0.10949246200660845,0.1321532773109757,-0.1820863408414366,-0.01635302933840732,1.3439312849880647,0.031858522768008074,-0.0714912090900155,0.038740025212784523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1833333333333333,1.0,1.0,0.0,1.0,-0.010967826755692607,-0.010754167759428647,0.5918015863336236,0.9991152268510559,-0.028493217540660566,-0.018489452607094174,-0.024800005733591656,-0.031784173015479415,-0.010179137062866586,0.004047095464865891,-0.046588269851788724,-0.027922931590669546,-0.04033853950140708,0.12628190602527795,0.484396488202341,-0.8859003977629452,0.2619125075625177,0.6116827046697105,-0.7617701426395673,0.01426582010435199,-0.5950583918749152,1.4063895518615703,0.03608441999340331,-0.5153577296262783,1.024210213233503,0.10129405255312085,-0.07602696591580527,0.12404299446580724,0.08364128136099769,-0.1098982889016642,0.13246733622900075,-0.19255604801247567,0.04019546562752607,1.2889286022720148,0.03199419176944829,-0.07171587478602914,0.03857214302683154,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1916666666666667,1.0,1.0,0.0,1.0,-0.011238208102430798,-0.010823984869038865,0.5918299046448431,0.9991033420627917,-0.028686945989069325,-0.018605538237634146,-0.024968081447243863,-0.03189738213330417,-0.01020550270073667,0.004072763639162745,-0.04659092003328727,-0.027861955548977153,-0.04027808753355548,0.12712586349276275,0.48376100020946694,-0.8848652894962631,0.262609412060429,0.6107652510379131,-0.7606649442948901,0.012617486623244878,-0.5944877076456184,1.416899853489578,0.03635158994245641,-0.5159562324746044,1.0245309289389586,0.101255488642496,-0.07646779166217144,0.12437289976457322,0.08361539765929571,-0.11027424427952015,0.13277878044529734,-0.2030535373779638,0.09676000944725205,1.233159106912236,0.032122799321688544,-0.07190581299531651,0.0383940394051141,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2,1.0,1.0,0.0,1.0,-0.011509512940318474,-0.010893857451249555,0.5918583729678523,0.9990913886077745,-0.028880679256148574,-0.018721362078849727,-0.025135918671933884,-0.031993352011839456,-0.010230187646878677,0.004096944390106262,-0.046592460061624624,-0.027801382329579002,-0.04022157808775394,0.12796949750265288,0.48312202500797147,-0.8838275161002023,0.263306097523506,0.6098448005983852,-0.759557162965479,0.010881594481385927,-0.5934457250507943,1.426942203643441,0.03661979998209812,-0.516556159842867,1.0248501138902548,0.1012163211896816,-0.07686037698062864,0.12468089668972393,0.08358860680094726,-0.11061488485641258,0.13308683754494677,-0.21356092730975332,0.1532709962695744,1.1766197532522549,0.03224326168009148,-0.07205484491876524,0.0382040715350529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2083333333333333,1.0,1.0,0.0,1.0,-0.011781586375517952,-0.010963778238658116,0.5918869830113175,0.9990793663603651,-0.029074412106579642,-0.018836926561169153,-0.025303534696436127,-0.03206949887606847,-0.010253079052347253,0.004119136296888417,-0.046593187672578903,-0.027742058526346237,-0.04016933895867483,0.12881280217925745,0.48247999392645646,-0.8827872745514344,0.26400255550711144,0.6089216696236396,-0.7584468303358076,0.00905813783474899,-0.5919331910411255,1.436510182710449,0.0368889776371246,-0.5171571465565838,1.0251676634645428,0.10117675369930579,-0.07719708198634212,0.12496394537765187,0.08356115666681485,-0.1109143851716543,0.13339132363372252,-0.2240590535035337,0.20965507372128434,1.1193118191812124,0.03235500732721247,-0.07215706958802137,0.038002700449486504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2166666666666666,1.0,1.0,0.0,1.0,-0.012054251033361683,-0.011033741853540193,0.5919157208884495,0.9990672746313923,-0.02926814254491536,-0.018952240751008723,-0.02547094743209555,-0.03212398073312904,-0.01027369771020806,0.004139581372965629,-0.0465922114245415,-0.027683065544931166,-0.0401221980975397,0.12965577673097464,0.48183540697486577,-0.8817447836772414,0.2646987834679529,0.607996227512191,-0.7573339742382503,0.007147276922993699,-0.5899514738221062,1.4455974006297945,0.03715905010421833,-0.517758777669334,1.0254834922310796,0.10113595750860849,-0.07747311279165503,0.12521901700923488,0.0835320981143306,-0.11116935426948249,0.13369078702340165,-0.23452865594147784,0.2658315823751578,1.0612400462275051,0.032455878190123244,-0.07220803187701019,0.03778649932789424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.225,1.0,1.0,0.0,1.0,-0.01232732109136778,-0.011103734697712116,0.5919445832883083,0.9990551139405519,-0.02946185759242061,-0.01906729985087452,-0.02563818115295444,-0.03215499892527098,-0.010291749038917854,0.004158207712862331,-0.04658923420020664,-0.027624138384581068,-0.04008071244873747,0.1304984014710676,0.4811887753799289,-0.8807002909346138,0.2653947571423503,0.6070688470524815,-0.7562186505520843,0.005149326902391026,-0.5875026646682062,1.4541975168142407,0.03742990894029332,-0.518360613754534,1.025797438453341,0.10109367519594903,-0.07768330648900923,0.12544296329450422,0.0835011216473458,-0.11137592693345688,0.13398384221567472,-0.2449486630941125,0.3217163584990579,1.00241326493828,0.03254461306583384,-0.0722036903961687,0.037553934303868886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2333333333333334,1.0,1.0,0.0,1.0,-0.012600588932862427,-0.011173748434477285,0.5919735562636677,0.9990428836920457,-0.02965555263791428,-0.019182110936583476,-0.025805258418356937,-0.03216039222026328,-0.010307248632207928,0.004174339175471131,-0.04658489799328418,-0.027566598396381994,-0.040045060110108555,0.1313406713175738,0.48054068520004894,-0.879654067622333,0.266090468828742,0.6061399620633,-0.7551009102013224,0.0030647992047584905,-0.5845895345137886,1.4623042883787658,0.037701460321982225,-0.5189621725092701,1.026109391136144,0.10105050781129554,-0.07782076318559428,0.12563316108324285,0.08346889360165699,-0.11152870985781549,0.1342704019142582,-0.25529620375388024,0.37722423179515685,0.9428450093573959,0.032621258360086,-0.07213949859534052,0.0373073583950978,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2416666666666667,1.0,1.0,0.0,1.0,-0.012873832361384242,-0.011243772612650206,0.5920026269512997,0.999030583498509,-0.029849220273870283,-0.019296680136540567,-0.025972204746203147,-0.03213853533996726,-0.01031989550842384,0.004187920450957254,-0.04657880106588427,-0.027510401347715815,-0.04001586519078651,0.13218257660125585,0.479891762660169,-0.8786064049165597,0.26678590536904456,0.605210035221518,-0.75398081052018,0.0008943901731596885,-0.5812155941382869,1.4699116003035306,0.03797359657962809,-0.519562938731123,1.026419227759926,0.10100611278790639,-0.07788079423515892,0.12578729890051266,0.08343499900478779,-0.11162426172004469,0.13454969342510337,-0.26554847426827866,0.43226506862166447,0.8825524863727274,0.032684418915087526,-0.0720118335377018,0.037045969640776555,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.25,1.0,1.0,0.0,1.0,-0.013146816399117876,-0.011313795762109852,0.5920317815418711,0.9990182129045164,-0.030042852433881613,-0.019411014424863038,-0.026139047834618068,-0.03208803047039771,-0.010329467085614658,0.004198769534367963,-0.046570809770369405,-0.02745576769086076,-0.03999364902471429,0.13302410653070557,0.4792426719627963,-0.8775576126406578,0.26748105214548845,0.6042795577012993,-0.752858415310904,-0.0013610086997128204,-0.5773851167034275,1.477013496484978,0.038246200637233684,-0.5201623697348985,1.0267268239634904,0.1009603905245876,-0.07785913195456295,0.1259033063398074,0.08339929617429243,-0.11165937549000304,0.1348209869396766,-0.275681553442164,0.4867461350678304,0.8215568960612751,0.03273302955910759,-0.07181771344205723,0.03676978380345641,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2583333333333333,1.0,1.0,0.0,1.0,-0.013419295259058172,-0.011383805569809754,0.592061005145378,0.9990057713764826,-0.030236440553046393,-0.01952512194959413,-0.02630581745574798,-0.032007725768246835,-0.010335766858161092,0.004206704179533822,-0.046560817115795676,-0.027402976286550498,-0.039978907861692566,0.13386524977666564,0.47859411046092626,-0.8765080164775629,0.2681758936386161,0.6033490456300179,-0.7517337940711853,-0.003700302384209711,-0.5731031585538231,1.4836042152378852,0.03851914707227988,-0.520759900621824,1.0270320574899836,0.10091329168391172,-0.07775213589063079,0.12597946113393155,0.083361690971544,-0.11163130873569571,0.13508364287577734,-0.2856705680783475,0.5405724828352043,0.7598836399187059,0.03276613295666489,-0.07155479298078138,0.03647920984901187,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2666666666666666,1.0,1.0,0.0,1.0,-0.013691014482842661,-0.01145378895894205,0.5920902817966074,0.9989932582985187,-0.030429975645737666,-0.019639012181607438,-0.026472545341163972,-0.031896736364006036,-0.010338619932845584,0.004211554125265158,-0.04654873190032043,-0.027352335256430597,-0.0399721092364506,0.13470599472543743,0.4779468030312858,-0.8754579549550923,0.26887041366168085,0.6024190358890377,-0.7506070212629744,-0.006122184834351945,-0.5683755753228408,1.4896782238169564,0.0387923028531781,-0.5213549496179115,1.0273348107943072,0.1008647940530788,-0.07755687765803154,0.12601441585775364,0.08332211441451909,-0.11153785120534776,0.13533710919298558,-0.2954897875756489,0.5936475321483892,0.6975622354374966,0.03278286041048656,-0.07122138834950498,0.03617494992634196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.275,1.0,1.0,0.0,1.0,-0.01396171326607376,-0.011523732153862308,0.5921195945007038,0.9989806729702831,-0.030623448370139795,-0.01975269600128049,-0.02663926505073407,-0.031754466537987414,-0.010337874376603464,0.00421316607641555,-0.04653447737098153,-0.027304170572727816,-0.03997368689511124,0.1355463296775503,0.4773014958332924,-0.874407776213267,0.26956459554552475,0.6014900814432621,-0.7494781755846356,-0.008625132177137193,-0.5632090330180166,1.4952302524951768,0.03906552807912132,-0.5219469237609824,1.0276349733220893,0.10081489910968855,-0.07727121248770286,0.12600722640959683,0.0832805198001263,-0.11137737950800419,0.13558092468115124,-0.30511270382501915,0.6458736953517885,0.634626259742368,0.032782437045883184,-0.07081652083492429,0.035857971911026354,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2833333333333332,1.0,1.0,0.0,1.0,-0.014231126969534045,-0.011593620750149879,0.5921489253027403,0.9989680146060982,-0.03081684909344427,-0.019866185751120972,-0.026806011818347953,-0.03158063090873961,-0.010333403957061074,0.004211407492424183,-0.04651799182844011,-0.02725881881081748,-0.03998403458410536,0.13638624304393224,0.47665894948982407,-0.8733578345149323,0.2702584223250163,0.6005627462305709,-0.7483473391849552,-0.011207396564768931,-0.5576110137336443,1.5002553281459958,0.03933867680394282,-0.5225352249651602,1.027932443659491,0.10076363225527685,-0.07689384634706697,0.12595738284694624,0.08323688344534341,-0.11114890827143453,0.1358147274496635,-0.3145121143314067,0.6971530416611937,0.5711132779644323,0.03276419326728286,-0.07033996001240661,0.035529495154111856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2916666666666667,1.0,1.0,0.0,1.0,-0.01449898980204604,-0.011663439794835776,0.5921782553792327,0.9989552823352624,-0.031010167961058228,-0.019979495260071586,-0.02697282237098987,-0.03137527328278419,-0.010325111169657137,0.004206170149001696,-0.04649922967800574,-0.0272166206340598,-0.04000349928357585,0.13722572354847157,0.47601993172750795,-0.8723084864991513,0.2709518769362805,0.5996375996387382,-0.7472145967938079,-0.013867000749327304,-0.5515898156569967,1.5047488071279174,0.03961159796690937,-0.5231192564278558,1.0282271315746578,0.10071104356984384,-0.07642439706989523,0.1258648386513861,0.0831912060065787,-0.11085213686991446,0.136038265157028,-0.32366021378414983,0.7473879997062749,0.5070647445344312,0.032727577823732784,-0.06979226106116121,0.035190976194448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3,1.0,1.0,0.0,1.0,-0.01476503765054066,-0.011733173878044924,0.5922075651514495,0.9989424752036161,-0.031203394970421156,-0.020092639839571883,-0.027139734719991735,-0.031138782030341736,-0.010312930189603964,0.004197373546040716,-0.04647816252250376,-0.027177914170135715,-0.04003237433112543,0.13806476043676297,0.47538520953865915,-0.8712600872040759,0.27164494242512593,0.5987152106160724,-0.7460800347656714,-0.016601733461171428,-0.545154547071873,1.5087064072215697,0.039884136434338364,-0.5236984293161796,1.0285189599293985,0.10065720841678338,-0.07586344649445187,0.125730035722047,0.08314351371937923,-0.11048748942459552,0.1362514050899044,-0.33252869590881784,0.7964820926778704,0.4425258730024417,0.03267217084768015,-0.06917479328172105,0.034844091231600594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3083333333333333,1.0,1.0,0.0,1.0,-0.015029011023931144,-0.011802807236081502,0.5922368344201687,0.9989295921764225,-0.03139652004916236,-0.020205636250300408,-0.027306787924818585,-0.03087190098451302,-0.010296829575593008,0.0041849680769773055,-0.04645478016158968,-0.027143028144918455,-0.04007089274480692,0.1389033436887513,0.4747555409526004,-0.8702129859037838,0.2723376021649368,0.5977961414816616,-0.7449437400423095,-0.019409145681140934,-0.5383151141123655,1.5121242383446247,0.04015613414770404,-0.5242721696492179,1.0288078664285178,0.10060222773053462,-0.07521258066040315,0.12555392321922598,0.08309385938306324,-0.11005614581609757,0.136454143140472,-0.34108886636762453,0.8443406995011848,0.3775454719250737,0.03259769608114596,-0.06848975755435749,0.03449071453734742,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3166666666666667,1.0,1.0,0.0,1.0,-0.015290658069474217,-0.011872323865425922,0.5922660425209441,0.9989166321426189,-0.03158953313698546,-0.02031850263867022,-0.027474021830803556,-0.030575734993386897,-0.01027681460519734,0.004168937847618511,-0.046429091436066335,-0.02711227485073434,-0.040119220976710876,0.13974146423227188,0.47413166652765243,-0.8691675218170888,0.2730298400815103,0.5968809415191374,-0.7438057990466636,-0.022286547900631837,-0.5310822020801866,1.5149988317536542,0.04042743136902413,-0.5248399252754189,1.0290938051716876,0.10054622791699663,-0.07447441542236533,0.12533796879412362,0.08304232301061698,-0.10956006168327148,0.13664661109661136,-0.34931176704348665,0.8908718341382316,0.3121757452023566,0.03250403177633879,-0.06774019085540761,0.03413289270020048,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.325,1.0,1.0,0.0,1.0,-0.015549737613554293,-0.011941707646730646,0.592295168498269,0.9989035939204498,-0.03178242427047638,-0.020431258442718647,-0.027641476783081185,-0.030251749405124404,-0.010252929141886552,0.004149303032659748,-0.04640112487893119,-0.027085943098826774,-0.040177453287763856,0.14057911415403457,0.473514300695561,-0.8681240197572151,0.2737216408817804,0.5959701404536071,-0.7426662965240326,-0.025231008465199045,-0.5234672502100617,1.5173271674313307,0.04069786801064302,-0.5254011728301413,1.0293767479735212,0.10048936031681444,-0.07365260523314876,0.12508416102229747,0.08298901208491305,-0.10900197568041392,0.13682908181051,-0.3571683117900495,0.935986933892321,0.2464720559040856,0.03239121986483559,-0.06692995632623822,0.03377281491114825,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3333333333333333,1.0,1.0,0.0,1.0,-0.0158060221734297,-0.012010942477579112,0.5923241912963774,0.9988904762644738,-0.0319751836699008,-0.020543924267775966,-0.027809193319677385,-0.029901762940510588,-0.01022525694670854,0.004126121664179304,-0.04637092914510047,-0.027064291336596994,-0.04024560691006639,0.14141628690421879,0.47290412310709995,-0.8670827858000505,0.27441299028292554,0.5950642419244638,-0.7415253143498217,-0.02823935309713266,-0.515482419848648,1.5191066993520557,0.04096728503343806,-0.5259554245475229,1.0296566854202067,0.10043180019090381,-0.07275183331560964,0.12479500212125405,0.08293406137199644,-0.10838540261347118,0.13700197189216112,-0.3646294335180463,0.9796016464852375,0.18049265330839503,0.0322594730523211,-0.06606371782049925,0.03341277971541157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3416666666666666,1.0,1.0,0.0,1.0,-0.016059300882646857,-0.012080012412480872,0.5923530899637518,0.998877277873895,-0.03216780182696366,-0.020656521733115562,-0.027977211847335395,-0.029527933606151514,-0.010193922361219833,0.004099490758782433,-0.046338573198526745,-0.02704754112316994,-0.0403236181431173,0.14225297749054963,0.47230177014030084,-0.8660441030551942,0.27510387523798036,0.5941637170767159,-0.7403829303258299,-0.031308165690499816,-0.5071405561019744,1.520335378319804,0.04123552589484837,-0.5265022347938163,1.0299336276354447,0.10037374519934306,-0.07177778198335094,0.12447349032307597,0.08287763225127032,-0.10771461148522787,0.13716584164935153,-0.37166624227366,1.0216366047471215,0.11429836361927848,0.03210917955002307,-0.06514689833817977,0.0330551588300132,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.35,1.0,1.0,0.0,1.0,-0.01630938227075222,-0.012148901808313397,0.5923818438678478,0.9988639974021407,-0.0323602695924363,-0.02076907329163474,-0.028145572304195392,-0.029132737521397653,-0.010159090303975594,0.004069546705445274,-0.04630414624149563,-0.027035871159857817,-0.04041133950946926,0.14308918265754117,0.47170782674071077,-0.8650082276279992,0.27579428415378004,0.59326899839971,-0.7392392169889992,-0.03443379046836033,-0.4984551431028626,1.5210116720790436,0.04150243802593844,-0.5270412061864925,1.0302076047340403,0.1003154133583406,-0.07073708247862132,0.12412309159392398,0.08281991153578638,-0.10699458794000805,0.13732139207098815,-0.3782501937321886,1.0620181770435266,0.047952245641886826,0.031940905211256115,-0.06418562227895386,0.03270235877441685,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3583333333333334,1.0,1.0,0.0,1.0,-0.016556096837776493,-0.012217595473195281,0.5924104329159958,0.9988506334675694,-0.03255257826251919,-0.020881602025453243,-0.028314313813891167,-0.028718940768342072,-0.010120965541242338,0.004036464856296726,-0.0462677573769831,-0.027029412064835286,-0.040508538071482775,0.14392490104652197,0.47112281876565715,-0.8639753848619621,0.27648420709691013,0.5923804739443824,-0.7380942404579801,-0.03761233558603629,-0.48944025315124895,1.5211345824138354,0.04176787431503597,-0.5275719951651322,1.0304786669483517,0.10025704047640582,-0.06963724436368612,0.12374770074726982,0.08276110976913387,-0.10623098110599694,0.13746945874342442,-0.38435326727561253,1.1006791811099215,-0.018480786446319897,0.03175539290684093,-0.0631866419994287,0.03235678117837093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3666666666666667,1.0,1.0,0.0,1.0,-0.016799299365845257,-0.012286078816591635,0.5924388377780639,0.9988371846651656,-0.03274471966279543,-0.02099413142109614,-0.02848347433596752,-0.0282895646181983,-0.01007979121321036,0.004000458286885873,-0.046229535001092205,-0.02702824206552151,-0.04061489498361755,0.14476013333214793,0.470547206001316,-0.8629457659488781,0.2771736359832656,0.5914984820479434,-0.7369480593432755,-0.040839678256287204,-0.4801104900843639,1.520703658971605,0.04203169457438579,-0.528094316886483,1.0307468844203465,0.1001988770883333,-0.06848656520040297,0.12335159236790627,0.08270145900152848,-0.10543003536926943,0.13761100269060078,-0.38994815254748866,1.1375595488079293,-0.08493437020405281,0.031553559045148366,-0.062157249722729624,0.0320207827183161,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.375,1.0,1.0,0.0,1.0,-0.017038870914203846,-0.01235433799832009,0.5924670401061609,0.9988236495790451,-0.0329366862286458,-0.021106685128626193,-0.028653090317744066,-0.027847844730633585,-0.010035846619300855,0.003961775718090334,-0.046189625928902016,-0.027032383758293865,-0.04073000632448141,0.14559488233132753,0.4699813760123171,-0.8619195249891637,0.2778625647469356,0.5906233066882279,-0.7358007237464701,-0.04411147146182777,-0.47048092733778346,1.5197190095771012,0.042293766965788446,-0.5286079493271777,1.0310123466603236,0.10014118492371271,-0.06729402196112066,0.12293936233829461,0.08264121006510194,-0.10459850815462524,0.13774709823055176,-0.3950084430878441,1.1726069294985397,-0.1513411279981991,0.03133648721949017,-0.06110517639801749,0.03169663568195702,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3833333333333333,1.0,1.0,0.0,1.0,-0.017274720449904673,-0.012422360074050709,0.5924950227465405,0.9988100267955735,-0.03312847108103699,-0.02121928670966257,-0.028823196352845633,-0.02739718515402089,-0.009989444289339221,0.003920698621219984,-0.04614819426290365,-0.027041802052613244,-0.040853385220662994,0.14642915308087648,0.46942563896863065,-0.8608967765765732,0.27855098948435064,0.5897551735786997,-0.7346522743727663,-0.04742315230775127,-0.46056704125938824,1.5181813068383017,0.04255396936137729,-0.5291127364931166,1.0312751616817124,0.10008423296506863,-0.06606914630143068,0.12251586112438373,0.08258062938397703,-0.10374357531927947,0.13787891805431496,-0.3995088353529311,1.2057772202698203,-0.21763312126930057,0.031105419045668187,-0.060038479620483365,0.031386490167299996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3916666666666666,1.0,1.0,0.0,1.0,-0.017506786074226077,-0.012490133134878218,0.5925227699388925,0.9987963149168795,-0.03332006809665764,-0.021331959379640542,-0.028993824851581727,-0.026941108163104032,-0.009940926390355286,0.003877537556461066,-0.046105420018982775,-0.02705640337878106,-0.040984465241555273,0.14726295288074534,0.4688802235739599,-0.859877593970424,0.2792389085700019,0.5888942470995733,-0.7335027417788982,-0.05076995205104329,-0.45038464033328646,1.5160917908892795,0.04281219061654958,-0.5296085906541858,1.0315354548297786,0.10002829316786421,-0.06482188645719478,0.12208612031318733,0.08251999537269517,-0.10287272625024935,0.13800771583254434,-0.4034253311271728,1.237035012174117,-0.28374232043307135,0.030861742331871195,-0.05896542317536335,0.031092338893934368,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4,1.0,1.0,0.0,1.0,-0.0177350358143595,-0.012557646438594128,0.5925502674984077,0.9987825125745315,-0.03351147197146378,-0.02144472574991269,-0.029165005728189,-0.026483201145641577,-0.009890660540665855,0.0038326278232003828,-0.04606149752985426,-0.027076036195739776,-0.04112260501231483,0.14809629130034088,0.4683452741943441,-0.8588620079046867,0.27992632274056223,0.5880406281411955,-0.7323521457755572,-0.054146907826537485,-0.4399497910564863,1.5134522681644171,0.043068331733575146,-0.5300954935460394,1.0317933673299446,0.09997363593024666,-0.06356245907017222,0.12165527417823174,0.08245959449128537,-0.10199365118093162,0.13813480675676226,-0.40673544105132897,1.2663539429216353,-0.34960108418195635,0.030606976797473706,-0.05789435113463082,0.03081598553023479,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4083333333333332,1.0,1.0,0.0,1.0,-0.01795946796067353,-0.012624890530397483,0.5925775029763695,0.9987686184431448,-0.033702678276795996,-0.021557607575343092,-0.029336766109658415,-0.026027061881076098,-0.009839035122488494,0.003786324526526632,-0.0460166336503477,-0.027100492790119356,-0.04126709396200469,0.14892918014624945,0.4678208492561237,-0.8578500060674534,0.28061323514485664,0.5871943529132244,-0.7312004949996188,-0.05754887606856544,-0.42927874128459254,1.5102651061529135,0.04332230689650748,-0.5305734965064296,1.0320490545886158,0.0999205254139901,-0.062301194676236404,0.1212284782779971,0.0823997170391455,-0.10111412357392657,0.13826154649998923,-0.40941838673241876,1.2937169481221178,-0.4151426414100712,0.03034275762590022,-0.0568335596984193,0.030559017334299554,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4166666666666667,1.0,1.0,0.0,1.0,-0.018180110941554178,-0.01269185735095377,0.5926044657955456,0.9987546312536778,-0.033893683507349434,-0.021670625512905186,-0.029509130070462637,-0.02557624363487009,-0.009786454200805142,0.0037389971870400726,-0.04597104579245079,-0.02712951231287794,-0.04141715909748539,0.14976163339057405,0.46730692094974013,-0.8568415332667201,0.2812996513578813,0.5863553927482967,-0.730047786667224,-0.06097054760541113,-0.41838784192111766,1.506533224140916,0.04357404436067348,-0.531042719541013,1.0323026842855163,0.09986921482844968,-0.061048380875076136,0.12081082723987668,0.08234065278123759,-0.10024188064338357,0.1383893091490429,-0.4114552986803792,1.3191164051319748,-0.4803015686300549,0.030070817193730004,-0.055791170110373045,0.03032278276489997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.425,1.0,1.0,0.0,1.0,-0.018397022739965584,-0.012758540329935468,0.5926311473573196,0.9987405498061966,-0.034084485120402935,-0.021783798896462085,-0.029682118397000315,-0.0251342015160314,-0.009733332168682223,0.0036910240379728117,-0.04592495982088161,-0.027162784957189788,-0.04157197267131227,0.15059366706005695,0.4668033762415391,-0.8558364922801222,0.28198557935787727,0.5855236549025014,-0.7288940065138014,-0.06440646437990509,-0.4072934678657263,1.5022600800090793,0.043823487183069644,-0.5315033493416025,1.0325544343013642,0.09981994179586562,-0.05981410732342485,0.12040727394218464,0.08228268650835258,-0.09938450519310749,0.13851946470329057,-0.4128294071479612,1.3425541657901885,-0.5450142555899884,0.02979296536254783,-0.05477500598566776,0.03010837455828419,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4333333333333333,1.0,1.0,0.0,1.0,-0.018610289867989502,-0.012824934463449815,0.5926575411182632,0.9987263729818897,-0.03427508156584899,-0.021897145532403493,-0.029855748384995634,-0.024704241510513245,-0.00968008824706392,0.0036427861652093725,-0.04587860784178724,-0.02719995714361176,-0.04173066059496757,0.1514252990871718,0.4663100191610164,-0.8548347453676837,0.28267102946635386,0.5846989843284116,-0.7277391289221692,-0.06785103772454382,-0.39601193915794786,1.4974496532144161,0.044070593783382614,-0.5319556363074408,1.0328044905281544,0.0997729239191919,-0.05860811665142185,0.1200225522826881,0.08222609363830236,-0.0985493119184544,0.13865335675000034,-0.4135262228429565,1.3640414767458575,-0.6092193518624933,0.02951106875093923,-0.05379247826271971,0.029916618584557853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4416666666666667,1.0,1.0,0.0,1.0,-0.018820025927186457,-0.012891036374065983,0.5926836426347073,0.9987120997541414,-0.03446547230670113,-0.022010681520161317,-0.030030033672463985,-0.024289473510358612,-0.009627140969989748,0.0035946616509559687,-0.04583222591832999,-0.027240637547256964,-0.041892311437480664,0.1522565491253768,0.46582657429734875,-0.853836116408744,0.283356014251849,0.5838811663705271,-0.7265831172346348,-0.07129856809395436,-0.38455944325329533,1.4921064241447044,0.04431533832891863,-0.5323998906459811,1.0330530446111068,0.09972835467195074,-0.05743966518856336,0.11966110560177601,0.08217113596546977,-0.09774324116490263,0.1387922809262898,-0.41353370444742243,1.3835987886046341,-0.672858187476808,0.029227029418047307,-0.052850480732640204,0.02974806861067325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.45,1.0,1.0,0.0,1.0,-0.01902636979320314,-0.0129568443524905,0.5927094495747522,0.9986977291984965,-0.03465565782989392,-0.02212442110085553,-0.030204984110193674,-0.023892769512410643,-0.009574902784087003,0.003547019879531787,-0.045786051747371555,-0.027284403779214105,-0.04205598584364716,0.15308743833170432,0.46535269140787366,-0.8528403936076541,0.2840405483991117,0.5830699303089966,-0.7254259242400644,-0.07474326613200086,-0.3729519593478706,1.4862353500898027,0.04455771094035007,-0.5328364776529848,1.0333002916716656,0.09968639972351034,-0.056317397011653725,0.11932702262438699,0.08211805766419888,-0.09697276285371759,0.13893746474021418,-0.4128424099239633,1.401255457661893,-0.7358751611825953,0.028942763390258364,-0.0519552987255123,0.029603006913032637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4583333333333333,1.0,1.0,0.0,1.0,-0.019229483472208157,-0.0130223583802902,0.5927349616980525,0.998683260501373,-0.034845639647324345,-0.022238376536478758,-0.030380605671026076,-0.023516727968073414,-0.009523774884192964,0.003500216154915781,-0.04574032233112661,-0.02733080952085498,-0.04222072620590171,0.15391798912076865,0.4648879510138212,-0.8518473326983376,0.2847246485462523,0.5822649536562985,-0.7242674928222979,-0.07817927492602042,-0.3612051856255971,1.4798418381249945,0.04479771771875627,-0.5332658122914063,1.0335464280596574,0.09964719380263054,-0.05524923431666884,0.11902398250839274,0.08206708164442356,-0.09624379289807194,0.1390900492733893,-0.4114456287167048,1.417049346444681,-0.7982180906689162,0.02866017944746113,-0.051112533056987264,0.02948145050464035,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4666666666666666,1.0,1.0,0.0,1.0,-0.0194295496841144,-0.01308758013341982,0.5927601808045564,0.998668692967414,-0.035035420287215145,-0.022352558021142444,-0.030556900398560842,-0.023163645037626225,-0.009474142395784818,0.0034545867649972816,-0.04569527167706462,-0.027379391905571992,-0.04238556642835,0.1547482248950815,0.4644318708359292,-0.8508566605658475,0.2854083330931854,0.5814658670940287,-0.7231077567521745,-0.08160069327727927,-0.34933447024045927,1.4729317152453207,0.045035380597807755,-0.5336883532039346,1.0337916491800763,0.09961083818809835,-0.05424228649395846,0.11875521024923064,0.08201840634847635,-0.09556162395708334,0.13925107321450358,-0.4093394921674856,1.4310263315589289,-0.8598385199799097,0.0283811585576578,-0.05032704078948402,0.029383162586209544,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.475,1.0,1.0,0.0,1.0,-0.01962676923289785,-0.013152512966663915,0.5927851106541688,0.9986540260253972,-0.035225003276006105,-0.02246697362502963,-0.03073386639528583,-0.022835493250391258,-0.009426370000006285,0.0034104446073407826,-0.04565112855806746,-0.0274296789481192,-0.04254954162990335,0.15557816975723696,0.46398391290558855,-0.8498680791941837,0.28609162198539356,0.5806722599236804,-0.7219466416020561,-0.08500159979547851,-0.33735474676628163,1.4655111961253293,0.04527073702805057,-0.5341045963045644,1.0340361474360942,0.0995773988973736,-0.053302779580871595,0.11852344330919085,0.08197220306526032,-0.09493087183673588,0.13942145958153906,-0.406523059760672,1.4432397293452526,-0.9206919804347713,0.028107534310945204,-0.049602893764373324,0.029307668696403333,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4833333333333334,1.0,1.0,0.0,1.0,-0.019821358227482426,-0.013217161879442222,0.5928097568599753,0.998639259232654,-0.03541439311110003,-0.022581629270861464,-0.030911497849546835,-0.022533907809206836,-0.00938079807946641,0.003368075466579922,-0.04560811436341736,-0.027481196835055482,-0.04271169764495349,0.15640784821003773,0.463543491176248,-0.8488812698440277,0.2867745364776064,0.5798836858967498,-0.7207840657591489,-0.0883760776066238,-0.32528047475137173,1.4575868489047412,0.045503839502990175,-0.5345150681000075,1.0342801103250163,0.09954690562396895,-0.05243600702724671,0.11833090994189499,0.08192861382147254,-0.0943554382772338,0.13960200539544498,-0.40299837917741776,1.4537496515088255,-0.9807382025322076,0.027841074657564968,-0.048943355248045606,0.02925427692814342,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4916666666666667,1.0,1.0,0.0,1.0,-0.02001354521761277,-0.0132815334637453,0.5928341267582135,0.9986243922779725,-0.03560359522490321,-0.022696528741919474,-0.031089785100238927,-0.022260180517206234,-0.009337739443699993,0.003327735007410269,-0.04556644106936904,-0.02753347691043423,-0.04287110019351832,0.15723728485096977,0.46310997945513444,-0.8478958973618188,0.2874570988824181,0.5790996692857265,-0.719619941512132,-0.09171823944843548,-0.3131255859078012,1.4491655594164592,0.04573475493900998,-0.5349203188920318,1.03452371871823,0.09951935145206814,-0.051646301961446595,0.11817931927707415,0.08188774989351444,-0.09383849029232172,0.13979337446265783,-0.39877051857152207,1.4626223041492936,-1.039941277546066,0.027583465204152197,-0.048350874434321955,0.029222101506203302,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5,1.0,1.0,0.0,1.0,-0.020203568307933857,-0.013345635835257358,0.5928582292585911,0.9986094249829962,-0.03579261594070784,-0.022811673720002427,-0.03126871473762526,-0.02201526105927593,-0.009297476673141007,0.0032896465187341,-0.045526309356172245,-0.027586062217008468,-0.043026843607206634,0.1580665040675722,0.46268271947689055,-0.8469116145227431,0.288139332309165,0.5783197110585444,-0.7184541761847713,-0.09502225291614917,-0.3009034363488835,1.4402544942789735,0.04596356392305938,-0.5353209160072462,1.0347671453501197,0.0994946933540597,-0.05093703043387965,0.11806986284646159,0.08184969096525885,-0.09338245567308778,0.13999609331501572,-0.39384756996127285,1.4699292444386713,-1.0982697687514564,0.027336294269126177,-0.047827097985868594,0.029210088975499815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5083333333333333,1.0,1.0,0.0,1.0,-0.020391672310329446,-0.013409478548981014,0.592882074678796,0.998594357302141,-0.035981462421064675,-0.022927063851152125,-0.03144826973826968,-0.02179976515107835,-0.009260260100627428,0.003253999416952659,-0.04548790689614204,-0.027638513481728876,-0.04317805901218285,0.1588955297402041,0.4622610289479031,-0.8459280663143778,0.28882126039850575,0.5775432950245084,-0.7172866732902151,-0.09828236561445669,-0.2886267651671567,1.4308610632706016,0.04619035984349542,-0.5357174371917963,1.0350105535344882,0.09947285345359824,-0.05031060447192037,0.11800322688414022,0.08181448493741583,-0.09298903377433554,0.1402105502640416,-0.3882406231510932,1.4757466095598704,-1.1556967734089696,0.027101039845302544,-0.04737289730445626,0.02921704623522814,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5166666666666666,1.0,1.0,0.0,1.0,-0.02057810598968373,-0.013473072500899116,0.5929056745671559,0.9985791893210809,-0.03617014260938613,-0.023042696836559903,-0.03162842963170967,-0.02161398888346681,-0.009226306430820995,0.003220948491120859,-0.04545140683481211,-0.027690414465086327,-0.04332392188456546,0.1597243849584655,0.46184420940235854,-0.8449448940746741,0.2895029070581219,0.5767698938289721,-0.7161173336803706,-0.10149292996866739,-0.27630765952288566,1.420992881388824,0.04641524792048109,-0.5361104642956538,1.0352540961207068,0.09945372101511973,-0.049768513228509725,0.11797961443277938,0.0817821483768999,-0.09265922027012152,0.14043699743101268,-0.3819637101355011,1.48015433243755,-1.2121999377341686,0.02687905856736672,-0.04698840981136598,0.029241669670398984,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.525,1.0,1.0,0.0,1.0,-0.02076311945195332,-0.013536429817392013,0.592929041517376,0.9985639212538707,-0.03635866516560508,-0.023158568545781355,-0.03180917069618743,-0.021457928446511995,-0.009195797981133895,0.0031906138492481325,-0.045416966484788254,-0.027741376623823276,-0.04346365890709935,0.16055309175712276,0.46143155372742795,-0.8439617394071648,0.2901842962047874,0.575998974686673,-0.7149460566663649,-0.10464842745004838,-0.2639575262931975,1.410657730975032,0.04663834415295153,-0.5365005773553191,1.0354979146956615,0.09943715510101425,-0.049311370070318494,0.11799877605045195,0.08175266757761146,-0.09239334422201706,0.14067555553443079,-0.3750337204804033,1.4832353582929714,-1.2677614280516902,0.026671576736145425,-0.046673092208664446,0.029282574669320383,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5333333333333332,1.0,1.0,0.0,1.0,-0.02094696171613009,-0.013599563734272018,0.5929521889791148,0.9985485534387804,-0.03654703939679113,-0.02327467314921692,-0.03199046618049999,-0.021330810281490958,-0.009168746586048769,0.0031631323561069793,-0.045384525238107806,-0.027790817423984343,-0.04359677355016082,0.16138167087681574,0.4610223532345199,-0.8429782478071666,0.2908654515177488,0.5752300047586052,-0.71377274108813,-0.10774349197667411,-0.2515870702180028,1.3998635242546291,0.046859774199416844,-0.5368883491657982,1.0357421390318622,0.09942288792557818,-0.04893740731006013,0.11805875734159921,0.08172582472367518,-0.09218999824206264,0.14092556862921768,-0.3674702518483833,1.4850764752611385,-1.3223692099715967,0.026479392207126168,-0.046425216667245195,0.02933819205626964,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5416666666666667,1.0,1.0,0.0,1.0,-0.02112987018437348,-0.013662486661558396,0.5929751321522271,0.9985330868405319,-0.03673527342473928,-0.023391001521066455,-0.03217228841989123,-0.021232945741810796,-0.00914554861582625,0.003138404141541998,-0.04535465357363562,-0.02783892646571578,-0.04372212833739993,0.16221013988921573,0.4606159302722603,-0.8419940934514715,0.29154639328351534,0.574462474715972,-0.7125972971892113,-0.11077293164752143,-0.23920625170551188,1.3886182441421722,0.047079667356403634,-0.5372743309664398,1.035986884563266,0.09941089328433461,-0.048648442321023166,0.11816099763643617,0.08170190728212456,-0.09205022607097213,0.1411882020529931,-0.35929596908195305,1.4857618269187207,-1.3760119960061834,0.026303990091489232,-0.046243659923093094,0.029407167419037705,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.55,1.0,1.0,0.0,1.0,-0.021312099447560736,-0.013725217673207802,0.592997882748113,0.9985175208180747,-0.03692338154642591,-0.023507548853338407,-0.03235460122515923,-0.02116391308766409,-0.009126284844444436,0.003116525275465444,-0.04532740974146978,-0.027885390322298614,-0.043839196346727644,0.1630385190982213,0.46021154586250285,-0.8410088978465593,0.29222714997245086,0.573695834324089,-0.7114196043872468,-0.11373175812804,-0.2268243731026908,1.3769299909878594,0.047298174034275,-0.5376590768311831,1.0362322584888461,0.09940103801035605,-0.04844370931108455,0.11830458550082801,0.08168084010244048,-0.09197341153163618,0.14146344511646758,-0.3505350564328896,1.485377589334967,-1.428683970864122,0.02614626620027996,-0.04612724018507652,0.029488401410211473,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5583333333333333,1.0,1.0,0.0,1.0,-0.021493880103113566,-0.013787770301766707,0.5930204577055874,0.9985018567826158,-0.03711137240077766,-0.023624303215354317,-0.032537372674343944,-0.02112184906940806,-0.009110713950435528,0.0030976366159317366,-0.045302425424069766,-0.027929392924799828,-0.04394793076143128,0.163866823856055,0.45980853511707553,-0.840022350359791,0.292907740618556,0.5729295845237781,-0.7102395731039368,-0.11661518258806959,-0.2144499585499291,1.3648068446277701,0.047515438459741634,-0.5380431183028578,1.036478357920103,0.09939291070147849,-0.04831800445167955,0.11848515237534052,0.08166214001377958,-0.09195565142726903,0.14174952126154716,-0.34121399609402997,1.484014178028431,-1.4803869299277217,0.0260063304440232,-0.04607258216072996,0.02958019542043111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5666666666666667,1.0,1.0,0.0,1.0,-0.021675435669529432,-0.013850160865508103,0.5930428720308302,0.9984860955254365,-0.037299257063863354,-0.0237412530818142,-0.03272056641574909,-0.02110577503124049,-0.009098985266466469,0.003081573206622931,-0.045280015338022075,-0.027970969420837627,-0.04404760159326261,0.16469506760991262,0.4594062457883082,-0.8390341453069703,0.2935881856393472,0.5721632401336345,-0.709057112366221,-0.1194186580629405,-0.2020908034688836,1.352256875489064,0.04773161287500872,-0.5384269532005286,1.0367252617458533,0.09938628637200353,-0.048269192669886385,0.11870155823226147,0.08164582523451536,-0.09199502481075594,0.142046416906616,-0.33136230891155916,1.481758634074239,-1.531123809227375,0.025884888319999133,-0.046076212913115366,0.029680888924832338,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.575,1.0,1.0,0.0,1.0,-0.021856980573540533,-0.01391240611109506,0.593065140644937,0.998470237912104,-0.03748704692998333,-0.023858386456037696,-0.03290414449722744,-0.021114534836694294,-0.009091092048571605,0.0030682758620272726,-0.04526023403198127,-0.028010016460790554,-0.04413785298122244,0.16552326196225506,0.4590040485725774,-0.83804399105592,0.2942685043724646,0.5713963341102655,-0.7078721328221599,-0.12213788773659558,-0.18975398131535845,1.3392881144739806,0.04794685326507495,-0.538811055184743,1.0369730394021834,0.09938093813737503,-0.048294322358020114,0.11895197615868991,0.08163175727400551,-0.09208920022004685,0.14235383551089553,-0.32101085417797937,1.4786969451798133,-1.5809012110265241,0.025782312159950693,-0.04613512262994668,0.029789325344835582,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5833333333333333,1.0,1.0,0.0,1.0,-0.022038719122005345,-0.013974523062349902,0.5930872782695216,0.9984542848810151,-0.037674753581649977,-0.023975690791885,-0.03308806766457654,-0.021146869686581516,-0.009087000460347827,0.003057665885285425,-0.045243112655184416,-0.028046431311571536,-0.04421840070893098,0.16635141657886887,0.4586013404156745,-0.8370516123709921,0.2949487149272473,0.5706284201299671,-0.7066845484410395,-0.12476883896590682,-0.1774458543825534,1.3259085219719553,0.04816131807767456,-0.5391958719110277,1.0372217505016006,0.09937663344972203,-0.04839009431644725,0.11923436557661926,0.0816197843360611,-0.09223557999615384,0.14267133421538958,-0.3101920641846864,1.4749135851981416,-1.6297293115822065,0.025698830776034187,-0.046246116156616335,0.029904354273857514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5916666666666666,1.0,1.0,0.0,1.0,-0.02222084478048269,-0.014036528884712551,0.5931092992891352,0.9984382374354651,-0.03786238871146805,-0.024093153103987117,-0.033272295655236095,-0.021201556696308552,-0.009086644317995664,0.003049626735757888,-0.045228645800011985,-0.028080279393609932,-0.04428910874504467,0.1671795391864171,0.45819754700063664,-0.836056751629643,0.29562883411139895,0.5698590744436629,-0.7054942772519034,-0.12730775547300702,-0.16517208822872276,1.3121259592809438,0.04837516711134219,-0.5395818237873533,1.0374714453067477,0.09937309699799723,-0.048553218378252216,0.11954702352758861,0.08160971015329976,-0.09243158190756162,0.14299865073346574,-0.29894071953220247,1.4704917491648428,-1.6776218996468284,0.02563435713063625,-0.04640608398707835,0.030025149874699508,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6,1.0,1.0,0.0,1.0,-0.022403541426235653,-0.014098440525188131,0.5931312172107398,0.998422096417883,-0.03804996390694827,-0.02421076130797162,-0.033456788071894714,-0.02127714744623478,-0.009089948064728013,0.0030440667633242434,-0.0452168417649807,-0.028111382846138552,-0.04434981946789551,0.16800763486216883,0.4577921201093703,-0.8350591619788656,0.2963088767631356,0.569087893764841,-0.7043012375954817,-0.12975118429144353,-0.15293765856313934,1.2979481569778415,0.04858855736318517,-0.5399693066441457,1.037722169666179,0.0993701913080719,-0.04877975403594137,0.11988736897105001,0.08160143242200268,-0.09267416703019782,0.14333501376169622,-0.28729058952888964,1.465510564924234,-1.7245948215361162,0.02558897961283335,-0.0466115293743008,0.030150475482044747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6083333333333334,1.0,1.0,0.0,1.0,-0.022586978356882285,-0.01416027515985536,0.5931530458152319,0.9984058631544052,-0.03823749093012656,-0.02432850085303495,-0.033641503422406106,-0.021372192117033333,-0.009096837287254356,0.0030408750943046892,-0.04520771657115317,-0.028139616755318442,-0.04440033564046939,0.16883570904155162,0.4573845511000376,-0.8340586288134588,0.296988857985099,0.5683145049931596,-0.7031053603558751,-0.13209593196515518,-0.1407469121466522,1.2833827122553418,0.04880165010488941,-0.5403586826102583,1.0379739532314485,0.09936772071202915,-0.04906573615315213,0.12025283703301026,0.08159481510111477,-0.09296023285620514,0.14367965643692138,-0.275276555064104,1.4600474368932659,-1.770667626359561,0.025562811590604667,-0.04685896681076773,0.03027926026995864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6166666666666667,1.0,1.0,0.0,1.0,-0.022771315244688877,-0.014222049828322899,0.5931747977140172,0.9983895387230578,-0.038424981523131146,-0.02444635851296027,-0.0338263997310186,-0.021485405364633406,-0.009107190994176624,0.0030398903754026824,-0.04520122043663214,-0.02816516674691439,-0.04444068871502259,0.16966376354070264,0.4569743578401511,-0.8330549480283155,0.2976687903481542,0.567538556550571,-0.7019065766548663,-0.13433912687584526,-0.12860353461491825,1.2684370298718488,0.04901460422302858,-0.5407502894243251,1.0382268240040116,0.09936539362900787,-0.04940752553501904,0.12064168169643175,0.081589626527524,-0.09328694589787245,0.14403226654955636,-0.2629360481801296,1.4541783854330657,-1.8158632669141062,0.025555466759149548,-0.047145293443391356,0.03041107888166472,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.625,1.0,1.0,0.0,1.0,-0.022956699821058704,-0.014283780950023717,0.5931964847774572,0.9983731242837708,-0.03861244708325498,-0.02456432126243158,-0.03401143570949801,-0.021615417687805737,-0.00912086579535034,0.003040966215757894,-0.04519728956658676,-0.028188098254832678,-0.04447101209270203,0.17049179893536842,0.45656109234112063,-0.8320479341185183,0.29834868509389106,0.5667597225615284,-0.7007048225800492,-0.136478199434824,-0.11651060572276777,1.25311832447344,0.04922757455087524,-0.5411444375009815,1.0384808045461429,0.09936305713181215,-0.049801179731971956,0.1210517712716963,0.08158571703344886,-0.09365131390886905,0.14439227764589724,-0.2503055496752238,1.4479749390830354,-1.8602061459456953,0.025566510719335495,-0.04746733698443917,0.030545351040269786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6333333333333333,1.0,1.0,0.0,1.0,-0.023143268777637453,-0.0143454845437079,0.5932181180181934,0.9983566210085665,-0.03879989882780239,-0.024682376443485705,-0.03419657047734411,-0.021760947043737808,-0.009137727567975686,0.00304394710996411,-0.0451958719103083,-0.028208521255947337,-0.044491438246963604,0.1713198144928995,0.4561443381779516,-0.8310374185071205,0.29902855229871167,0.5659777013187565,-0.6995000386941014,-0.138510886037099,-0.10447061896353432,1.2374335941060872,0.0494407127350175,-0.5415414117073991,1.038735913188016,0.09936056103439672,-0.050242977433644365,0.12148114870680349,0.08158294751443473,-0.09405049586272751,0.14475917754660506,-0.23742178021785076,1.4415058720128195,-1.9037233924630481,0.02559551438291549,-0.047822133891546326,0.030681656809328217,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6416666666666666,1.0,1.0,0.0,1.0,-0.023331148318964018,-0.014407176113161967,0.593239707512682,0.9983400300696,-0.03898734773706622,-0.02480051196547445,-0.03438176381906101,-0.021920786073431398,-0.009157632803801444,0.0030486725462751086,-0.04519690375512441,-0.028226587152563536,-0.04450216141530874,0.1721478082859417,0.4557237093838932,-0.8300232483067382,0.2997084008857983,0.5651922142971496,-0.6982921696209391,-0.14043522910512152,-0.09248550785588744,1.2213896012657226,0.04965416645725716,-0.5419414730658406,1.038992165492965,0.09935777413330682,-0.05072935185012284,0.12192801363582362,0.08158118538543868,-0.09448178566620502,0.14513250447030668,-0.2243213418541179,1.4348367804762718,-1.9464443453412539,0.02564196373611549,-0.048206939711661345,0.030819746732904107,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.65,1.0,1.0,0.0,1.0,-0.0235204548326529,-0.01446887056402099,0.5932612623385234,0.9983233526275463,-0.03917480451356472,-0.024918716473905766,-0.03456697642422416,-0.022093815198346453,-0.009180432739653799,0.003054979076084809,-0.04520031323744711,-0.028242483643534298,-0.04450343237629485,0.1729757773951213,0.45529884898044953,-0.8290052849465235,0.3003882387218023,0.5644030048909864,-0.6970811636195963,-0.14224957506800096,-0.08055667262226313,1.2049928550170663,0.049868078797286094,-0.5423448607025935,1.0392495756335645,0.0993545915436983,-0.05125693214717564,0.12239073901944009,0.0815803119063796,-0.09494264339590996,0.14551185093813812,-0.2110404825218981,1.428030063589726,-1.988400434055988,0.025705275838114466,-0.048619257017612494,0.030959535412162786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6583333333333332,1.0,1.0,0.0,1.0,-0.023711295665497074,-0.014530582138607959,0.5932827905222497,0.9983065898203198,-0.039362279553851444,-0.02503697950545349,-0.03475217010334127,-0.02227901418099962,-0.009205976357434845,0.0030627019411456546,-0.04520602298239425,-0.02825643235334812,-0.044495552456405456,0.17380371814500334,0.4548694271814403,-0.8279834026564142,0.30106807275090464,0.5636098369072178,-0.6958669721053035,-0.14395257048048649,-0.06868500679605867,1.1882495940314561,0.05008258772122574,-0.5427517940161342,1.0395081577498344,0.09935093767972192,-0.05182257976282911,0.1228678875569944,0.08158022573394708,-0.09543072239206252,0.1458968705412378,-0.19761488168929975,1.4211449536184755,-2.0296250782824776,0.025784813033801618,-0.04905685966922091,0.03110110046625536,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6666666666666667,1.0,1.0,0.0,1.0,-0.02390376999004925,-0.014592324364858002,0.59330429899525,0.9982897427521304,-0.03954978293027159,-0.025155291634727395,-0.034937307979083086,-0.022475471962489054,-0.009234112972292798,0.003071676422999686,-0.04521395232252445,-0.028268687367444312,-0.044478867502962725,0.17463162635645,0.4544351393177357,-0.8269574868205736,0.30174790915070143,0.5628124928511187,-0.6946495491105756,-0.14554315642948928,-0.056870923395288535,1.171165770379025,0.05029782568118279,-0.5431624750304138,1.039767927308002,0.09934676790168073,-0.052423419515547076,0.12335822627361104,0.08158084525653364,-0.09594389229557354,0.14628728501787203,-0.18407945340587595,1.414237587340682,-2.0701536087524097,0.025879895987351437,-0.049517813156154666,0.03124468280031767,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.675,1.0,1.0,0.0,1.0,-0.024097969747899503,-0.01465411001825849,0.5933257935563143,0.9982728124828858,-0.039737324382068576,-0.02527364461479593,-0.0351223546526765,-0.02268239499776547,-0.009264694634681324,0.003081738963165552,-0.04522401942168676,-0.028279534151244706,-0.044453761817631395,0.17545949761003135,0.45399570352284785,-0.8259274322185207,0.3024277535051802,0.5620107720356249,-0.6934288506883389,-0.14702056137058442,-0.045114380340380636,1.1537470338855826,0.05051391932101493,-0.5435770909020701,1.040028902463173,0.09934206968990111,-0.05305686626914774,0.12386073890239269,0.08158211052006759,-0.09648025861228815,0.14668289095017828,-0.17046816668357667,1.4073611139674287,-2.110023211723404,0.025989816308044505,-0.05000049152172448,0.03139068716283777,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6833333333333333,1.0,1.0,0.0,1.0,-0.024293980658165706,-0.01471595109637843,0.593347278839414,0.9982558000179473,-0.039924913315784745,-0.025392031512612854,-0.03530727634521989,-0.022899114377732406,-0.009297578406833791,0.0030927280698503164,-0.04523614338655884,-0.028289288748455165,-0.04442065205210704,0.17628732751794834,0.4535508582132499,-0.8248931411722004,0.30310761099270256,0.5612044885409139,-0.692204834261406,-0.14838429254088223,-0.033414904829164725,1.1359987168503016,0.05073098928631686,-0.5439958165557759,1.0402911054273827,0.09933686356625893,-0.05372064793772169,0.12437463627159806,0.08158398494895303,-0.09703817939923143,0.14708356595705796,-0.15681388373855853,1.4005658355616675,-2.1492728985790244,0.0261138489715923,-0.05050359158072393,0.03153968299135279,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6916666666666667,1.0,1.0,0.0,1.0,-0.024491883282292515,-0.014777858805649314,0.5933687582853191,0.9982387062982425,-0.04011255881501976,-0.025510446840448068,-0.035492041013774074,-0.023125092056854826,-0.009332628535349094,0.0031044850202253706,-0.045250246383119606,-0.02829829727601108,-0.04437998110123086,0.17711511200280233,0.4531003593905525,-0.8238545216139941,0.30378748658766275,0.5603934690456377,-0.690977457922388,-0.1496341260995604,-0.021771616414352844,1.1179258189092656,0.05094915013720813,-0.5444188174284155,1.0405545638463622,0.09933120385014149,-0.05441282565283978,0.12489936514617606,0.08158645693350008,-0.09761627970919395,0.14748927445914495,-0.14314821659614563,1.3938993762745087,-2.1879435018406745,0.026251264567635213,-0.05102614523682325,0.03169240583325905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7,1.0,1.0,0.0,1.0,-0.02469175413899401,-0.014839843560019512,0.5933902341155977,0.9982215321907215,-0.040300269659634694,-0.025628886684624593,-0.03567661844227716,-0.023359926522598762,-0.009369718534576176,0.003116854365710656,-0.0452662557615022,-0.028306935772007,-0.044332212048672215,0.17794284758211737,0.4526439777857026,-0.8228114850864308,0.30446738527492756,0.5595775505457606,-0.6897466796870869,-0.150770096150818,-0.010183248557922913,1.0995329918196237,0.05116851036244412,-0.544846252309723,1.0408193121912703,0.09932517931873275,-0.05513181195034522,0.12543461607566808,0.08158954133310248,-0.09821346447067558,0.14790007318149723,-0.12950140234544383,1.3874068771128463,-2.226077698863498,0.026401341359340857,-0.051567530752034685,0.0318497597178613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7083333333333333,1.0,1.0,0.0,1.0,-0.024893666866037143,-0.014901914991043385,0.5934117073074626,0.9982042784791252,-0.04048805435450142,-0.025747348833147835,-0.03586098030757447,-0.023603358255860026,-0.00940873319690061,0.0031296842467319185,-0.045284106192941175,-0.028315610469675772,-0.044277822226763824,0.17877053165811455,0.45218149585804673,-0.8217639446793996,0.3051473122765478,0.5587565779711264,-0.6885124567026963,-0.1517924828053178,0.0013518315375279269,1.0808245239282073,0.05138917249319715,-0.5452782762742827,1.0410853931749933,0.0993189138473527,-0.05587638786371363,0.12598033085456706,0.08159328094864637,-0.09882893050942254,0.14831611660361066,-0.11590219706349603,1.3811312133837843,-2.263720064584316,0.026563377139604688,-0.05212748385582611,0.03201282089960511,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7166666666666666,1.0,1.0,0.0,1.0,-0.02509769342851572,-0.01496408196892,0.593433177567836,0.9981869458550167,-0.040675921167927856,-0.02586583290415672,-0.03604510022109708,-0.023855275343902423,-0.009449570550075023,0.0031428265222691763,-0.04530374182741034,-0.028324758582451537,-0.0442172974500812,0.17959816281290658,0.4517127046546407,-0.8207118129055213,0.30582727329073833,0.5579304017039369,-0.6872747444103601,-0.1527017994352096,0.01283560499847349,1.0618043240765518,0.05161123331477086,-0.54571504370732,1.0413528592062637,0.099312567114207,-0.05664571984327904,0.12653671024058344,0.08159774802653064,-0.0994621784454841,0.14873766259948074,-0.10237778815848864,1.3751132324263085,-2.3009171548711693,0.026736700884496534,-0.052706109613420704,0.0321828434279281,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7249999999999999,1.0,1.0,0.0,1.0,-0.025303905376335232,-0.01502635263397265,0.5934546433048875,0.998169534908998,-0.04086387817994587,-0.025984340477508288,-0.03622895374694479,-0.02411571962263344,-0.009492143786869106,0.003156136717575599,-0.045325118486920994,-0.02833484969696592,-0.04415112647554307,0.180425741110018,0.4512374005273254,-0.8196549995087232,0.30650727474365663,0.557098874997035,-0.6860334956593717,-0.15349877927462593,0.024270385411299732,1.0424759046803544,0.05183478417460542,-0.5461567114345064,1.041621773898792,0.09930633546302858,-0.057439377458913254,0.1271042226124397,0.08160304586477207,-0.10011302523041055,0.14916507854385808,-0.08895372462613571,1.3693920097348447,-2.337717622285851,0.02692068422921287,-0.05330389600995078,0.03236126703989317,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7333333333333334,1.0,1.0,0.0,1.0,-0.02551237515683955,-0.015088734438066482,0.5934761015951538,0.9981520461220139,-0.04105193334073809,-0.02610287523224536,-0.036412518397311675,-0.024384893745377813,-0.009536383198295695,0.003169473790834784,-0.04534820591734135,-0.028346387885172897,-0.04407979573190145,0.18125326840395706,0.45075538169699214,-0.818593409195314,0.3071873240551512,0.5562618512834301,-0.6847886597679624,-0.15418436151231185,0.035658805160720904,1.022842363705121,0.05205991138525774,-0.5466034419741526,1.0418922136569286,0.09930045302605273,-0.05825735289271328,0.12768361428796338,0.08160931060240073,-0.10078161812679065,0.1495988481909727,-0.07565386448179723,1.3640051220941387,-2.374172366396907,0.027114752822533367,-0.053921730259651746,0.03254972792440469,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7416666666666667,1.0,1.0,0.0,1.0,-0.02572317749192332,-0.015151234195498749,0.5934975481441666,0.9981344798566119,-0.04124009453960899,-0.02622144309319267,-0.036595773606327736,-0.024663169604315707,-0.009582238148464827,0.003182699716417238,-0.045372990130540074,-0.028359914664213486,-0.044003784350028455,0.1820807486604522,0.4502664446457802,-0.8175269392705905,0.3078674299203633,0.5554191813615885,-0.6835401815228555,-0.15475967701598922,0.04700380411286871,1.002906365240406,0.052286696721647645,-0.5470554069388339,1.0421642693641988,0.09929519321964564,-0.059100083301673045,0.12827592228128237,0.08161671328395514,-0.10146845098818913,0.15003957967406834,-0.06250033842506608,1.358988936877724,-2.410334721197114,0.02731839765128391,-0.05456091892201087,0.03275007297643295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.75,1.0,1.0,0.0,1.0,-0.025936390832671574,-0.015213858142966215,0.5935189772382821,0.9981168363479989,-0.04142836968507811,-0.02634005239050329,-0.03677870068347216,-0.024951098570632775,-0.009629679137023424,0.0031956788785146278,-0.0453994758789256,-0.028376012954790242,-0.04392355951266945,0.18290818829095115,0.4497703803086309,-0.8164554771572926,0.3085476026098838,0.5545707104336269,-0.682288000106728,-0.1552260338193963,0.05830862077534964,0.9826701183518357,0.05251521801277914,-0.5475127906228527,1.0424380482065358,0.09929087073731024,-0.059968477227407835,0.12888249034788357,0.08162546230314427,-0.1021743837716782,0.1504880150183996,-0.04951352861813363,1.354378917206499,-2.44626068266663,0.027531186466882573,-0.055223213010335837,0.03296437824950704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7583333333333333,1.0,1.0,0.0,1.0,-0.026152098908649037,-0.015276612008320844,0.5935403816851241,0.9980991156946999,-0.041616766796898165,-0.026458714036649487,-0.03696128274773641,-0.02524942407467886,-0.009678700004369135,0.003208277263813548,-0.0454276893163693,-0.028395312216841485,-0.043839572129053074,0.18373559650607404,0.4492669700253234,-0.8153788977647924,0.3092278542920824,0.5537162749653939,-0.6810320479392155,-0.15558490249295812,0.06957678606631036,0.9621353538626288,0.05274554982942902,-0.5479757938223395,1.0427136756683573,0.09928784417937431,-0.060863946364888566,0.1295049892634048,0.08163580634624634,-0.10290066631724937,0.15094504161813127,-0.03671206131016125,1.3502099432179457,-2.4820091800936317,0.027752775491688003,-0.05591083941957509,0.033194972433854275,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7666666666666666,1.0,1.0,0.0,1.0,-0.02637039239358346,-0.01533950108796802,0.5935617527396734,0.9980813178485832,-0.04180529411108552,-0.02657744172615302,-0.03714350464367849,-0.02555909712196509,-0.00972932034584858,0.0032203614363337796,-0.04545768091332698,-0.02841849497686149,-0.04375225282604789,0.18456298569394072,0.44875598120254945,-0.8142970606695692,0.3099081993823212,0.5528556993283394,-0.6797722494130924,-0.15583790150789897,0.08081211982898207,0.9413032986836085,0.05297776427097394,-0.5484446379465123,1.0429912977471,0.09928651947828548,-0.06178844418433416,0.13014544241409132,0.08164803797413356,-0.10364896756897224,0.1514117062024667,-0.02411281191671888,1.346516650262746,-2.51764239543401,0.027982921635887753,-0.056626540191715424,0.03344446634044207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.775,1.0,1.0,0.0,1.0,-0.026591370714514215,-0.015402530332946156,0.5935830800125914,0.9980634426039712,-0.04199396019940616,-0.026696252164308147,-0.03732535284040726,-0.02588129543897171,-0.009781588214543255,0.0032317972700428767,-0.045489528710650526,-0.028446305007009575,-0.04366200823317098,0.18539037183071214,0.44823716262225116,-0.8132098070578909,0.3105886549249846,0.5519887921725777,-0.6785085195025077,-0.1559867826915701,0.09201873023735613,0.920174647272062,0.05321193185669382,-0.5489195694922014,1.043271083440698,0.09928735430356106,-0.06274451313959539,0.13080625794637202,0.08166249800602543,-0.10442141159778595,0.15188923190867065,-0.011730921064172506,1.343333785416291,-2.553226135743303,0.02822149551698669,-0.05737362139224489,0.03371578956792742,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7833333333333332,1.0,1.0,0.0,1.0,-0.02681514403773827,-0.015465704443958141,0.5936043513567715,0.9980454895855024,-0.042182774105203234,-0.026815165332321086,-0.03750681531436532,-0.026217447072566187,-0.009835583208638374,0.0032424484055034765,-0.04552334201688364,-0.028479557474425883,-0.043569217524088204,0.1862177749323334,0.4477102393168895,-0.812116956370463,0.311269241015755,0.5511153424683763,-0.6772407622146146,-0.15603341685896852,0.10320101625258692,0.8987495297545535,0.053448122529590386,-0.5494008649697164,1.0435532275732322,0.09929086366295081,-0.06373534251337687,0.13149026895214133,0.08167958089976168,-0.10522062202712901,0.15237903919461449,0.00042017997289534037,1.3406965842701104,-2.588830264567359,0.028468495647032965,-0.05815601370546819,0.0340122357875261,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7916666666666667,1.0,1.0,0.0,1.0,-0.027041835472379806,-0.015529027975907973,0.5936255527273803,0.9980274582343427,-0.04237174549800061,-0.02693420479771977,-0.03768788141653589,-0.02656925943569883,-0.00989142005981419,0.0032521743860962848,-0.045559265678284444,-0.028519151453935732,-0.04347422916172206,0.18704521955842798,0.4471749069136949,-0.8110183025753552,0.31194998127331397,0.5502351151387922,-0.6759688688492641,-0.15597977969202184,0.11436367330852464,0.8770274761959393,0.053686406784144367,-0.5498888363872926,1.0438379540371567,0.09929762695840783,-0.06476483936028177,0.1322007834610428,0.08169974136142177,-0.10604977678504879,0.15288277148347573,0.012328736080840508,1.3386411705464127,-2.624529199129495,0.02872406424094226,-0.05897834729356566,0.034337518405673784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8,1.0,1.0,0.0,1.0,-0.027271583541489244,-0.01559250545284187,0.5936466680097209,0.9980093477922674,-0.04256088484999406,-0.027053398080664887,-0.03786854172437624,-0.026938755010580403,-0.009949252864723711,0.003260828414333954,-0.045597485081974504,-0.028566085293836932,-0.04337735777705514,0.1878727353816402,0.4466308253275515,-0.8099136099794456,0.3126309033717787,0.5493478461886255,-0.6746927160232233,-0.15582793792428784,0.12551170242836046,0.8550073764357285,0.05392685693360609,-0.5503838374246092,1.04412551954666,0.0993082968109793,-0.0658377155413814,0.13294164639734873,0.0817235024686469,-0.1069126755175498,0.15340232662511166,0.023984629063896756,1.3372049816464602,-2.660402481186679,0.028988505206523907,-0.05984604403218574,0.034695838788771916,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8083333333333333,1.0,1.0,0.0,1.0,-0.02750454498171729,-0.015656141494614376,0.593667678808061,0.9979911572830388,-0.04275020363838714,-0.027172777089007897,-0.038048787878364715,-0.027328315204174534,-0.010009280134158346,0.0032682546508138602,-0.04563823209153318,-0.02862147544850678,-0.04327888109321062,0.18870035783861097,0.44607761165467186,-0.8088026084687328,0.3133120396477914,0.5484532372134997,-0.6734121634055122,-0.15558003587429023,0.1366504230026323,0.832687434842828,0.05416954853758643,-0.5508862704544957,1.0444162180169696,0.09932361004004908,-0.06695959453476563,0.1337173161598626,0.08175146565692848,-0.10781382253471028,0.15393989551496734,0.03537933411268235,1.3364272237859527,-2.6965354305346323,0.029262305011979045,-0.06076543096708242,0.03509196977718343,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8166666666666667,1.0,1.0,0.0,1.0,-0.02774089794642078,-0.015719940957113755,0.593688564187067,0.9979728854903763,-0.04293971457857835,-0.027292378637728164,-0.03822861240253173,-0.027740734216965664,-0.010071750875999765,0.003274284954757634,-0.045681792163919856,-0.028686579551994506,-0.04317903678455228,0.1895281288823077,0.4455148320853054,-0.8076849880434479,0.31399342779939415,0.5475509491463804,-0.6721270510979739,-0.15523828235574313,0.14778548949145967,0.8100651192601513,0.054414562017139075,-0.5513965946073939,1.0447103857096132,0.09934440127478461,-0.06813714259741754,0.13453295913303798,0.08178432300190663,-0.10875852885543491,0.1544980095421944,0.04650587382078797,1.336349360850485,-2.733019891278463,0.02954615729557908,-0.061743879787734546,0.03553135791684259,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.825,1.0,1.0,0.0,1.0,-0.02798084570430365,-0.015783909088512526,0.5937093003555554,0.997954530931672,-0.043129431894526477,-0.02741224507190335,-0.038408008507697065,-0.028179285260642433,-0.010136971981333846,0.003278734934703087,-0.04572851296024195,-0.02876282471464254,-0.04307801913471492,0.19035609785985738,0.44494199261138156,-0.8065603924831821,0.3146751116978232,0.5466405950659091,-0.670837196579809,-0.1548049379772771,0.1589229123501404,0.7871371033215203,0.05466198449251275,-0.5519153351176246,1.0450084073155836,0.09937161979671927,-0.06937823001058718,0.13539456628421043,0.08182287234024477,-0.1097530378183964,0.15507959896941204,0.05735877168204506,1.3370156414746348,-2.769955082078799,0.02984099229825246,-0.06278997834394673,0.03602024874409082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8333333333333333,1.0,1.0,0.0,1.0,-0.028224620947423968,-0.015848051704787952,0.5937298602798133,0.9979360918264016,-0.04331937163428061,-0.02753242501684783,-0.0385869698753365,-0.02864780207655274,-0.010205317252081465,0.0032813991379191717,-0.045778814845471194,-0.0288518422956596,-0.04297597532569992,0.19118432254558634,0.4443585282517956,-0.8054284119387111,0.31535714233839823,0.5457217318494071,-0.6695423911151503,-0.15428230282770905,0.17006908351603692,0.7638992012255047,0.054911911888776616,-0.5524430942464597,1.0453107231886813,0.09940635036909728,-0.07069212963881744,0.1363090970987546,0.08186803591301306,-0.1108046798939788,0.15568806490427578,0.06793400713262177,1.338473669019555,-2.8074485625086743,0.030148012477897446,-0.06391374182866727,0.03656584063940649,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8416666666666666,1.0,1.0,0.0,1.0,-0.02847249084992018,-0.015912375388731644,0.5937502132105519,0.99791756605794,-0.0435095520407722,-0.027652974284784543,-0.03876549041900156,-0.02915077950855061,-0.01027723849805474,0.0032820451557345996,-0.04583320377931898,-0.028955510758109728,-0.04287300114967433,0.192012870366009,0.4437637904507346,-0.8042885741982029,0.3160395789630401,0.5447938504010095,-0.6682423954980711,-0.15367270452506673,0.18123080683379963,0.7403462939463757,0.055164451367144374,-0.5529805641481024,1.045617837992907,0.09944983901324644,-0.07208976198720518,0.13728465754709207,0.08192088339989967,-0.11192206385631565,0.15632736825723192,0.07822897438935716,1.3407750189572565,-2.845617328209391,0.030468736024666376,-0.0651268733290955,0.037176474295339546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8499999999999999,1.0,1.0,0.0,1.0,-0.028724763053907035,-0.01597688771788849,0.5937703241034712,0.9978989511271652,-0.0436999939906543,-0.027773956974779905,-0.03894356401896523,-0.02969349793258799,-0.010353279248266484,0.003280406353200145,-0.04589228724072693,-0.029076008676432126,-0.04276913588335911,0.19284181986247378,0.44315703221867553,-0.8031403343129262,0.3167224903950632,0.5438563641184685,-0.6669369349775298,-0.15297848658788643,0.1924153338319912,0.7164722457553482,0.05541972415585439,-0.5535285421352779,1.0459303310936037,0.09950352496030934,-0.07358399849260344,0.13833072065682517,0.08198266045465807,-0.1131153134671159,0.15700214004589652,0.0882424476008542,1.343975907449707,-2.8845890473692504,0.0308050504673113,-0.06644308616857497,0.03786186685470039,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8583333333333334,1.0,1.0,0.0,1.0,-0.02898179280399938,-0.016041597528416485,0.5937901529080771,0.997880244095826,-0.04389072151742893,-0.027895446812183755,-0.03912118422418597,-0.030282177720442994,-0.010434091774854787,0.003276172840655141,-0.04595679401334108,-0.029215880577802708,-0.04266435599650308,0.19367126244868083,0.4425373904758579,-0.8019830621872558,0.3174059566372844,0.5429085951765575,-0.6656256931639728,-0.1522019970650525,0.20363040529129475,0.6922698098235549,0.055677868874932895,-0.5540879489175786,1.046248869107152,0.09956908035839762,-0.07519003813305503,0.13945840074289562,0.08205482416886567,-0.11439636143554033,0.15771781867592205,0.0979745552003286,1.3481379132923144,-2.9245034496213163,0.031159279179100996,-0.06787850402661055,0.03863340240813251,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8666666666666667,1.0,1.0,0.0,1.0,-0.029243991509944094,-0.016106515223840673,0.5938096536924582,0.9978614415171108,-0.04408176243956516,-0.028017528786165733,-0.03929834391366411,-0.03092417172677351,-0.010520458330181497,0.0032689801844122046,-0.046027598903082105,-0.029378119106547335,-0.042558567275732616,0.19450130453511374,0.44190386491645794,-0.8008160276338779,0.31809007079787766,0.5419497580945428,-0.6643083046662644,-0.15134557733454762,0.21488429905352976,0.6677305215949929,0.05593904547550607,-0.5546598505357214,1.0465742211337392,0.09964845977784687,-0.07692587685216523,0.14068079562553182,0.08213908730893116,-0.11577931586620016,0.15848082151926235,0.1074267668706641,1.35332875234024,-2.965513874896335,0.03153426440882054,-0.0694521595219233,0.03950449401090239,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.875,1.0,1.0,0.0,1.0,-0.029511837092052875,-0.01617165314022603,0.5938287735626313,0.9978425393501515,-0.04427314912010668,-0.028140301160041615,-0.03947503490666929,-0.03162820618478706,-0.010613317765327614,0.003258395192050367,-0.046105753782851366,-0.029566268074005586,-0.042451594824334096,0.19533207011164494,0.4412552925283218,-0.7996383822601636,0.31877494142576657,0.5409789399121209,-0.6629843461386518,-0.15041155095054143,0.22618588449696542,0.6428445785752827,0.05620343994841324,-0.5552454849096107,1.0469072773406671,0.09974396216965331,-0.0788128951313194,0.14201341550938107,0.08223747372377632,-0.1172809189647106,0.15929876035794877,0.1166018972547278,1.359623098219806,-3.007788982687025,0.03193347154565429,-0.07118661815575411,0.04049103697587597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8833333333333333,1.0,1.0,0.0,1.0,-0.02978588656209258,-0.016237025982604368,0.5938474513231045,0.9978235328542797,-0.04446491939183962,-0.02826387795018534,-0.03965124750794483,-0.03240468357563512,-0.010713799053629992,0.0032438978913041476,-0.0461925267906311,-0.029784552385747544,-0.04234317023599933,0.19616370390460797,0.4405903166642693,-0.7984491373753883,0.3194606953599406,0.5399950761117976,-0.6616533253269653,-0.14940221238030216,0.23754468402385986,0.6176007052168758,0.05647127000126698,-0.5558462941716507,1.0472490717500038,0.09985830874283674,-0.08087659679435699,0.1434747229908817,0.08235238805325173,-0.11892112383195652,0.16018071327666528,0.12550413153822604,1.367103434244717,-3.051514609383017,0.03236112076986375,-0.07310876275188338,0.04161197929091198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8916666666666666,1.0,1.0,0.0,1.0,-0.030066791420504547,-0.016302651351807956,0.5938656158094794,0.9978044164576289,-0.04465711769202979,-0.028388391997082527,-0.039826969969578026,-0.03326606527069634,-0.010823263716294133,0.0032248585299203287,-0.04628945208299359,-0.03003804274875084,-0.04223291502138966,0.19699637525735889,0.43990734924841585,-0.7972471368769822,0.3201474812266541,0.5389969211815883,-0.6603146675840407,-0.14831981542490433,0.24897094173437737,0.5919860017522324,0.0567427919612443,-0.5564639642888087,1.047600810328849,0.09999474130386543,-0.08314754245485112,0.14508681640442944,0.08248670384122359,-0.12072382325027053,0.16113756962941705,0.13413907939547054,1.3758609069879335,-3.096895739369536,0.032822354168801915,-0.07525078450045797,0.04289004312211908,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9,1.0,1.0,0.0,1.0,-0.030355316619356747,-0.01636855038652648,0.593883183802922,0.9977851835930739,-0.04484979646384514,-0.028513998788764303,-0.040002187845400945,-0.03422735739407106,-0.010943359778856219,0.003200508031477179,-0.04639839331580716,-0.030332865617197592,-0.042120319069177806,0.19783028292633906,0.43920452429002177,-0.7960310237686478,0.3208354737572943,0.5379830123909598,-0.658967699166475,-0.14716656105704432,0.2604756991403254,0.5659857762273836,0.057018309237413675,-0.557100473913325,1.0479639058020391,0.10015714703412781,-0.08566253480945862,0.14687629910720812,0.08264387545376839,-0.12271777515749704,0.1621824701684238,0.14251386564896829,1.3859961287351903,-3.1441585189558285,0.033323448977708725,-0.07765144133267565,0.0443526421515017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9083333333333332,1.0,1.0,0.0,1.0,-0.030652364062776025,-0.01643474855286268,0.5939000574083528,0.9977658264923476,-0.045043017898920096,-0.028640881245460867,-0.04017688320605426,-0.03530673089354051,-0.01107609073076557,0.0031698998137420177,-0.04652162505299673,-0.03067647225628964,-0.0420047125204825,0.19866566104126102,0.43847964033492487,-0.7947991985585288,0.32152487915088357,0.5369516249289633,-0.6576116264145669,-0.14594458433075486,0.2720708772132972,0.5395833597696352,0.057298182777539446,-0.5577581549776867,1.048340021031374,0.10035021758638518,-0.08846613142274418,0.1488753912623353,0.08282808092748617,-0.12493778394807586,0.16333137180545076,0.15063726852085513,1.3976198391220584,-3.1935521822471213,0.03387209105960021,-0.08035766385924736,0.046033053856180395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9166666666666667,1.0,1.0,0.0,1.0,-0.030959001910800327,-0.016501276623515884,0.5939161207408478,0.9977463359263137,-0.045236856118527444,-0.028769255738884232,-0.04035103367253874,-0.03652631686178909,-0.011223904084709887,0.003131860168543346,-0.046661937675733935,-0.03107798536896504,-0.041885228890307866,0.1995027865527788,0.43773008876630937,-0.7935497672476088,0.3222159417727524,0.5359007159918252,-0.6562455096363842,-0.14465593991503006,0.28376936312569306,0.5127599065232649,0.05758284408840701,-0.5584397683109791,1.0487311233663088,0.10057965290753701,-0.09161258529220562,0.1511233594420447,0.08304440516063605,-0.1274262160565942,0.1646037764712882,0.15851991977386293,1.4108532778747418,-3.2453506610790064,0.034477727354751825,-0.08342661507354521,0.04797192485665125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.925,1.0,1.0,0.0,1.0,-0.03127650134244726,-0.016568171901751146,0.5939312357147862,0.9977267008755575,-0.045431399921373,-0.028899379705363843,-0.0405246112122941,-0.03791323148990825,-0.011389805623393139,0.003084923461000062,-0.04682277317977806,-0.03154864778294948,-0.0417607565346713,0.20034198858971997,0.4369527639133881,-0.7922804759011614,0.3229089525702275,0.5348278546613534,-0.6548682301400455,-0.14330258566785714,0.29558509851120957,0.4854941820849851,0.05787281156678531,-0.5591485985622457,1.0491395531123182,0.10085242352061041,-0.09516834629036075,0.1536683645289849,0.08329907587441676,-0.13023495403005736,0.16602367705866872,0.16617458563242926,1.4258280285412095,-3.2998534953099634,0.035152022166864416,-0.08692834441255348,0.05021921245995209,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9333333333333333,1.0,1.0,0.0,1.0,-0.03160638295023871,-0.016635479762517585,0.5939452366635355,0.997706908110341,-0.04562675626653414,-0.029031561325954584,-0.04069758062340135,-0.03950090256855195,-0.011577507379542004,0.003027247176568222,-0.04700840162030355,-0.03210240562156387,-0.04162987458133608,0.20118366027812232,0.43614394966147,-0.7909886278387924,0.3236042597039927,0.5337301334246576,-0.653478448352073,-0.1418863634878229,0.3075331636013799,0.4577623482680988,0.05816871112452142,-0.5598885740511883,1.0495681102406413,0.1011771093231828,-0.09921529990352451,0.15656986190570654,0.08359976869046326,-0.1334279273671668,0.16762079164150068,0.17361655347757188,1.4426849483098947,-3.357385410671724,0.03590945022298203,-0.09094922184214482,0.052836697886222694,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9416666666666667,1.0,1.0,0.0,1.0,-0.03195047562035414,-0.01670325560568594,0.5939579234286979,0.997686941652172,-0.04582305471349867,-0.02916617189702971,-0.04086989760789889,-0.04133079208943524,-0.011791619918824669,0.00295650028270802,-0.04722415098965905,-0.03275666852494576,-0.04149076815613615,0.20202827374510635,0.4352991755816627,-0.7896709782027329,0.3243022820484019,0.5326040558719006,-0.6520745502793538,-0.14040897644323094,0.3196298476497078,0.42953775857378973,0.05847130240383501,-0.5606644189262815,1.0500201647437553,0.10156433845473933,-0.10385497603277005,0.15990173201545943,0.08395600264910485,-0.13708440283029644,0.16943218144722438,0.1808641572722336,1.4615715715055544,-3.418293534514718,0.036768069847763624,-0.09559639557505495,0.05590124744151659,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.95,1.0,1.0,0.0,1.0,-0.03231099164608161,-0.016771567345762663,0.5939690524409652,0.9976667820802444,-0.04602045311100996,-0.029303661711386743,-0.04104150630262656,-0.04345463781116181,-0.012037902643212825,0.0028697164901705817,-0.0474767070129802,-0.033533301948179405,-0.041341116104611005,0.20287639925236797,0.4344130333942572,-0.7883235989718681,0.3250035264148111,0.531445393377486,-0.650654578661286,-0.13887196086661902,0.33189268979313913,0.40079078935952017,0.05878151228865081,-0.5614818473107726,1.050499797698,0.10202735648359551,-0.10921403190752521,0.16375637607143778,0.08437965355674981,-0.1413032733720332,0.17150437986733325,0.18793948474425615,1.482637017521139,-3.482940589574257,0.037750532540805626,-0.10100358898317952,0.05950904681023772,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9583333333333333,1.0,1.0,0.0,1.0,-0.03269062297566368,-0.016840498599890452,0.5939783251631896,0.9976464056343223,-0.04621914491569053,-0.029444580521733453,-0.041212336093559974,-0.0459373700257622,-0.012323589524375896,0.0027631019651648057,-0.04777450351091731,-0.03445992070348358,-0.0411779424583696,0.2037287296864996,0.4334789417165373,-0.786941705268209,0.32570860960768105,0.5302490013157001,-0.6492161439482316,-0.13727665169749334,0.34434046460839346,0.3714887487475521,0.05910047794618177,-0.5623478120760012,1.0510119821905926,0.10258276370891162,-0.1154513989099415,0.16825008160908927,0.08488561935968808,-0.14620865316509635,0.17389620010654694,0.1948693213842101,1.5060228761630612,-3.5516914094684737,0.0388854003219527,-0.10733863600984828,0.06378108682804307,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9666666666666666,1.0,1.0,0.0,1.0,-0.033092664944831304,-0.016910152781986362,0.5939853730764839,0.9976257830508277,-0.04641936863164931,-0.029589603969984415,-0.0413822974858578,-0.048860894533253006,-0.012657811481662003,0.0026317853856497125,-0.0481282278473997,-0.035571566307218264,-0.04099742084273398,0.20458611198084983,0.43248884341242483,-0.78551943094505,0.3264182867374726,0.529008582491401,-0.6477563086595102,-0.13562413884354885,0.3569930710625235,0.3415959325350456,0.05942960229401669,-0.5632708245776034,1.0515628158118007,0.10325146546488473,-0.1227675763116276,0.1735300421015573,0.08549267808471983,-0.15195716149641214,0.17668243708707454,0.20168639910462915,1.5318476770779255,-3.6248885551104206,0.04020885741289004,-0.1148132392346013,0.06887022437609858,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9749999999999999,1.0,1.0,0.0,1.0,-0.033521175576624054,-0.016980658363739257,0.593989738166251,0.997604878051118,-0.04662141998948376,-0.02973956772643125,-0.0415512767374305,-0.05232895836822617,-0.013052139306838857,0.002469498275694962,-0.0485514675745468,-0.03691285692648727,-0.04079461952873846,0.20544958744424768,0.4314328154446768,-0.7840495378998497,0.3271334875757597,0.5277163819574265,-0.646271436663447,-0.1339152117124162,0.3698712592263589,0.31107393949571177,0.05977062556972994,-0.5642613660632445,1.0521598192635275,0.10405988358956231,-0.1314166332322697,0.1797834899191164,0.08622458164398883,-0.1587473439198983,0.1799587293673821,0.2084310272931661,1.5601812203594934,-3.7028103836408244,0.041766912564839415,-0.12369549090217591,0.07497014917542622,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9833333333333334,1.0,1.0,0.0,1.0,-0.033981180405283376,-0.01705217561555086,0.5939908476323911,0.9975836453816509,-0.04682566760986,-0.029895511444580018,-0.041719128894839475,-0.05647330562402354,-0.013521269681262185,0.0022681782652622644,-0.049061519189032524,-0.038540683036152754,-0.04056317553500803,0.2063204433740092,0.430298566191887,-0.782523039446398,0.32785536309820573,0.5263627934260694,-0.6447569965033871,-0.13215028838866275,0.38299609140184837,0.27988242614103187,0.06012571750343068,-0.5653324160926396,1.0528123182980578,0.10504146905765288,-0.14172148794274753,0.18724943510255887,0.08711142089708912,-0.16683169318522983,0.18384788236297966,0.21515318198013167,1.5910030478323445,-3.785601231116306,0.04361817940861851,-0.13432565451544587,0.08232648900927231,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9916666666666667,1.0,1.0,0.0,1.0,-0.03447893435990065,-0.017124905172748596,0.5939879813801553,0.9975620282897486,-0.047032572975994426,-0.030058734869177497,-0.04188566881566987,0.002952241556312503,-0.00806434010586776,0.017104090883778355,-0.033823348081237936,0.015894037621073928,-0.036695216180145915,0.20720027859520856,0.42907079064563103,-0.7809287139814737,0.3285853445907112,0.5249358537376727,-0.6432073052907307,-0.13032932534608066,0.3963879766902313,0.24798058564377334,0.060497595226540246,-0.5665001269718353,1.053531927413682,0.07900276093687542,-0.032776692443360345,0.0910354370540345,0.06350163991996616,-0.08320617718725387,0.13182395760283905,0.10998541517683702,1.1075118021270969,-2.5184257012655125,0.015658913978261885,0.0434836134490757,-0.13666725485707243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0,1.0,1.0,1.0,1.0,-0.033959822497103956,-0.017162020341123112,0.5942895577995125,0.9975615539983019,-0.04709202783138467,-0.029765981983023437,-0.04203894885152892,0.0626688720798918,-0.0024518646511331524,0.02594087519185143,-0.03457027753425956,0.05918046192125048,-0.03635694734912222,0.20763715605629046,0.42975228798449766,-0.7810057821621641,0.3289137237635385,0.5249760238062818,-0.6425599305433398,-0.13031719813571546,0.4014546214373,0.23790866445327333,0.06038669940306838,-0.5646076892018217,1.0505345307171066,0.0729997738704602,0.09947022552700524,-0.024452296222612357,0.05829096760943675,0.0127369786515108,0.07949722045077712,0.0058646302202736145,0.5310135764886315,-1.0206124474478806,-0.011176574799846295,-0.35115349731483336,0.7676232166509411,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0083333333333333,1.0,1.0,1.0,0.0,-0.03346750167450984,-0.01720841635464753,0.594487546600363,0.997550407100777,-0.04729022829621842,-0.02956890418481347,-0.04221965781570426,0.05632457338294431,-0.002413380327366865,0.012718592377103887,-0.045600534006960014,0.026001831535147533,-0.0404113248024488,0.20841694149304957,0.4307286277377478,-0.7813362522518505,0.32955686071753515,0.5251481367151979,-0.641882351616551,-0.1302315815090761,0.4052382029650418,0.23097037818630867,0.06031131897987614,-0.5723526852604158,1.0663256476911978,0.08729400522562547,0.12313953199107441,-0.027197133829290898,0.07195257184593795,0.03281765768349709,0.08339049995988557,-0.0026935558857271724,0.394831409491303,-0.6645696937449619,-0.009345318229873889,-0.9700263070770232,1.9786579415785877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0166666666666666,1.0,1.0,1.0,0.0,-0.03304122698616785,-0.017257838369532645,0.5945630378705015,0.9975357985402302,-0.04745202819016442,-0.029549719251567814,-0.042396341156980315,0.04588165757906344,-0.0027325950643692443,0.003817222298519157,-0.0405263704601115,-0.003217759940702785,-0.04115077577139219,0.20909205614338422,0.43180461351768223,-0.7814590677259856,0.33011293329430413,0.5255229847676735,-0.6411700888773417,-0.13036209073381091,0.4080351449288217,0.2268325028908573,0.06023094409923715,-0.5807747943197721,1.0835121630767497,0.08139354715298697,0.11796511839652468,-0.00037052481077326505,0.06707173153807866,0.03702945633717203,0.0944679402074522,-0.01693729144371714,0.2887966959693411,-0.39948396853023593,-0.004151135184970733,-1.0347244303840397,2.080837967526885,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.025,1.0,1.0,1.0,0.0,-0.03271436644155648,-0.017309944623763618,0.5946031252860434,0.9975190492565117,-0.04761813116704648,-0.029597605868732082,-0.04257043200840767,0.034081990860717996,-0.003791582336635126,0.0016624693610441858,-0.04111662030818101,-0.014604712994014765,-0.04118266373494479,0.20977350061226602,0.4326947130443565,-0.7813424276653634,0.33067472290983646,0.5257652943208174,-0.6403078859464268,-0.13051386969980472,0.4100514812311975,0.22431231204413807,0.06024213339345996,-0.5895980924334832,1.1010062804833125,0.0828044569647085,0.09276377230956423,0.026030305302777723,0.06826420818895951,0.01800094054326795,0.1103194919803463,-0.017381383913195325,0.20556034454676353,-0.23934531837308148,0.007029366645703583,-1.0790067102403178,2.1004852714584654,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.033333333333333,1.0,1.0,1.0,0.0,-0.032483316701704,-0.0173644554198724,0.5946322599580585,0.9975012686030047,-0.04778884487103509,-0.02967287786756693,-0.04274302001900469,0.02347864221559173,-0.004886952520195378,0.0013511986809787426,-0.04185379790078212,-0.01942380816600151,-0.04111234211244448,0.21047213042612936,0.4333506763895083,-0.7810252293042727,0.33125067009745346,0.5258230004433946,-0.6393314306776693,-0.1306517804656975,0.41146115067126776,0.22284341425130594,0.060348100209998874,-0.598758239490444,1.1185202509343908,0.08481672450190103,0.06599808717090427,0.04740670153070781,0.06992052402617022,-0.0031719523811268857,0.12188971566935214,-0.015418857386504947,0.14059438057830387,-0.13110568860143612,0.01814037135176111,-1.1166667599657232,2.096436993370352,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0416666666666665,1.0,1.0,1.0,0.0,-0.03233359213545589,-0.01742077827901332,0.5946578246318075,0.997482933065271,-0.04796279602507182,-0.029760530348342352,-0.042914790857545154,0.014688262399645166,-0.005820647324658229,0.0015273751086495521,-0.04242162244224203,-0.02171539533745369,-0.04105458914283918,0.2111871126872977,0.4337946811638716,-0.780552315973185,0.3318400649769393,0.5257124284477986,-0.638276390685271,-0.13077085065624647,0.41239472090750257,0.22212721723411413,0.060544472915989314,-0.6082092050995785,1.135946897039485,0.0866187888559522,0.04275035335000621,0.06394749409596168,0.07140425724553423,-0.021623912771824294,0.12994460015698595,-0.013270931112883133,0.08954946836806865,-0.05190605529371339,0.02876012927846741,-1.149314612273753,2.083081902158752,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.05,1.0,1.0,1.0,0.0,-0.032249836630610755,-0.017478421469782422,0.5946821307005783,0.9974642445976101,-0.04813905388447174,-0.029854621647770304,-0.043086120812803434,0.0076225080229290285,-0.006574309789603422,0.0017975434881042861,-0.042849632302017236,-0.022978108769543436,-0.04102013662170492,0.2119157769070619,0.4340631822786751,-0.7799594377360066,0.3324407410515457,0.5254626018971975,-0.6371656873417195,-0.13087296265091222,0.41295364181073557,0.22197831332974405,0.06082743569797333,-0.6179134830283399,1.1532382826370366,0.08809864345319274,0.023768589668909934,0.07672999002204861,0.07262557213850274,-0.03668046194615249,0.1357610917280061,-0.011420222515431955,0.049388043098504975,0.008387940472585065,0.03899588273238802,-1.1778842458515504,2.0652598268442324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.058333333333333,1.0,1.0,1.0,0.0,-0.032218641557543004,-0.017537035844200143,0.5947059254974398,0.9974452979124303,-0.04831701645662007,-0.029952599056985104,-0.04325720058955955,0.0020148624428091635,-0.007172565317552206,0.002051680372987844,-0.04317578872245953,-0.02377810321675756,-0.04100066680547359,0.21265542341151758,0.4341908243250201,-0.7792734828061508,0.3330504911792477,0.5251010874153628,-0.6360137058231375,-0.13096118769817033,0.4132178549591443,0.22226701624199055,0.06119440429486245,-0.6278406091971044,1.1703678941535556,0.08927687593182854,0.00861457239944019,0.08667856439487753,0.07359964933267737,-0.04869672600447128,0.14014060968272846,-0.009924111068784769,0.017818747225265552,0.05507946315406742,0.04898121722827581,-1.2031573915575144,2.0447681720892597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0666666666666664,1.0,1.0,1.0,0.0,-0.0322290035434712,-0.01759637478457135,0.5947294638845242,0.997426144835122,-0.04849627086734516,-0.030053210743141788,-0.04342812263194927,-0.00240990497958873,-0.0076449039503504205,0.00226478987109455,-0.04342665177343266,-0.02433721112661079,-0.0409883032327844,0.21340372483925904,0.4342067584853324,-0.778514794996092,0.333667401873757,0.524650989797123,-0.634830010513674,-0.13103836450205864,0.41325062093115666,0.22289630438231184,0.061643789318444595,-0.6379661062209652,1.1873177521718576,0.09020082596375212,-0.003376269085525463,0.0944681510226042,0.07436438141910973,-0.05820898992320078,0.143538700010164,-0.008738637727442877,-0.006947077689608561,0.09144791126512453,0.05881867894918541,-1.2257881717880936,2.0223530786876243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.075,1.0,1.0,1.0,0.0,-0.03227209627204422,-0.017656258201883407,0.594752843019974,0.9974068184984577,-0.048676516500531154,-0.03015573562485407,-0.04359893075617895,-0.005889751202567869,-0.008016935209919328,0.002436567117084923,-0.04362028407889864,-0.024749423328815384,-0.04097835957754441,0.21415877051091345,0.4341345531735947,-0.7776990136224408,0.33428989753623284,0.5241309375833094,-0.6336213941563015,-0.13110683166029438,0.4131020703309842,0.2237911480964093,0.062174715610682205,-0.6482704120602393,1.2040737787983493,0.09091767401982864,-0.012825579780491037,0.10058865645087955,0.07495821889623833,-0.06571380132835092,0.14622514402157671,-0.007805449542132026,-0.02632011794171496,0.11978022668155286,0.06858154236429242,-1.246307111607341,1.9983745843400857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0833333333333335,1.0,1.0,1.0,0.0,-0.03234089788474565,-0.017716550053165286,0.5947761082216139,0.9973873426199277,-0.04885752514314483,-0.030259694998458684,-0.043769645612528024,-0.00861886420358636,-0.008309323627146755,0.002572903388454806,-0.04376948718287379,-0.025060142319352822,-0.04096852731550987,0.21491901940625618,0.4339929988223242,-0.7768383173885773,0.3349167055220276,0.5235557597749838,-0.6323929247799811,-0.13116845532776084,0.41281195229879475,0.22489264149367105,0.06278681502451613,-0.6587378914144209,1.2206239952441924,0.0914679968631793,-0.020252657704745713,0.10540458465863045,0.07541448628968883,-0.07162325370432487,0.1483736188720841,-0.007072908148526014,-0.04141673739279317,0.14178545166363243,0.07832204840241552,-1.2651347512823663,1.9730367281835104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.091666666666667,1.0,1.0,1.0,0.0,-0.03242983656228429,-0.017777145081543398,0.5947992865894566,0.9973677352998069,-0.04903911927143806,-0.030364739789483876,-0.0439402769851635,-0.010752465399780803,-0.0085384457950282,0.0026803686732046663,-0.04388376021072116,-0.025295201405949416,-0.04095782834680363,0.21568323712529977,0.4337970088785156,-0.7759422705447969,0.335546805641061,0.5229372166882373,-0.6311485005084334,-0.13122471346276982,0.4124117913744376,0.22615423895746983,0.0634800830840558,-0.6693559912482787,1.2369577242680745,0.0918850901602597,-0.026075524102249226,0.10919367919467682,0.07576062327812716,-0.0762678496972935,0.15010521094344753,-0.0064992487587334224,-0.05312191596707261,0.15878597694210295,0.08807775408087082,-1.2825993558881854,1.9464705451134057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1,1.0,1.0,1.0,0.0,-0.03253449340528413,-0.01783796068659569,0.5948223977154281,0.997348010785658,-0.049221159036715256,-0.03047060230875987,-0.04411082950835172,-0.012413799991240653,-0.008717254504611187,0.002764739672469558,-0.04397039226019235,-0.02547163355602173,-0.04094593117555976,0.21645043757559385,0.4335584067539534,-0.7750184227353327,0.3361793825766631,0.5222846289466956,-0.629891171264257,-0.1312767761404064,0.41192658703267687,0.2275390744427061,0.06425477759253065,-0.6801145473458906,1.2530651709960825,0.09219581154067014,-0.03062660691952157,0.11217117378739871,0.07601880004883266,-0.07990990432648948,0.15150931728478367,-0.006051431030736909,-0.06213814489312797,0.1718218719754172,0.09787563072067323,-1.2989539898496871,1.9187662592879828,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1083333333333334,1.0,1.0,1.0,0.0,-0.032651363787887945,-0.017898931566843627,0.5948454571876937,0.9973281804471021,-0.049403533631341257,-0.030577072368519087,-0.04428130526734638,-0.013700616338202428,-0.008856020261821515,0.0028307593219766996,-0.044035092992673476,-0.02560182839134854,-0.04093278630680186,0.21721983398431094,0.4332865654298569,-0.7740727509816736,0.33681378564187486,0.5216053849494625,-0.6286233452203537,-0.13132557064661543,0.4113761556262188,0.2290179368237268,0.06511134359606702,-0.6910052244124402,1.2689371619228742,0.09242169413788026,-0.03416951104878385,0.11450570222676815,0.07620680720377027,-0.0827572207435856,0.1526543106429168,-0.005703366099456542,-0.06902372119957034,0.18171728102439944,0.10773466633492379,-1.3143911316173962,1.8899874289802199,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1166666666666667,1.0,1.0,1.0,0.0,-0.032777668498637065,-0.017960005933869472,0.594868477884065,0.9973082534106258,-0.04958615508486478,-0.03068398322931304,-0.0444517049856356,-0.014690526615615995,-0.00896291459011683,0.002882238441164934,-0.04408238736648423,-0.02569528000822159,-0.040918453252610835,0.21799079914455852,0.43298891490314034,-0.7731099943648866,0.33744949603005925,0.5209053419343025,-0.6273469327535417,-0.131371832242064,0.4107761916793507,0.23056769579311276,0.06605035536477938,-0.7020210662061805,1.2845649614790862,0.09257997683654651,-0.036913412663641676,0.11633034481245863,0.07633889555744178,-0.08497462345518514,0.15359356070963948,-0.00543437630960264,-0.07422283812001496,0.1891274896296441,0.11766758037316194,-1.3290545530995912,1.8601783415918893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.125,1.0,1.0,1.0,0.0,-0.03291120489632811,-0.018021142696187573,0.5948914706104038,0.9972882370215315,-0.049768953573475105,-0.03079120203930171,-0.044622028591962536,-0.015445274703551656,-0.009044460813360567,0.002922224589691222,-0.04411588491772371,-0.025759436157046234,-0.04090302624331422,0.21876283359825338,0.43267134188546286,-0.772133911901466,0.3380861005678322,0.5201891412252094,-0.6260634525418597,-0.1314161435851088,0.41013910832421857,0.23217006165088752,0.06707246993561972,-0.7131561336307667,1.299940134282739,0.0926844701095475,-0.03902463356102004,0.11775065884157998,0.07642648662362528,-0.08669315457614735,0.15436922279404852,-0.0052279961949447395,-0.0780892922444032,0.19457440614819632,0.1276820134210968,-1.3430487676360214,1.8293686320159308,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1333333333333333,1.0,1.0,1.0,0.0,-0.03305022960889459,-0.018082309296547465,0.5949144445440101,0.9972681372000384,-0.04995187377185016,-0.030898622717518042,-0.044792275521646704,-0.016014092276651383,-0.009105883031109593,0.0029531596649309865,-0.044138476153407685,-0.025800191751633773,-0.04088660604618009,0.21953554031305098,0.43233850434379,-0.7711474833841936,0.33872327080711967,0.5194604560247,-0.6247741123736409,-0.13145896551197975,0.4094747034752773,0.23381060256224936,0.06817838892179766,-0.7244052123334476,1.3150544386793517,0.0927462583212979,-0.04063575353854931,0.11885070322164015,0.07647875043009789,-0.088017282533015,0.1550148421271902,-0.00507105861150936,-0.08090520881520957,0.19847415103934785,0.13778139262395683,-1.3564464861183945,1.7975765713037362,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1416666666666666,1.0,1.0,1.0,0.0,-0.033193365974690754,-0.018143480021271717,0.5949374076032505,0.9972479587226641,-0.05013487197466908,-0.031006160416659392,-0.04496244490438029,-0.01643633187351192,-0.009151378046534682,0.0029770091979608544,-0.0441524820363787,-0.025822223973826927,-0.040869291507759406,0.220308604570275,0.43199407932648703,-0.770153066847772,0.33936074640833386,0.5187221865163258,-0.6234798718397399,-0.13150066122863396,0.4087906881772984,0.23547796416820999,0.06936882647935233,-0.7357635750660733,1.329899743804468,0.09277426134111755,-0.041852747651827116,0.11969765049939074,0.07650306820499497,-0.08903053469934585,0.15555725446146473,-0.00495299491624579,-0.08289586463604559,0.20115882266834972,0.14796558442326774,-1.3692944942758545,1.7648115909398054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.15,1.0,1.0,1.0,0.0,-0.033339530903642695,-0.018204634666598423,0.594960366767775,0.9972277054464961,-0.05031791380992522,-0.031113747137119157,-0.04513253570120591,-0.01674353576936962,-0.009184328666211487,0.002995364145894542,-0.044159770538196925,-0.025829243216654585,-0.04085117865011577,0.2210817780020696,0.4316409585495929,-0.7691525225425371,0.3399983219438696,0.5179766137797109,-0.6221814914659498,-0.1315415154272505,0.4080931057313432,0.23716324960672186,0.07064448199551879,-0.7472267872380451,1.344467965195015,0.09277568120276913,-0.04276058078616085,0.12034536336855695,0.07650540071361456,-0.0897999062675936,0.15601802446131963,-0.004865293231782752,-0.08424144203059591,0.2028937792434088,0.158231399530587,-1.381618293892013,1.731076293623408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.158333333333333,1.0,1.0,1.0,0.0,-0.033487877017802106,-0.018265757482369843,0.5949833283509517,0.9972073804882288,-0.05050097241699915,-0.03122132823521927,-0.045302546815504274,-0.016961065686203147,-0.00920747191826908,0.003009520072881712,-0.044161848649471425,-0.02582419029666335,-0.04083236212992022,0.2218548659236545,0.431281402980051,-0.7681473107916293,0.34063583642022743,0.517225521411866,-0.6208795714320512,-0.13158174944916368,0.40738666414345515,0.23885952715560013,0.07200601647152878,-0.7587905466309401,1.358751015364858,0.09275635674209914,-0.04342760456334638,0.12083719160404183,0.07649058095893446,-0.09037932216344968,0.15641455754739297,-0.004801074827510132,-0.0850863602865326,0.20389139569171766,0.16857299055577923,-1.3934257796537408,1.6963680840035833,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1666666666666665,1.0,1.0,1.0,0.0,-0.033637746845559924,-0.01832683633432002,0.5950062982240121,0.9971869863668898,-0.05068402699340983,-0.031328859645343994,-0.045472477187567174,-0.017109389714213604,-0.009223032243453319,0.0030205386707495116,-0.04415993543768667,-0.025809394535510764,-0.04081293705117441,0.2226277172811046,0.4309171651402038,-0.7671385693491364,0.3412731649598518,0.5164702917436534,-0.6195745821734933,-0.13162153334104235,0.4066749997265677,0.24056143953491715,0.07345403183811511,-0.7704505502322742,1.3727407665950748,0.09272104512014767,-0.04390902266789731,0.12120817161946906,0.07646254672180941,-0.09081236385642066,0.15676096994602595,-0.004754760360333732,-0.0855466886894718,0.2043220220493902,0.178982169335358,-1.4047101637030623,1.6606805045021122,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.175,1.0,1.0,1.0,0.0,-0.03378863654576341,-0.018387862039904893,0.5950292819935014,0.9971665251173041,-0.050867061635248366,-0.03143630567759165,-0.0456423258765567,-0.01720510045281109,-0.009232827228245479,0.0030292956725148238,-0.04415502018204746,-0.02578670129676073,-0.04079300047056705,0.22340021667565696,0.43054958593558607,-0.7661271745979715,0.34191021219892426,0.5157119820142589,-0.6182668885996174,-0.13166099545516924,0.4059608859986306,0.24226489418975664,0.07498905262711808,-0.7822023826926578,1.3864290237732266,0.0926736453420951,-0.044249628156390886,0.12148676260933966,0.07642452532500843,-0.09113442244188086,0.15706877445352152,-0.00472180562050506,-0.08571603631293945,0.204322710174622,0.18944866323849563,-1.4154523131129748,1.624004337957281,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.183333333333333,1.0,1.0,1.0,0.0,-0.0339401671775243,-0.018448827842334894,0.5950522851355619,0.9971459983799752,-0.051050064411811306,-0.0315436372803901,-0.045812092131616064,-0.0172617213881907,-0.009238351656960058,0.003036518270210973,-0.04414790863841429,-0.025757574984366625,-0.04077265245380357,0.22417227803680617,0.43017967133759727,-0.765113789972314,0.34254690704860197,0.5149513847029554,-0.6169567692659346,-0.1317002301013841,0.405246399121352,0.24396681803782752,0.0766115095587567,-0.7940414221174904,1.3998075055610295,0.0926173756981058,-0.04448596880065936,0.12169621994744695,0.0763791804072278,-0.09137440136801178,0.15734742320434814,-0.004698491735842247,-0.08567022970898952,0.20400415709491748,0.19996032486747944,-1.425622629551826,1.586328524972851,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1916666666666664,1.0,1.0,1.0,0.0,-0.03409206194837042,-0.01850972899474594,0.5950753130915658,0.9971254074719877,-0.051233026626890325,-0.03165083067853853,-0.04598177545320957,-0.017290331973229784,-0.009240854111173237,0.0030428262031189143,-0.044139294183426256,-0.025723160519805253,-0.040751977318072174,0.22494383960395872,0.42980815312224174,-0.7640989042655141,0.3431831985390447,0.5141890753247921,-0.6156444315462116,-0.1317393036507666,0.4045330488368141,0.24566496347467193,0.07832172470824274,-0.805962759851855,1.4128678325227741,0.09255494154210397,-0.04464802755877573,0.12185562527142091,0.07632875123464666,-0.09155604088964875,0.15760472626116906,-0.004681717837403676,-0.0854710128901115,0.203456183724135,0.21050324851998065,-1.4351829662018178,1.5476412379354798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2,1.0,1.0,1.0,0.0,-0.034244127997341466,-0.01857056259282915,0.5950983715570627,0.9971047534675238,-0.05141594251234288,-0.0317578661135456,-0.04615137550394675,-0.017300138932364883,-0.009241340114074768,0.003048700378268725,-0.04412961849334579,-0.025684456491437725,-0.04073114486356916,0.22571486039584124,0.429435537544951,-0.763082862884457,0.34381905290251275,0.513425450688128,-0.6143300238282484,-0.1317782587320075,0.40382188223985016,0.24735775443322977,0.08011989703408971,-0.817961138220854,1.4256015261932875,0.09248851784174728,-0.0447607284659457,0.1219810156616119,0.07627503748656395,-0.09169909493149442,0.15784725330925342,-0.004669084736503293,-0.08516905412720766,0.20275232336336269,0.22106214476410035,-1.4440860351458684,1.5079290992875727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2083333333333335,1.0,1.0,1.0,0.0,-0.03439624307914818,-0.018631326490131953,0.5951214654595085,0.9970840371266051,-0.05159880736379755,-0.03186472801495438,-0.04632089289557546,-0.017298708143597498,-0.009240692244478127,0.003054587743499316,-0.044119368419502925,-0.02564218453618266,-0.04071024538976836,0.22648531490132118,0.42906214098114265,-0.7620658873378205,0.3444544491638208,0.5126607570759338,-0.6130136439910574,-0.13181712172970833,0.40311356460136066,0.2490441688640613,0.08200609378764441,-0.8300308604376194,1.437999984177567,0.09242001400879774,-0.04484457771235517,0.12208542992809157,0.07621960930007998,-0.09181980704198844,0.15808033172937774,-0.004658453121997863,-0.08480597848578242,0.2019527294472423,0.2316201412489638,-1.4522791706418436,1.4671799877062508,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.216666666666667,1.0,1.0,1.0,0.0,-0.03454834147933851,-0.01869202063895331,0.5951446009498527,0.9970632591507806,-0.05178161970332257,-0.03197140247641065,-0.04649032787505262,-0.017292400640635735,-0.009239682759476665,0.0030608835846043774,-0.04410901167327699,-0.025596894459861415,-0.040689337448575176,0.22725519396265453,0.42868812791641175,-0.7610481057189888,0.34508937972418074,0.5118951205707615,-0.6116953516327588,-0.13185589961737412,0.4024084492650871,0.2507236332573505,0.08398023272157244,-0.8421657910648848,1.4500545259883917,0.09235113682761253,-0.044916856063442756,0.12217988552394976,0.07616387871362762,-0.09193190476838975,0.15830856371030544,-0.004647935654435997,-0.08441641969951008,0.20110714676532304,0.24215896308172447,-1.4597046982898942,1.4253829582298438,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.225,1.0,1.0,1.0,0.0,-0.03470040792291555,-0.018752645641175084,0.5951677836428609,0.9970424200112956,-0.0519643789039811,-0.032077878346109506,-0.04665968144087947,-0.01728675148518007,-0.009238937030560137,0.003067875999502036,-0.04409878136059346,-0.02554916151827089,-0.040668583246788424,0.22802450051511472,0.4283135267134186,-0.7600295559124214,0.34572384714238125,0.5111285586631273,-0.610375167929219,-0.13189458732394893,0.4017066242730355,0.25239595464348336,0.08604207650567315,-0.8543592720757843,1.461756366814731,0.09228327610052656,-0.04499262131244075,0.12227430283208829,0.07610900442681645,-0.09204739506776694,0.15853618932391678,-0.0046361094166269545,-0.08402975041719385,0.2002576467044892,0.2526593555937129,-1.466298265519368,1.382526707974563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2333333333333334,1.0,1.0,1.0,0.0,-0.03485246965073811,-0.018813203051502924,0.5951910192149735,0.9970215200335795,-0.052147085592798695,-0.03218414647617959,-0.046828955007676414,-0.017287059074566888,-0.009239094308884381,0.0030757679691538337,-0.04408895810219474,-0.025499623182467915,-0.040647960545067016,0.22879324856432998,0.42793825089453774,-0.7590102006717874,0.34635786313129435,0.510360997319632,-0.6090530818106935,-0.13193316810765124,0.40100795342480056,0.2540612607024253,0.08819122198146766,-0.8666040954902076,1.4730966377879677,0.09221791367564569,-0.0450866403712924,0.12237933147779545,0.07605629430629812,-0.09217824702981936,0.15876864904189159,-0.004621195574467385,-0.08367233175141653,0.19944131608798155,0.2631015000028353,-1.4719930592387387,1.3386021881160914,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2416666666666667,1.0,1.0,1.0,0.0,-0.03500460036435301,-0.01887369568402706,0.5952143116159535,0.9970005591936272,-0.05232974171074723,-0.032290200886089526,-0.046998149185017525,-0.01729687117307267,-0.009240599500826127,0.0030849344722553313,-0.04407972781738337,-0.025448505127689876,-0.040627778832346945,0.22956146574304215,0.4275620827072304,-0.7579899003877915,0.3469914520474862,0.5095922545459637,-0.6077290237785208,-0.13197160725019005,0.4003120854105119,0.25571997657828305,0.0904271015057204,-0.8788924897297633,1.4840664032833326,0.09215586085822458,-0.045208188410872374,0.12249988845545623,0.07600629660416969,-0.09233162308095233,0.15900703840408204,-0.0046026309158603285,-0.08336502181723326,0.19868867116965228,0.27346323086970936,-1.4767161932771478,1.2936014883685232,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.25,1.0,1.0,1.0,0.0,-0.03515688715126551,-0.018934126308392585,0.5952376693219988,0.9969795378783993,-0.0525123494443276,-0.032396034376819434,-0.04716726793302845,-0.017319248677039902,-0.009243818511488054,0.00309554080197171,-0.04407125062651801,-0.025396067153766425,-0.04060823949719369,0.23032917957863372,0.42718478108768987,-0.7569685358641964,0.34762463474136385,0.5088221369349495,-0.6064029645039588,-0.13200987862291558,0.39961853639451334,0.25737273855525283,0.09274894249596281,-0.8912160320448267,1.4946566625941098,0.0920979350073603,-0.04536528140467233,0.12264075659409013,0.07595965808165905,-0.09251377535305139,0.15925287177183112,-0.0045798538989694215,-0.0831244806412923,0.19802378781107577,0.2837217431215275,-1.4803919002720578,1.2475193959103104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2583333333333333,1.0,1.0,1.0,0.0,-0.03530945516639441,-0.01899449867474672,0.5952610959967959,0.9969584559330766,-0.052694912113763585,-0.03250164315303841,-0.04733631347296782,-0.017357864569299275,-0.009249214673873376,0.0031076095990093056,-0.044063705620424234,-0.025342857819010793,-0.04058926648014804,0.23109643132649815,0.4268059946838192,-0.75594588777789,0.3482574463488472,0.5080503582900795,-0.6050748092489903,-0.1320479381485062,0.3989266773998237,0.259020373041801,0.09515579722441253,-0.9035656880676309,1.5048583932151711,0.09204530084605422,-0.04556831859806043,0.12281023295056537,0.07591746583374026,-0.09273326093181655,0.15951092538295075,-0.004551472690762504,-0.08296717609930004,0.1974692675855949,0.2938545889100752,-1.482944006533753,1.2003535159580547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2666666666666666,1.0,1.0,1.0,0.0,-0.03546245310238251,-0.019054817357051796,0.5952845968812992,0.9969373132221113,-0.052877433607011165,-0.03260702446013554,-0.04750528893155017,-0.017415391615709815,-0.009257159090517636,0.0031213673872986657,-0.04405721464520751,-0.02528917072217831,-0.0405710316990148,0.23186326792606796,0.42642530911105553,-0.7549216986483537,0.34888992583859285,0.5072765825860859,-0.6037444490809096,-0.13208573650109495,0.39823575012619167,0.26066389301501275,0.0976465189777974,-0.9159317654870559,1.514662554526744,0.09199866371735033,-0.04582452504363954,0.12301296686191066,0.0758802536837655,-0.09299581320612482,0.1597831017246487,-0.004516859708067478,-0.0829073339280817,0.197045559985769,0.3038376982320262,-1.4842929436514396,1.152103433111682,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.275,1.0,1.0,1.0,0.0,-0.03561605121280689,-0.019115087461370063,0.5953081767366536,0.996916109510664,-0.05305991832920898,-0.032712176972805554,-0.04767419787180063,-0.017494237989363247,-0.009267969451969086,0.0031369039513666347,-0.04405187547182595,-0.025235353385094098,-0.040553650285493494,0.232629742388454,0.42604225259975853,-0.7538956716635248,0.3495221172435766,0.5065004280699774,-0.6024117575535795,-0.13212321914364067,0.3975448885010223,0.26230446570823046,0.10021975886161297,-0.9283039037951549,1.5240601171003658,0.09195870968148723,-0.04614037407756677,0.12325346831579598,0.07584859363321761,-0.09330659587516443,0.16007145581894422,-0.004475429507971862,-0.08295699455593164,0.19676992223910506,0.3136465386419346,-1.4843579890935654,1.1027720416391507,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.283333333333333,1.0,1.0,1.0,0.0,-0.03577043868696753,-0.01917531462542765,0.5953318398225639,0.9968948444699501,-0.053242371083841514,-0.03281710083498843,-0.047843044252960834,-0.017596505262736806,-0.009281933911627288,0.0031542860768886574,-0.04404776118040136,-0.0251817616700071,-0.04053722872103883,0.23339591308742608,0.4256563028764294,-0.7528674741764237,0.35015406906581314,0.5057214726548331,-0.6010765914839272,-0.13216032699289448,0.3968531335502595,0.26394339171899783,0.10287396128849631,-0.940671065305282,1.5330420885540632,0.09192604221184619,-0.046521514328240476,0.12353580200031411,0.07582298916727348,-0.09367012163012278,0.16037791840292082,-0.004426676699463283,-0.08312649108123016,0.19665723856531314,0.3232560892135569,-1.4830576535173434,1.052365464726286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2916666666666665,1.0,1.0,1.0,0.0,-0.035925821128777846,-0.019235504989519838,0.5953555898159594,0.9968735176809639,-0.05342479699318397,-0.03292179769509117,-0.04801183238683728,-0.017723997926003286,-0.009299308712199519,0.0031735533022836876,-0.04404492500254512,-0.02512876049883895,-0.04052186350310063,0.23416184309198476,0.4252668940276212,-0.7518367416301862,0.35078583372969785,0.504939259376142,-0.5997387922468641,-0.13219699708863172,0.3961594469830018,0.2655820863509857,0.10560736034850558,-0.9530215313537773,1.5415995415124706,0.09190118337134845,-0.04697277380402709,0.12386355666108573,0.0758038772858527,-0.09409024838991087,0.16070425579473024,-0.004370177224269911,-0.08342455787843428,0.1967202107408006,0.3326409505179531,-1.48031031930844,1.0008932978926,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3,1.0,1.0,1.0,0.0,-0.03608241808081062,-0.019295665158993735,0.595379429709339,0.9968521286382701,-0.05360720142044723,-0.033026270749466013,-0.04818056688749613,-0.017878225202777244,-0.009320316887303651,0.003194716390702138,-0.044043400662311646,-0.02507672515906027,-0.04050763950049473,0.23492759947694855,0.42487342331302896,-0.7508030815654057,0.35141746702057736,0.5041533018483346,-0.5983981872206817,-0.13223316327996565,0.39546272425228557,0.2672220618980112,0.1084179771304622,-0.9653429039604227,1.5497236435189399,0.09188457095186842,-0.04749815874772745,0.12423983426564034,0.0757916264054459,-0.09457017502383147,0.1610520559433848,-0.0043055896670607385,-0.08385836752385356,0.19696942890158553,0.3417754631084208,-1.476034911018047,0.9483688313056993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.308333333333333,1.0,1.0,1.0,0.0,-0.03624046052929306,-0.01935580216255829,0.5954033617050277,0.9968306767541049,-0.05378958989413204,-0.03313052478765528,-0.04834925261334779,-0.01806039589423817,-0.009345146684739444,0.0032177567095336796,-0.04404320284298641,-0.025026041009155526,-0.040494628084913845,0.23569325260784924,0.4244752580484924,-0.7497660777257589,0.35204902750312195,0.5033630897924115,-0.5970545913144744,-0.13226875691641607,0.3947618075242709,0.2688649101660121,0.11130361806697926,-0.9776221132040781,1.557405688700899,0.09187655498890834,-0.04810083806514598,0.12466723400680557,0.07578653356327458,-0.09511242763613037,0.16142271787421336,-0.00423265597739475,-0.08443352370263724,0.19741337130516734,0.35063383367204104,-1.4701515975919577,0.8948092492511384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3166666666666664,1.0,1.0,1.0,0.0,-0.03640018833924996,-0.01941592340669434,0.5954273871117876,0.9968091613630264,-0.05397196803456279,-0.03323456623243154,-0.04851789460146267,-0.01827140802570022,-0.009373949502187359,0.0032426259093951172,-0.04404432767135924,-0.024977101585122372,-0.04048288520549434,0.23645887539343036,0.42407174267860986,-0.7487252943319589,0.3526805759132986,0.5025680947210658,-0.5957078085894448,-0.13230370754625556,0.3940554988572416,0.2705122847530973,0.11426187435832955,-0.9898454305869553,1.5646371310064588,0.09187739353597346,-0.0487831152807372,0.12514782834529115,0.07578882094944839,-0.09571883668178849,0.16181743890733902,-0.0041512026864226614,-0.08515402371424674,0.19805835542964,0.3591902672887423,-1.4625825269776938,0.8402358071384297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.325,1.0,1.0,1.0,0.0,-0.036561847584027335,-0.019476036625550718,0.5954515062476653,0.9967875817273475,-0.054154341482152014,-0.033338403168272614,-0.048686497994533055,-0.01851183507827673,-0.009406837426228762,0.003269245821657615,-0.044046753179754115,-0.0249303052502094,-0.040472449534774364,0.23722454250011546,0.4236622061271468,-0.7476802805866707,0.3533121745189461,0.501767775847715,-0.594357633999352,-0.13233794362785645,0.39334257379570015,0.2721658827565061,0.11729012252179163,-1.0019984886537063,1.5714096188198727,0.09188724794526204,-0.049546392113172244,0.12568313276466903,0.07579863199139392,-0.09639050778464497,0.16223719908358358,-0.004061142736861423,-0.0860222012913725,0.1989084566190391,0.3674191049274947,-1.453252591067895,0.7846739841148853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3333333333333335,1.0,1.0,1.0,0.0,-0.036725687747982856,-0.019536149825653392,0.595475718352337,0.9967659370435286,-0.054336715827045065,-0.0334420453525562,-0.04885506796132795,-0.01878191049389484,-0.0094438805401431,0.003297508626787545,-0.04405043978245046,-0.024886050538413113,-0.04046334078500251,0.2379903295258514,0.42324596947672366,-0.7466305754525477,0.3539438864464885,0.5009615862579884,-0.5930038552713851,-0.13237139325853658,0.3926217955023854,0.27382742569674795,0.12038552610712112,-1.0140663071047535,1.577715030741707,0.09190617803955581,-0.05039112804200885,0.12627407183104955,0.0758160273088937,-0.09712778963196556,0.16268274351780354,-0.00396247770814262,-0.08703865916238174,0.19996540806200724,0.3752949654546059,-1.4420902167383742,0.7281536083826801,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.341666666666667,1.0,1.0,1.0,0.0,-0.036891958794854,-0.019596271224926336,0.5955000215120423,0.9967442264496748,-0.054519096540021406,-0.033545504204396316,-0.04902360961183348,-0.019081512039084494,-0.009485104181419938,0.003327277370561966,-0.04405533081764813,-0.024844730349853898,-0.0404555582766743,0.23875631213410806,0.4228223539931133,-0.7455757127228199,0.3545757749740943,0.5001489793538489,-0.591646254940722,-0.13240398492299216,0.3918919294763271,0.27549863955753956,0.12354503861270173,-1.026033325599346,1.5835455122929174,0.09193413757580704,-0.05131680008947592,0.12692094425897915,0.07584098086780622,-0.09793024227031988,0.16315456369330628,-0.0038553001321983693,-0.088202199978068,0.2012284945947196,0.38279289137515354,-1.4290281767366997,0.6707089518699361,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.35,1.0,1.0,1.0,0.0,-0.03706090810721731,-0.01965640918575972,0.5955244126000931,0.99672244903422,-0.05470148890475683,-0.03364879276673868,-0.04919212790856003,-0.01941014751366308,-0.00953048632959771,0.003358386899650072,-0.044061353201619226,-0.02480672517485429,-0.04044907983008773,0.23952256515211484,0.4223906894752324,-0.7445152263815648,0.35520790279428527,0.49932941555348304,-0.5902846125431633,-0.1324356482607399,0.3911517588360843,0.2771812339399933,0.12676540763004035,-1.0378834433836985,1.5888935132728725,0.09197097038296298,-0.05232186679052453,0.12762338960427,0.07587337664605287,-0.09879660894208997,0.1636528787598368,-0.003739795585977479,-0.08950976357182117,0.2026944518991869,0.3898884974244718,-1.4140044122824902,0.6123787906979805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3583333333333334,1.0,1.0,1.0,0.0,-0.03723277731452787,-0.019716572142122656,0.5955488872357629,0.9967006038458446,-0.054883897951751796,-0.03375192563812243,-0.04936062757573986,-0.01976694318806437,-0.009579955299506638,0.0033906452731558815,-0.04406841823194687,-0.0247723955485604,-0.04044386104151308,0.24028916164049077,0.4219503228799379,-0.7434486562294154,0.35584033125152853,0.4985023692048141,-0.5889187069613914,-0.13246631484942512,0.39040010008346343,0.278876880422526,0.13004318023644293,-1.049600065804054,1.593751825471217,0.09201640752644569,-0.05340374004165649,0.12838035908388834,0.07591300610280571,-0.09972479437365789,0.16417761788543483,-0.003616244261081536,-0.09095637790777822,0.2043573818587141,0.396558121014689,-1.396962857460422,0.5532064278325866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3666666666666667,1.0,1.0,1.0,0.0,-0.03740779903841258,-0.01977676852098574,0.5955734397640814,0.9966786899046154,-0.05506632839439258,-0.03385491887141767,-0.04952911300833541,-0.02015063623970698,-0.009633387906442435,0.0034238356882865806,-0.044076422565771434,-0.02474207396746316,-0.04043983499577791,0.24105617194422227,0.4215006271412048,-0.7423755537301666,0.35647311956266536,0.4976673356472554,-0.5875483189117394,-0.13249591899842458,0.38963581920428797,0.2805871903043052,0.13337470964695183,-1.0611661576747056,1.5981136204034156,0.09207006581629706,-0.054558768192433105,0.12919009286300964,0.07595956671362258,-0.10071185216172895,0.16472840468279237,-0.0034850217354143176,-0.09253513041412753,0.20620869398879416,0.4027789734367071,-1.3778542538607175,0.4932396743997325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.375,1.0,1.0,1.0,0.0,-0.037586193594058084,-0.019837006658591387,0.595598063258666,0.9966567062142897,-0.05524878456773772,-0.03395778983788405,-0.04969758818292049,-0.02055957232598926,-0.009690608258019064,0.003457718937359363,-0.04408524938812135,-0.024716056529031378,-0.04043691245537977,0.24182366273742906,0.42104101007673067,-0.7412954880150319,0.3571063240300889,0.49682383833545196,-0.5861732335500115,-0.13252439854501535,0.38885784790989464,0.2823136919890059,0.13675616312705471,-1.0725643033683994,1.6019724867112126,0.09213144793343286,-0.05578223336482613,0.13005010595933397,0.076012661800966,-0.10175398359641319,0.16530454468261402,-0.003346598701639003,-0.09423716564229134,0.2082370818861401,0.40852929062424104,-1.3566369424946245,0.43253078638097353,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3833333333333333,1.0,1.0,1.0,0.0,-0.03776816569548027,-0.01989729471237773,0.5956227495492056,0.9966346517756766,-0.055431270370711425,-0.03406055705604471,-0.04986605657257753,-0.02099170927262867,-0.00975138731165398,0.00349203639095379,-0.044094769774485794,-0.024694594581761625,-0.04043498255282439,0.24259169607644615,0.420570923251791,-0.7402080519641777,0.35773999725934813,0.4959714359206485,-0.5847932431670292,-0.1325516956434519,0.38806519977691645,0.28405780833574085,0.14018353115735585,-1.0837767733829493,1.6053224668430985,0.0921999443981697,-0.0570683655390436,0.13095718467915685,0.07607180185074669,-0.10284654989878961,0.16590501676233327,-0.0032015394415618736,-0.09605171430897119,0.21042854247743104,0.4137884822032767,-1.3332776188457451,0.3711363537902779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3916666666666666,1.0,1.0,1.0,0.0,-0.03795390121995073,-0.019957640569619902,0.5956474892745818,0.9966125256008914,-0.055613789212437564,-0.034163239986120635,-0.05003452106796623,-0.021444627667532152,-0.009815443316577287,0.003526513479448716,-0.044104844241463506,-0.024677886693731346,-0.040433913997312894,0.24336032847739855,0.42008987065107994,-0.7391128682703793,0.358374187394268,0.49510972917047213,-0.5834081499373059,-0.13257775753570805,0.3872569860047451,0.28582083436362976,0.14365263783044266,-1.0947855970158284,1.6081580926077172,0.0922748375481347,-0.05841037541758132,0.13190739520394068,0.07613640745933625,-0.1039840994277863,0.1665284693502489,-0.0030504988771978825,-0.09796615773874917,0.21276644445893944,0.4185372774786311,-1.307752036075982,0.309117139979902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4,1.0,1.0,1.0,0.0,-0.03814356409262471,-0.020018051754091614,0.5956722719619014,0.9965903267283012,-0.055796343963466874,-0.03426585879208909,-0.0502029839066549,-0.021915548931381656,-0.009882443234427222,0.003560863622089341,-0.04411532446972686,-0.024666071259398653,-0.04043355678998801,0.24412961003558173,0.41959741699483133,-0.7380095953774454,0.3590089373836704,0.4942383675968521,-0.5820177686778584,-0.1326025372914052,0.38643243048127063,0.28760391574338984,0.14715915244866637,-1.1055726406508823,1.610474419176097,0.09235530762773447,-0.059800507477092424,0.1328961055972444,0.07620581400454407,-0.10516041093040385,0.16717322211195595,-0.002894218074262489,-0.09996613052005499,0.2152316506696761,0.4227578669495169,-1.280045640946188,0.246537869420842,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.408333333333333,1.0,1.0,1.0,0.0,-0.038337293356213276,-0.020078535332260804,0.5956970861309044,0.9965680542379076,-0.055978936912635384,-0.03436843407477339,-0.050371446612666605,-0.02240136118762393,-0.00995200520308627,0.003594792530852163,-0.04412605517478045,-0.02465922006401456,-0.0404337444241318,0.24489958360452746,0.41909319552646174,-0.7368979331770918,0.35964428429434375,0.4933570556549654,-0.5806219295687733,-0.13262599450361243,0.38559088382941087,0.2894080285414577,0.15069860227960127,-1.1161196910315982,1.6122670570980646,0.09244044102051485,-0.06123011394099209,0.13391802209253623,0.07627927807668633,-0.10636855337112339,0.16783727368447243,-0.0027335181257859276,-0.1020356628387975,0.2178026972593039,0.4264340378978859,-1.2501541269979333,0.18346696315914013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4166666666666665,1.0,1.0,1.0,0.0,-0.03853520049212605,-0.020139097820706595,0.5957219194223773,0.9965457072668784,-0.05616156973024573,-0.034470986580681484,-0.050539909947973555,-0.02289865298132506,-0.010023702074957832,0.003628002797261858,-0.044136876093433315,-0.024657333111770714,-0.04043429652863864,0.2456702840525903,0.4185769150958148,-0.7357776283425698,0.3602802586849485,0.492465558374,-0.5792204807831172,-0.13264809592683496,0.384731836100624,0.29123396069771157,0.15426638641363113,-1.1264085427675146,1.613532201895416,0.09252924058048007,-0.06268974966925023,0.1349672400610169,0.07635598564518009,-0.10760096229340377,0.16851831585460442,-0.0025692923995163097,-0.10415736247566865,0.22045603041619177,0.4295513025588654,-1.2180838900173185,0.11997622213789416,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.425,1.0,1.0,1.0,0.0,-0.03873736705871037,-0.02019974509657105,0.5957467587483489,0.9965232850249072,-0.05634424343818892,-0.034573536892539065,-0.05070837387738481,-0.023403754606269426,-0.010097066024048322,0.003660198653460845,-0.04414762404785333,-0.024660334995552997,-0.0404350218958891,0.24644173761420213,0.41804836636530757,-0.7346484791760749,0.36091688405509675,0.4915637062834087,-0.5778132909711966,-0.13266881604360437,0.3838549277881497,0.2930822957150609,0.15785779065558236,-1.1364210891985536,1.6142666608003629,0.09262063794153619,-0.06416928718614212,0.13603730955503712,0.0764350618734988,-0.10884953205451464,0.16921375438398112,-0.0024024971907948833,-0.10631263489657927,0.22316629917245479,0.4320970173624661,-1.183852371800178,0.05614045968330483,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.433333333333333,1.0,1.0,1.0,0.0,-0.03894384270891471,-0.02026048231292966,0.5957715904610219,0.9965007868090633,-0.056526958387524015,-0.03467610510853245,-0.05087683754791953,-0.023912786501581136,-0.010171594177342905,0.003691090786566189,-0.04415813504474163,-0.024668073042584567,-0.04043572181944023,0.2472139613516159,0.41750742697604576,-0.7335103398499858,0.36155417638284015,0.4906513995064248,-0.5764002515433841,-0.13268813754668154,0.3829599588523477,0.2949533990172525,0.16146800336967224,-1.1461394156308509,1.614467876223471,0.09271350760801489,-0.06565805027738181,0.13712131479080458,0.0765155824322361,-0.11010572265648388,0.16992073646965533,-0.002234140883228264,-0.10848193828301267,0.2259067004832893,0.4340604917334745,-1.1474882797783437,-0.007962914343813132,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4416666666666664,1.0,1.0,1.0,0.0,-0.03915464364389022,-0.020321313820973384,0.5957964005366416,0.9964782120177764,-0.05670971424391174,-0.03477871051813625,-0.051045299283354134,-0.024421713885859148,-0.01024675518650462,0.0037204010780338198,-0.044168246364639716,-0.02468031741299168,-0.04043619365357619,0.24798696274100238,0.4169540655273512,-0.7323631239295615,0.3621921437623007,0.4897286109058006,-0.5749812786967023,-0.1327060517249915,0.38204689548343285,0.2968474073897824,0.1650921321844736,-1.155545893861526,1.6141339455612993,0.09280668255718272,-0.0671449638188315,0.13821196639951738,0.07659658610126852,-0.11136067929300997,0.17063618459887575,-0.002065271778525224,-0.11064506880479996,0.22864937047658573,0.43543308495482214,-1.109031672132308,-0.07225435398152236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.45,1.0,1.0,1.0,0.0,-0.03936975155081677,-0.02038224310083646,0.5958211747698667,0.9964555601636105,-0.05689250998115976,-0.0348813712829892,-0.051213756594192535,-0.024926406520827546,-0.010321996617566298,0.003747867137748157,-0.04417779859580042,-0.024696763258058717,-0.0404362344967452,0.24876073939423562,0.4163883442457319,-0.7312068070766605,0.36283078615119463,0.4887953881848746,-0.5735563151334029,-0.1327225587429903,0.3811158743722677,0.2987642218585289,0.1687252214522526,-1.164623276833056,1.6132636369904456,0.09289897102009614,-0.06861871678089493,0.13930170475052073,0.0766770883966783,-0.11260536217222117,0.17135683632174548,-0.001896964812078128,-0.11278147001393068,0.2313658136045127,0.43620828964078373,-1.068533900581401,-0.13665267717489105,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4583333333333335,1.0,1.0,1.0,0.0,-0.03958911306278944,-0.020443272702778348,0.595845898973715,0.9964328308844911,-0.057075343882986115,-0.03498410413155291,-0.05138220620285208,-0.025422702251942937,-0.010396753000881677,0.00377324650639425,-0.04418663756832325,-0.02471703496535667,-0.04043564489453539,0.24953527892467064,0.4158104202476696,-0.7300414288503861,0.36347009523557866,0.4878518548695969,-0.5721253314246733,-0.1327376678051928,0.380167204316534,0.3007035042831909,0.17236227034515333,-1.1733547922045493,1.6118564009417178,0.0929891740539518,-0.07006793472273287,0.14038281216498527,0.07675609591324406,-0.11383068368989502,0.17207928923503202,-0.0017303074211072467,-0.11487055900038512,0.23402735951268294,0.4363818004374226,-1.0260574060399552,-0.20107559912892814,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.466666666666667,1.0,1.0,1.0,0.0,-0.0398126397662688,-0.020504404200234354,0.5958705591798497,0.9964100239530826,-0.05725821355294942,-0.035086924076210876,-0.05155064408340281,-0.025906472773545946,-0.010470454353082175,0.003796320408945023,-0.04419461614773028,-0.02474069243291777,-0.040434232455727956,0.2503105589618015,0.41522054533368635,-0.7288670935405774,0.36411005441641536,0.48689821012337636,-0.5706883269794857,-0.13275139720000875,0.3792013650555946,0.30266467785040696,0.17599825145954298,-1.1817242336003886,1.6099123770049635,0.09307610347866868,-0.0714813575867157,0.14144753142440347,0.07683262103832744,-0.11502764963408296,0.1728000502489646,-0.0015663848725655516,-0.11689206097556193,0.23660563587886152,0.43595156666839996,-0.9816753656750432,-0.2654402916557519,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.475,1.0,1.0,1.0,0.0,-0.04004020876779647,-0.020565638155996616,0.5958951418338637,0.9963871392840491,-0.05744111593233644,-0.035189844161027745,-0.05171906551476445,-0.02637368992287261,-0.010542534958782612,0.0038168969573369915,-0.04420159585154265,-0.024767239228063894,-0.040431815277527504,0.2510865473159818,0.414619064287891,-0.7276839699933128,0.3647506389195508,0.48593472737569554,-0.5692453305871905,-0.13276377421973556,0.37821900330027464,0.3046469315478386,0.17962812978962667,-1.1897160482991334,1.6074323960807886,0.09315859972620189,-0.07284801824823162,0.14248818764093008,0.07690569666937375,-0.11618750083482898,0.17351558802159772,-0.0014062653889651555,-0.11882634329835162,0.23907304437199794,0.4349178277807081,-0.9354711934809501,-0.3296639601913176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4833333333333334,1.0,1.0,1.0,0.0,-0.040271663816947245,-0.02062697410247798,0.5959196339803354,0.9963641769389879,-0.05762404732563927,-0.0352928752475914,-0.051887465145875125,-0.026820490729959654,-0.010612442183732598,0.0038348137192866097,-0.04420744825875126,-0.02479613240416777,-0.04042822508266017,0.2518632022905715,0.4140064116962158,-0.7264922904132286,0.3653918160275716,0.4849617517761292,-0.567796400512459,-0.1327748349564915,0.37722092600062207,0.30664922858994026,0.18324688192255478,-1.1973154201584044,1.6044179776684415,0.09323554914505205,-0.0741574170978021,0.1434973103329984,0.07697439056040589,-0.11730185153905781,0.17422238728428185,-0.0012509854289466382,-0.12065473967955653,0.24140322631875155,0.4332831306189655,-0.8875379001684358,-0.39366442938427504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4916666666666667,1.0,1.0,1.0,0.0,-0.04050681696739911,-0.020688410536663922,0.5959440234327432,0.9963411371288876,-0.05780700343310995,-0.03539602584523892,-0.05205583707101029,-0.027243239445855674,-0.010679645084255712,0.0038499395930350227,-0.04421205618911898,-0.024826793675118856,-0.04042330998202699,0.252640473135066,0.413383107336261,-0.7252923481544294,0.3660335454288909,0.48397969651671124,-0.5663416241324525,-0.13278462397688467,0.376208090972282,0.30867031865315114,0.18684951529994276,-1.204508346635274,1.6008713222577173,0.09330590031408237,-0.0753996879463048,0.14446775244907784,0.07703781892924311,-0.11836282080787797,0.17491700367217033,-0.0011015354830379298,-0.122359855414923,0.24357150467542055,0.4310523277676498,-0.8379773218096354,-0.4573607276335201,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5,1.0,1.0,1.0,0.0,-0.04074545074320651,-0.020749944929979662,0.5959682989238596,0.9963180202140273,-0.057989979389744165,-0.03549930199056195,-0.052224174913170475,-0.02763858484197369,-0.01074364258064376,0.003862175953383065,-0.04421531463676802,-0.024858621586873297,-0.040416936791116374,0.25341830062913956,0.4127497502304441,-0.7240844945390773,0.3666757796763923,0.4829890380959979,-0.5648811171179229,-0.1327931938812088,0.37518159507704,0.31070875366786394,0.19043108738534895,-1.2112817088552317,1.5967952988745495,0.09336867894942258,-0.07656575075571159,0.1453928031145857,0.07709515897814212,-0.11936315340463799,0.1755961176152443,-0.0009588467361931752,-0.12392584501802806,0.24555528952425187,0.42823255644874436,-0.786899230120679,-0.5206736607085727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5083333333333333,1.0,1.0,1.0,0.0,-0.04098732076346817,-0.020811573752911358,0.5959924502329421,0.9962948267013148,-0.05817296980993071,-0.03560270717946732,-0.052392471913276874,-0.02800351121655783,-0.010803970974651739,0.003871457059773738,-0.0442171314503246,-0.024891004282510263,-0.040408992845648396,0.25419661778422303,0.41210701149033246,-0.7228691347691864,0.36731846474519325,0.48199031062663394,-0.5634150221721984,-0.13280060475582123,0.37414266022198156,0.3127629068118887,0.1939867245740885,-1.217623333803952,1.5921934279125745,0.09342300103502899,-0.07764744709334304,0.14626629103980937,0.07714566001675305,-0.1202963269594104,0.1762565858442322,-0.0008237789253257022,-0.1253386545249291,0.24733443550611134,0.42483319774443196,-0.734420340374986,-0.5835263646457989,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5166666666666666,1.0,1.0,1.0,0.0,-0.04123215876620054,-0.020873292513834095,0.5960164682868768,0.9962715572391264,-0.058355968836905324,-0.03570624235331141,-0.05256072102282336,-0.02833538175484237,-0.010860210613107903,0.0038777497428998707,-0.04421742775944893,-0.024923332434277093,-0.04039938728119647,0.25497535064639004,0.4114556261122217,-0.7216467230217471,0.36796154067667153,0.4809840993133411,-0.5619435073538523,-0.13280692352996423,0.37309261750162453,0.31483099425963246,0.19751164068108948,-1.2235220478614814,1.5870698594637862,0.0934680838682056,-0.07863765478241747,0.14708267582405066,0.07718865292404065,-0.1211566426464139,0.17689548912399378,-0.0006971096838931379,-0.126586221984768,0.24889154132001212,0.4208658162234302,-0.6806632355627151,-0.6458448284908069,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.525,1.0,1.0,1.0,0.0,-0.04147967596188284,-0.020935095811135236,0.5960403452333671,0.9962482126097935,-0.05853897019607588,-0.035809905938822634,-0.052728914997632485,-0.028631973156716367,-0.010911991529728302,0.0038810524106266476,-0.04421613815456591,-0.024955011913830975,-0.04038805176162151,0.25575441918202646,0.4107963839106255,-0.7204177568387855,0.36860494229392726,0.4799710332491937,-0.5604667640201318,-0.13281222325055278,0.37203288985556876,0.3169110991672222,0.201001154844479,-1.2289677210633305,1.5814293474377277,0.0935032547842718,-0.0795303789394819,0.14783712480328726,0.07722355774277267,-0.12193929717742469,0.17751017494622934,-0.0005795256180990416,-0.12765863116750098,0.2502121835684046,0.41634408037930615,-0.6257552274463318,-0.7075583781417993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.533333333333333,1.0,1.0,1.0,0.0,-0.041729566639258295,-0.020996977397390433,0.5960640744852511,0.9962247937199384,-0.058721967251234984,-0.035913693939757546,-0.052897046490446714,-0.028891500756290486,-0.010958997933807082,0.0038813934340447497,-0.04421321063277694,-0.024985475791471347,-0.04037494066130018,0.2565337382261279,0.41013011979656366,-0.7191827709416924,0.3692485999723844,0.47895177769371733,-0.5589850044380819,-0.13281658229026588,0.37096497364883285,0.31900119731910587,0.20445070868741125,-1.2339513016522536,1.5752772198280895,0.09352795740462438,-0.08032081741424224,0.148525573592857,0.07724988926590459,-0.12264043456307161,0.17809829408269362,-0.0004716153031436576,-0.12854821523142324,0.2512850796877186,0.4112836646289192,-0.5698271765220753,-0.7686001135152765,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5416666666666665,1.0,1.0,1.0,0.0,-0.04198151194085432,-0.021058930254068246,0.596087650735999,0.996201301588927,-0.058904953062654114,-0.036017600076601354,-0.05306510814024931,-0.029112930846023274,-0.011001111035899628,0.003878975196417801,-0.0442089245849877,-0.02501396884510252,-0.04036004071020983,0.25731321847210353,0.40945770362038814,-0.7179423306122379,0.369892440448359,0.47792702600647585,-0.5574984591187536,-0.13282008350560517,0.3698904196017117,0.3210991838286842,0.20785588258829432,-1.2384648406720318,1.5686193455458064,0.09354227467796128,-0.0810063875689182,0.14914527936819244,0.0772677235214636,-0.12325820365122975,0.1786584140018066,-0.00037341192453632654,-0.12925098092099185,0.25210346010024587,0.40570279398769116,-0.5130127853555111,-0.828907813286639,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.55,1.0,1.0,1.0,0.0,-0.04223518905070743,-0.021120948174205765,0.5961110722386671,0.9961777374095434,-0.059087922994487715,-0.036121613959106263,-0.05323309295554361,-0.029294806429911852,-0.011037860352357775,0.003873550816898358,-0.044202602269277004,-0.025040584196585298,-0.04034327890676385,0.25809277613742726,0.4087800133370817,-0.7166970162855558,0.3705363953644088,0.47689747429953017,-0.5560073642047184,-0.1328228058223415,0.368810790633483,0.32320292165410996,0.21121242192053943,-1.2425015147415122,1.5614620896066456,0.093544841476082,-0.0815828317543632,0.14969301590579187,0.07727585889950483,-0.12378869819867022,0.17918793641368502,-0.0002860312271418808,-0.12976119529445884,0.252660335235404,0.3996196912254202,-0.45544532099326407,-0.8884221723821284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.558333333333333,1.0,1.0,1.0,0.0,-0.04249025387504456,-0.02118302003579739,0.5961343310153697,0.9961541022159384,-0.05927086452470796,-0.036225730334181146,-0.053400992702127,-0.029436438379441814,-0.011069056446566663,0.003865253246245888,-0.04419421621536987,-0.0250647873442371,-0.04032468640767856,0.25887229916337157,0.4080979897578154,-0.715447447013808,0.3711803714300174,0.475863881036498,-0.5545119935118589,-0.1328248506927242,0.3677277330134707,0.3253101894159409,0.21451621077538466,-1.2460555960219195,1.5538123093394376,0.09353530758863915,-0.08204821238993798,0.15016633022590264,0.07727394565685053,-0.1242302678642393,0.17968492362531618,-0.00021000633386114576,-0.13007706155122256,0.2529527550215793,0.39305491422800987,-0.397259002308763,-0.9470891568126083,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5666666666666664,1.0,1.0,1.0,0.0,-0.04274637197977235,-0.021245138114660705,0.5961574284558644,0.9961303974222453,-0.059453772539839064,-0.03632993440138617,-0.053568800914282635,-0.02953846886797763,-0.011094905295886581,0.0038545407580726707,-0.044184437805418086,-0.025085585499614066,-0.04030441002899597,0.25965169793057125,0.4074125431305827,-0.7141942441151241,0.37182429445868964,0.4748269698351262,-0.5530126154776298,-0.13282630592790584,0.3666428396076293,0.3274188009044696,0.21776333715767293,-1.2491224981133249,1.5456772703264354,0.0935147334145281,-0.08240465102350658,0.15056529972817145,0.07726288335583198,-0.12458505618152094,0.18014935402497434,-0.00014476337614643953,-0.13020272111826436,0.25298435056371527,0.38603197993473115,-0.33858822035786496,-1.0048613769833503,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.575,1.0,1.0,1.0,0.0,-0.04300321074482564,-0.021307293349458543,0.596180364115679,0.9961066243449305,-0.05963663962602777,-0.036434212456025225,-0.0537365112901624,-0.029602188071765144,-0.011115342647632127,0.00384135435726749,-0.044172863170164736,-0.025102920680689346,-0.04028265554182701,0.2604308780536137,0.40672457890742364,-0.7129380253516718,0.3724680861526146,0.47378746343347267,-0.5515095042781093,-0.13282726341565998,0.36555768766149965,0.3295265952586695,0.22095007710763018,-1.251698733027884,1.5370646197230484,0.09348298344708295,-0.08265579794439648,0.15089248725566273,0.07724250231133989,-0.12485582715562327,0.18058174150451523,-9.090703876502015e-05,-0.13014356325312115,0.25276128616364746,0.3785738461730631,-0.2795644558934951,-1.0616971004188391,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5833333333333335,1.0,1.0,1.0,0.0,-0.04326045685519325,-0.02136947555291996,0.5962031370024354,0.9960827841601191,-0.05981945719957005,-0.03653854948538903,-0.05390411896764674,-0.02962764743428425,-0.011130400818313815,0.0038259387390485074,-0.04415971848615934,-0.025116759397098426,-0.040259272304739205,0.2612097476546893,0.4060349464981761,-0.7116793693275297,0.373111669497212,0.47274603938253246,-0.5500029197858879,-0.1328278210452186,0.36447378022007726,0.3316314890071971,0.22407290126055732,-1.2537819057115498,1.527982318652788,0.09344010719288587,-0.08280169156357209,0.1511469680217492,0.0772128904826741,-0.12504261723460752,0.18098144416329287,-4.7719103693499854e-05,-0.12990338012456526,0.2522905822980359,0.37070638205597584,-0.22031486139473255,-1.1175563045581693,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.591666666666667,1.0,1.0,1.0,0.0,-0.043517778849455006,-0.02143167626603573,0.5962257511024469,0.9960588785274357,-0.0600022197713682,-0.03664293134332822,-0.05407161650758847,-0.0296152298682025,-0.011140100012885698,0.0038083838271751494,-0.04414504683906309,-0.025127074492536556,-0.04023413361477541,0.26198821317349513,0.40534455071469744,-0.710418909217976,0.3737549676606592,0.4717034198128959,-0.5484931468753877,-0.13282805873405487,0.36339263132609023,0.3337314382969701,0.2271285168085631,-1.2553706473844628,1.5184386813137456,0.09338603505445242,-0.08284316124866464,0.15132835750608198,0.07717397533358761,-0.12514587435272007,0.18134761306200176,-1.487587728166151e-05,-0.12948640311883142,0.25157916495320176,0.362455357969273,-0.16096236842787714,-1.1724041769857774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6,1.0,1.0,1.0,0.0,-0.043774869857790145,-0.021493885446147436,0.5962482068378566,0.99603490872771,-0.06018491913709591,-0.036747342714179836,-0.05423899803361203,-0.029567184590197228,-0.01114454877519254,0.0037887609842128366,-0.04412862494906275,-0.025133614993596155,-0.0402075344508925,0.2627661815722635,0.4046542271440317,-0.7091572300357617,0.37439790241943843,0.4706602748099871,-0.5469804595681879,-0.13282806897650662,0.36231567350143007,0.33582447508975044,0.23011382389337853,-1.2564646118520144,1.5084422490363585,0.09332105151993231,-0.08278643917100648,0.15144057276305523,0.07712589181782192,-0.1251704453985114,0.18168120195264592,7.06243914183613e-06,-0.12890231492293847,0.2506384096142089,0.35384607530875134,-0.10162654819373618,-1.2262143045289742,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6083333333333334,1.0,1.0,1.0,0.0,-0.0440314358481086,-0.021556093034239155,0.5962705069886995,0.9960108761609124,-0.060367547725153556,-0.03685176760430008,-0.05440625860378229,-0.029485205485474005,-0.011143933236176339,0.003767331738434192,-0.04411057512434392,-0.025136313881963426,-0.040179617568622074,0.26354356403216067,0.403964776728514,-0.7078948996719251,0.3750403991909562,0.4696172457229207,-0.5454651268428437,-0.13282794102673584,0.3612442594107079,0.3379087451238736,0.2330259513970423,-1.2570644231876917,1.4980017762382627,0.0932456439241014,-0.0826361421932198,0.15148612734766642,0.07706904684695148,-0.12512005689552463,0.18198299106843674,1.849429974165595e-05,-0.1281609855326471,0.24948225282958925,0.3449059495815854,-0.0424208665732273,-1.2789635878825445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6166666666666667,1.0,1.0,1.0,0.0,-0.04428719855853693,-0.021618289181414025,0.5962926547658004,0.995986782199593,-0.060550098276210884,-0.0369561901666114,-0.05457339361640289,-0.029371272656534803,-0.011138471855727756,0.003744256742514318,-0.04409096295669908,-0.025135227631338845,-0.040150470859536824,0.2643202756376652,0.40327695810747805,-0.7066324612466339,0.3756823865335543,0.46857494052839505,-0.5439474097170472,-0.1328277607381776,0.36017965707588595,0.33998251263691026,0.23586225638640496,-1.2571716262949015,1.487126189238316,0.09316028861014458,-0.08239763362617669,0.15146822644484637,0.07700382234475223,-0.12499893948677898,0.18225405027706199,1.9827100526392805e-05,-0.12727299559203487,0.24812549099707648,0.3356624705638239,0.01654734890824905,-1.3306338257840578,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.625,1.0,1.0,1.0,0.0,-0.04454189724429594,-0.021680464222803335,0.5963146537293197,0.9959626281836297,-0.06073256375494084,-0.03706059489337706,-0.054740398860969305,-0.029227548628825255,-0.011128406552603623,0.0037196987969567814,-0.044069841403202366,-0.02513045873009031,-0.04012019444943435,0.2650962355089964,0.4025914828347444,-0.7053704292311777,0.3763237962300354,0.4675339300648077,-0.542427559338226,-0.1328276105750604,0.35912304281750734,0.34204416997382486,0.23862032590643936,-1.256788634039221,1.4758245458085284,0.0930654893580396,-0.08207677495691956,0.15139048905197683,0.07693062183347976,-0.1248117190662057,0.1824956658986321,1.1482631162573753e-05,-0.126249666047219,0.2465839514965007,0.3261432837301831,0.0751773130787381,-1.3812115520997326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6333333333333333,1.0,1.0,1.0,0.0,-0.04479528999225621,-0.021742608720129626,0.596336507678345,0.9959384154106777,-0.06091493735056213,-0.03716496681732799,-0.05490727054145172,-0.029056329041815283,-0.01111400194750466,0.0036938170806724764,-0.044047262821596427,-0.025122156628685506,-0.040088894604497334,0.26587136712696585,0.40190901185819605,-0.704109286429101,0.3769645635641123,0.46649474521062495,-0.5409058152854034,-0.13282756936099155,0.35807549597509897,0.34409224516185194,0.241297977781908,-1.2559186710769226,1.4641059967033205,0.09296178616318818,-0.0816797864188068,0.1512568538383885,0.07684988023234807,-0.12456330971785445,0.18270931224334763,-6.0860114664551546e-06,-0.1251028411444699,0.24487422357282296,0.31637605381497125,0.1333751256024529,-1.4306877949381258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6416666666666666,1.0,1.0,1.0,0.0,-0.04504715464521199,-0.021804713516617884,0.5963582205356284,0.9959141451270742,-0.061097212490991405,-0.03726929170383852,-0.055074005279567816,-0.028859997660433668,-0.011095540970126258,0.003666764149896311,-0.044023280600597944,-0.025110514495244898,-0.040056679619918226,0.2666455986117162,0.4012301530610976,-0.7028494816672045,0.3776046275672412,0.46545787490284346,-0.5393824041341702,-0.13282771200858484,0.3570379954650995,0.3461254070333719,0.24389326013668888,-1.25456571527918,1.4519797492262263,0.09284974748742125,-0.08121312462884278,0.15107149593662106,0.07676205809239445,-0.12425881670817152,0.18289661860320328,-3.239607705929348e-05,-0.12384467369554786,0.2430133656251532,0.3063883105464371,0.19105400834269037,-1.4790578252484865,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.65,1.0,1.0,1.0,0.0,-0.045297289361514254,-0.02186676978917188,0.5963797962373502,0.9958898185200626,-0.06127938285693389,-0.03737355622229294,-0.055240600105801785,-0.02864098458098216,-0.01107331968744678,0.0036386840330548263,-0.04399794891640384,-0.025095763800474014,-0.040023657139195,0.2674188629184229,0.4005554597810487,-0.7015914281634906,0.37824393119898553,0.4644237649321554,-0.5378575383086833,-0.1328281092956092,0.35601141808017317,0.34814246792227116,0.24640444962434863,-1.2527344376045444,1.439455032949179,0.09272996022485214,-0.08068336970148748,0.15083874772050754,0.076667633445483,-0.1239034467574418,0.1830593344564746,-6.694192362599605e-05,-0.12248742442143468,0.24101862364449333,0.29620729773610577,0.2481344437024502,-1.5263208917547866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.658333333333333,1.0,1.0,1.0,0.0,-0.045545512836957416,-0.02192876909372183,0.5964012386312896,0.9958654367114909,-0.06146144239258636,-0.03747774809203505,-0.05540705244284717,-0.028401727874997822,-0.011047642166081959,0.0036097108379060487,-0.04397132207032025,-0.025078168123794334,-0.039989932328222476,0.2681910979487971,0.3998854302327395,-0.7003355025385294,0.3788824214579993,0.4633928174568861,-0.5363314152265622,-0.13282882770731194,0.35499653839140893,0.35014238409411347,0.24883004843229065,-1.2504301412174725,1.4265410676969799,0.09260301996425913,-0.0800971216629498,0.1505630242658862,0.07656709373427661,-0.12350242561565805,0.18319929475637764,-0.00010920321637963859,-0.12104327940841042,0.2389071724643954,0.2858598313735944,0.3045442214139138,-1.5724799444558846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6666666666666665,1.0,1.0,1.0,0.0,-0.045791664219452494,-0.02199070340265817,0.5964225513848015,0.995841000752955,-0.061643385312152826,-0.037581856201661434,-0.05557336008420112,-0.02814463906472659,-0.011018815640540892,0.0035799677083263714,-0.04394345375482364,-0.025058016824762004,-0.03995560657316432,0.26896224658449386,0.39922050775333284,-0.6990820444257259,0.37952004942789014,0.46236539117189446,-0.5348042167294104,-0.13282992934921553,0.353994030090033,0.3521242541300111,0.25116878014724187,-1.2476587005809792,1.4132470338749143,0.09246952208576076,-0.07946090710074016,0.1502487547075626,0.0764609283592288,-0.12306092368924659,0.18331838660382127,-0.0001586532712438693,-0.11952418807850029,0.23669588519169116,0.2753721689844918,0.3602184026458488,-1.6175413512832693,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.675,1.0,1.0,1.0,0.0,-0.0460356027502148,-0.022052565134220183,0.5964437379031974,0.9958165116223159,-0.06182520610211933,-0.03768587070207862,-0.05573952116962286,-0.02787207273912826,-0.010987146104004133,0.0035495660720949933,-0.043914396344619126,-0.025035618908177813,-0.03992077653376358,0.26973225665022643,0.3985610817810605,-0.6978313566267367,0.3801567702639864,0.4613418020620653,-0.5332761087831652,-0.13283147192849934,0.3530044685901006,0.354087315513975,0.2534195845820322,-1.244426501173375,1.399582045175592,0.09233005382202952,-0.07878109687882162,0.14990032042998536,0.07634962198134088,-0.12258399038135637,0.1834185181458392,-0.00021476700147127215,-0.1179417230205182,0.23440113341841262,0.2647698913819574,0.4150992110636187,-1.661514612874404,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.683333333333333,1.0,1.0,1.0,0.0,-0.04627720716725794,-0.02211434717408652,0.5964648012586682,0.9957919702214837,-0.062006899519491045,-0.03778978307468459,-0.055905534158648504,-0.02758630048068959,-0.010952934380436409,0.003518605144165612,-0.04388420024177318,-0.025011297275101464,-0.03988553346537425,0.270501080814861,0.39790748947201915,-0.6965837057518928,0.38079254312757915,0.4603223246655385,-0.5317472414269797,-0.13283350879924005,0.3520283347063577,0.3560309396869846,0.2555816116702745,-1.2407403803965855,1.385555123660341,0.09218518731996861,-0.07806383539068151,0.14952200068930388,0.07623364862530235,-0.12207649752425831,0.183501590236399,-0.00027702821602526573,-0.1163069621646573,0.23203861917523882,0.2540777974136632,0.46913586083180636,-1.7044120800994556,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6916666666666664,1.0,1.0,1.0,0.0,-0.046516374907807516,-0.022176042889606395,0.5964857441295346,0.9957673773753545,-0.062188460586295256,-0.03789358617663434,-0.05607139780306334,-0.027289489132477154,-0.010916472706167187,0.0034871716543051876,-0.04385291328291667,-0.02498538348270491,-0.03984996275978469,0.2712686764388926,0.39726001785788245,-0.695339323281915,0.3814273310744081,0.45930719376999435,-0.5302177489458919,-0.1328360890654331,0.35106601922068964,0.3579546258335623,0.25765421453892656,-1.2366075701595116,1.3711751771739344,0.09203547370283505,-0.07731498144388893,0.1491179259620523,0.07611346659209706,-0.12154309198621593,0.1835694711923086,-0.00034493614959496544,-0.114630393056383,0.22962323840469923,0.24331981196747177,0.5222843315851788,-1.7462486784229547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7,1.0,1.0,1.0,0.0,-0.04675302114593189,-0.022237646137221536,0.5965065687493508,0.9957427338317686,-0.06236988458069479,-0.03799727426554217,-0.05623711111904462,-0.02698368330912722,-0.010878041827847972,0.0034553397681048132,-0.04382058020898185,-0.02495821309231802,-0.039814143670331655,0.27203500537657493,0.39661890644795433,-0.6940984069858586,0.3820611009041141,0.45829660646576825,-0.5286877502404412,-0.13283925773506663,0.350117828155418,0.3598579936603963,0.25963694186973235,-1.2320356415368325,1.3564509790199584,0.0918814381078159,-0.07654006053091078,0.14869203905224726,0.07598951416701638,-0.12098815726877765,0.1836239748244295,-0.0004180111729007452,-0.11292183838082726,0.22716897481238063,0.2325189072399214,0.574507100162398,-1.7870416425555602,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7083333333333335,1.0,1.0,1.0,0.0,-0.04698707770039136,-0.022299151263697668,0.5965272768651686,0.9957180402623595,-0.06255116702507033,-0.03810084300622158,-0.05640267335954389,-0.026670791950333488,-0.010837908607323775,0.003423171169782929,-0.043787242194438476,-0.024930121652558854,-0.039778149192962686,0.2728000337406895,0.3959843501823673,-0.6928611226310442,0.38269382297719173,0.4572907244821814,-0.5271573493654848,-0.13284305591831477,0.3491839885810092,0.36174077541376864,0.2615295296595919,-1.2270324518234716,1.3413911497980084,0.09172357565305767,-0.07574422795398217,0.14824806375967725,0.07586220609096528,-0.12041578368266692,0.18366684179612847,-0.0004957996769089368,-0.11119040141414627,0.2246888222582144,0.22169703705611665,0.625772838449894,-1.8268102642127104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.716666666666667,1.0,1.0,1.0,0.0,-0.04721849184562241,-0.022360553101822875,0.5965478697041148,0.9956932972641549,-0.06273230367142554,-0.03820428946219167,-0.05656808398735609,-0.02635257863269879,-0.010796324111008471,0.0033907152758453967,-0.043752936431189625,-0.02490144133850794,-0.03974204607779884,0.27356373163745923,0.3953565026487213,-0.6916276059231973,0.3833254710056302,0.4562896767377238,-0.5256266362105058,-0.13284752106301512,0.34826465479851554,0.36360280736469985,0.2633318924873343,-1.2216060942293343,1.3260041412830799,0.09156234827033316,-0.0749322420492482,0.14778948073457032,0.07573193074742912,-0.11982974651306155,0.18369972425701597,-0.0005778781531495802,-0.10944442972367407,0.22219473332928397,0.21087508384941,0.6760560860761622,-1.8655756551931013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.725,1.0,1.0,1.0,0.0,-0.04744722505608775,-0.022421846961244198,0.5965683479473225,0.995668505361799,-0.06291329048445596,-0.03830761207471384,-0.05673334264921501,-0.026030655295666297,-0.010753522151412814,0.003358009549338753,-0.043717695761128356,-0.024872498246645176,-0.03970589494739326,0.2743260728785284,0.39473547948154647,-0.6903979646188013,0.3839560218229822,0.45529356204029703,-0.5240956872945345,-0.13285268722086727,0.3473599147522813,0.3654440209692567,0.2650441143904154,-1.215764850388869,1.3102982222114568,0.09139818232658081,-0.07410844659155869,0.14731951000018118,0.07559904800509276,-0.11923349145474105,0.18372417361708582,-0.00066385651369405,-0.10769149519535226,0.21969759138498302,0.20007281776011632,0.7253369059665848,-1.903360527426723,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7333333333333334,1.0,1.0,1.0,0.0,-0.04767325171112602,-0.022483028615110166,0.5965887117101867,0.9956436650102669,-0.06309412362259739,-0.038410810632075715,-0.056898449151157084,-0.025706478997476977,-0.010709718241232558,0.0033250798859483168,-0.04368154835039315,-0.02484361032886889,-0.03966975049948262,0.2750870346762356,0.3941213618721953,-0.6891722807565276,0.3845854551390484,0.4543024518801448,-0.522564566650221,-0.13285858533824335,0.34646979654525967,0.3672644338877829,0.2666664394500029,-1.209517145796558,1.2942814658259678,0.09123146694822837,-0.07327676135004291,0.1468410995218683,0.07546388764843925,-0.11863012650599081,0.18374163125564724,-0.0007533807112242163,-0.10593838832828051,0.2172072031659411,0.18930886719268458,0.7736005299657434,-1.9401889911387116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7416666666666667,1.0,1.0,1.0,0.0,-0.0478965577840801,-0.02254409428316723,0.5966089605278775,0.9956187765979522,-0.06327479941734132,-0.03851388623173895,-0.057063403435309454,-0.025381351295830076,-0.010665108915530876,0.0032919410450366177,-0.043644517397840886,-0.024815085936177022,-0.03963366177381393,0.27584659732766553,0.3935142001257124,-0.6879506129601035,0.38521375328378954,0.4533163932651972,-0.521033326773607,-0.13286524356605434,0.34559427494680994,0.3690641410220224,0.26819926217696016,-1.2028715082227732,1.2779617390258116,0.09106255295661114,-0.07244067970517243,0.14635691913517768,0.07532674832317676,-0.11802241946174408,0.18375342191126576,-0.0008461347307492373,-0.10419112468573632,0.2147323089880493,0.17860070007777673,0.8208370008983135,-1.9760863718411548,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.75,1.0,1.0,1.0,0.0,-0.04811713953602746,-0.022605040611926825,0.5966290933450387,0.9955938404500155,-0.06345531435106834,-0.03861684123781621,-0.05722820555818235,-0.025056419842813354,-0.010619871374808076,0.0032585971008837287,-0.04360662086964887,-0.024787222933790744,-0.03959767246476871,0.2766047438921791,0.39291401721044245,-0.6867329987709413,0.3858409009444347,0.4523354115557824,-0.5195020096183666,-0.13287268758375584,0.3447332778004974,0.3708433057042504,0.2696431177846325,-1.1958365291149193,1.2613466929619486,0.0908917523202235,-0.07160327222193952,0.14586935911301557,0.07518789692073091,-0.1174128001323338,0.18376074946788057,-0.000941842032541329,-0.10245496141152999,0.21228060757188527,0.16796461501902282,0.8670408165954813,-2.011079046495894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7583333333333333,1.0,1.0,1.0,0.0,-0.04833500223099376,-0.02266586465247831,0.5966491085086105,0.9955688568318946,-0.06363566503361172,-0.038719679236170465,-0.05739285567048178,-0.024732681791029238,-0.010574163400814813,0.003225041891353303,-0.04356787125153979,-0.02476030834450685,-0.03956182126365223,0.2773614598663359,0.39232081225534676,-0.6855194569748866,0.38646688489913505,0.4513595132629916,-0.517970647615809,-0.13288094093326336,0.3438866922566178,0.3726021511482205,0.2709986724272772,-1.1884208279461819,1.2444437549175467,0.09071933803127097,-0.07076719508830043,0.14538053264199435,0.07504756832619308,-0.11680336642069133,0.18376469482624724,-0.0010402665310227377,-0.10073442180247527,0.20985879268179852,0.1574157414604671,0.9122105805931957,-2.0451942988880267,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7666666666666666,1.0,1.0,1.0,0.0,-0.04855015888619718,-0.022726563836477337,0.596669003762743,0.9955438259528869,-0.0638158481777214,-0.038822404989238495,-0.05755735399840419,-0.02441098862583789,-0.010528123497497682,0.0031912594435586023,-0.04352827530996632,-0.02473461847454291,-0.03952614221698985,0.27811673285936694,0.39173456395897077,-0.6843099898935747,0.38709169374987124,0.4503886887821042,-0.5164392647045958,-0.13289002535927288,0.34305437077045614,0.37434095224894703,0.2722667134756403,-1.180633019438366,1.2272601213138148,0.0905455443156189,-0.06993470237424915,0.14489228149408895,0.07490596545557726,-0.11619589342856229,0.18376621554761607,-0.0011412131967741823,-0.099033326050042,0.20747259892711645,0.14696804798717822,0.9563486634349916,-2.0784601940194225,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.775,1.0,1.0,1.0,0.0,-0.04876262906772967,-0.022787135950786613,0.5966887762448039,0.9955187479697255,-0.06399586057355446,-0.03892502439248851,-0.057721700826332045,-0.024092052063641727,-0.01048187121100982,0.0031572243580991997,-0.04348783385302577,-0.024710419476449468,-0.03949066508938455,0.27887055227159624,0.3911552338824426,-0.6831045856166518,0.387715317656728,0.44942291503918225,-0.5149078773566821,-0.1328999611532096,0.3422361368224504,0.37606002779700576,0.2734481398937302,-1.1724816835555987,1.2098027516838896,0.09037056708965707,-0.0691076611321717,0.14440618421502682,0.07476325951166207,-0.11559184480948836,0.18376614695684967,-0.001244528368811726,-0.09735482641738402,0.2051268543015139,0.13663435786678058,0.9994608777892022,-2.1109054711558617,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.783333333333333,1.0,1.0,1.0,0.0,-0.048972437739165556,-0.022847579111192597,0.596708422481525,0.9954936229900798,-0.06417569906227188,-0.03902754443423464,-0.05788589648081409,-0.023776450686090602,-0.010435507585296332,0.0031229021353339484,-0.04344654148170554,-0.024687968306156965,-0.03945541572179683,0.2796229089775279,0.3905827696067679,-0.6819032201566576,0.3883377480750656,0.4484621580352794,-0.5133764955886483,-0.13291076749875308,0.3414317903301664,0.37775973315397227,0.27454395277342,-1.1639753381418794,1.192078363461217,0.09019456458347119,-0.0682875684341211,0.14392356618948332,0.07461959039105515,-0.11499238564528058,0.18376520440097632,-0.001350099863847709,-0.09570144529103763,0.2028255372947152,0.12642637094952613,1.0415561699386888,-2.142559455041244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7916666666666665,1.0,1.0,1.0,0.0,-0.0491796141679483,-0.022907891735568196,0.596727938384374,0.9954684510759244,-0.06435536050877551,-0.039129973160361264,-0.058049941315689184,-0.023464637013090157,-0.01038911571266608,0.003088249428566286,-0.04340438632162986,-0.024667514035459207,-0.03942041637824806,0.2803737950146541,0.3900171077418739,-0.6807058595134937,0.38895897749657893,0.44750637527842757,-0.5118451239499991,-0.13292246281760706,0.34064111273426645,0.37944045341858434,0.2755552460762223,-1.1551224140566205,1.1740934274332022,0.09001765805444872,-0.06747556952906963,0.14344551100027525,0.07447506717976005,-0.11439839618990866,0.18376398637730107,-0.001457856967364557,-0.09407511472415697,0.2005718366679654,0.11635469106703766,1.082646329624275,-2.173451984729051,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8,1.0,1.0,1.0,0.0,-0.04938419089204262,-0.02296807251679639,0.5967473192432681,0.9954432322467256,-0.06453484177357026,-0.03923231964535941,-0.05821383569819346,-0.023156944750909465,-0.010342761342036304,0.0030532142103216623,-0.04336134972508877,-0.02464929948665663,-0.03938568607570272,0.2811232032784354,0.3894581767812834,-0.6795124616399864,0.38957899919472827,0.4465555180987809,-0.5103137624823599,-0.13293506511487582,0.33986387175143046,0.38110259709843836,0.27648319762453727,-1.1459312326481415,1.155854163715733,0.08983993252174804,-0.06667247639103202,0.1429728725562196,0.07432976867924213,-0.1138104858913247,0.18376297826218302,-0.0015677703880628835,-0.09247721626692296,0.19836821225235668,0.10642885810321467,1.1227457197168,-2.2036133594533247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.808333333333333,1.0,1.0,1.0,0.0,-0.04958620274725889,-0.023028120395718346,0.5967665597177807,0.9954179664824044,-0.06471413968368905,-0.03933459397095367,-0.058377579995877185,-0.02285359598457323,-0.010296493510956524,0.0030177358389665513,-0.043317405932432725,-0.024633563162889408,-0.03935124089368149,0.2818711272233499,0.3889058998020234,-0.6783229783042234,0.3901978069745663,0.4456095338469055,-0.5087824076456294,-0.13294859232407477,0.3390998257964844,0.38274659028945696,0.2773290603779425,-1.1364099853946739,1.1373665381089801,0.08966143745751554,-0.06587878601236885,0.14250628751698136,0.0741837439085935,-0.11322900716817297,0.1837625563954215,-0.0016798522552985418,-0.09090862005365352,0.19621645538676957,0.09665738395098433,1.161871026768364,-2.2330743009792764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8166666666666664,1.0,1.0,1.0,0.0,-0.04978568595384379,-0.02308803453431898,0.5967856538250061,0.9953926537260421,-0.06489325100256638,-0.03943680721350561,-0.05854117456415035,-0.022554708114914356,-0.010250345170691844,0.0029817450129369693,-0.04327252168129461,-0.024620541455216468,-0.0393170942615061,0.28261756056939397,0.3883601970144106,-0.6771373568480367,0.39081539492653816,0.44466836797931136,-0.5072510532091029,-0.13296306265246413,0.33834872808386957,0.3843728713548845,0.27809415402372034,-1.1265667155353354,1.1186362586994116,0.08948218737503177,-0.06509469787960409,0.1420461876056578,0.07403701253263728,-0.11265406848039117,0.18376299229590387,-0.0017941562369566677,-0.08936972227154505,0.1941177478460987,0.08704779161468279,1.2000410331348377,-2.2618659319188206,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.825,1.0,1.0,1.0,0.0,-0.049982677259372,-0.023147814289315668,0.5968045949232493,0.995367293886298,-0.06507217239869581,-0.03953897144131909,-0.058704619734269395,-0.02226030036863575,-0.010204333776629366,0.002945163599960583,-0.04322665575096578,-0.024610471115834864,-0.03928325722230064,0.28336249701293376,0.38782098817069666,-0.6759555418441291,0.3914317571834436,0.443731966038899,-0.5057196911073644,-0.13297849492802405,0.337610330425292,0.38598188608689193,0.2787798569048539,-1.1164093015090932,1.0996687725769998,0.0893021622582546,-0.06432013013927373,0.14159281144830116,0.07388956516905187,-0.11208554628771128,0.18376445680644338,-0.001910777853435519,-0.0878604802811922,0.19207271833568185,0.07760665676854184,1.2372764110788692,-2.2900197695725666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8333333333333335,1.0,1.0,1.0,0.0,-0.0501772131336281,-0.023207459186270697,0.5968233756906964,0.9953418868395151,-0.06525090041285005,-0.03964109972295103,-0.0588679158015758,-0.0219702997343254,-0.010158461818891724,0.00290790432823668,-0.043179758428042704,-0.02460359199577345,-0.03924973867387725,0.2841059299403649,0.3872881948454227,-0.6747774766572316,0.3920468876793557,0.44280027554118284,-0.5041883122623289,-0.1329949089500214,0.3368843867458497,0.3875740833271459,0.27938759830319604,-1.1059454420173542,1.0804692625398689,0.0891213077797548,-0.0635547340251652,0.14114621562997476,0.07374136352895189,-0.11152309553761008,0.18376702398667843,-0.0020298550627151357,-0.08638044478306073,0.19008149581985156,0.06833965113328122,1.27359953904441,-2.3175677349643387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.841666666666667,1.0,1.0,1.0,0.0,-0.05036932901001904,-0.02326696889430634,0.5968419880981914,0.9953164324314925,-0.06542943142358512,-0.039743206147646155,-0.05903106301379357,-0.02168454619811449,-0.010112717270169302,0.0028698703250160007,-0.04313177087798686,-0.024600150055198566,-0.03921654558730737,0.28484785214259634,0.38676174260361057,-0.6736031049169628,0.3926607799089261,0.4418732477799388,-0.5026569073742531,-0.13301232584573597,0.3361706563455743,0.3891499110172228,0.2799188510904086,-1.0951826425250197,1.0610426436609275,0.08893953525549558,-0.06279790616840364,0.1407062846976781,0.07359234034751361,-0.11096615836202584,0.18377067458848595,-0.0021515691928664094,-0.08492878852538688,0.1881437591209001,0.05925158708595779,1.3090343401301885,-2.344542176849078,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.85,1.0,1.0,1.0,0.0,-0.0505590585670564,-0.023326343201462447,0.5968604233751854,0.9952909304789023,-0.06560776161068575,-0.03984530585907463,-0.05919406155919088,-0.02140279716848923,-0.010067073929304254,0.0028309544863663223,-0.04308262440499783,-0.024600400664781606,-0.039183683204721764,0.28558825552795647,0.3862415630759493,-0.6724323719122703,0.3932734266851476,0.4409508395684824,-0.5011254676858541,-0.13303076843656916,0.33546890693709325,0.39070981264582755,0.28037512475462867,-1.0841282030151844,1.0413935595923842,0.08875672128487055,-0.06204879844973754,0.14027273987366362,0.07344239906026395,-0.11041397068813352,0.18377529896356548,-0.0022761463010306793,-0.08350433113370914,0.1862587823736328,0.05034646297077394,1.3436061426891133,-2.370975910620521,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8583333333333334,1.0,1.0,1.0,0.0,-0.050746433042560456,-0.023385581990699556,0.5968786719678509,0.995265380770333,-0.06578588691613894,-0.039947415103654044,-0.05935691155440677,-0.02112473099139249,-0.01002149164009824,0.002791038659582945,-0.04303223958014617,-0.024604612228037594,-0.0391511552182046,0.2863271308306775,0.3857275959627816,-0.6712652259190685,0.39388481989326385,0.4400330149351366,-0.4995939857248603,-0.1330502616174198,0.3347789174933458,0.39225422405678334,0.28075795880658816,-1.0727892068135345,1.0215263784839188,0.088572707022323,-0.06130632507827305,0.13984514626969924,0.0732914131795459,-0.10986556648634016,0.18378069926534457,-0.0024038590422564843,-0.08210555970029176,0.1844254760338948,0.04162750862862441,1.37734156292741,-2.3969022722024613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8666666666666667,1.0,1.0,1.0,0.0,-0.050931480572427454,-0.023444685216515448,0.5968967234882457,0.9952397830669375,-0.0659638030021427,-0.04004955129489369,-0.05951961303173758,-0.020849949463273586,-0.00997591636502037,0.0027499926158733538,-0.04298052521447164,-0.024613070167051634,-0.03911896393198348,0.28706446731166185,0.38521979099131143,-0.670101619474442,0.39449495023814,0.4391197467937101,-0.4980624560314317,-0.1330708327539401,0.3341004809420884,0.3937835705797258,0.28106891656510574,-1.0611725102997276,1.0014451883890099,0.08838729702340564,-0.06056916658948919,0.1394229184096707,0.07313922532265926,-0.10931977937917114,0.1837865908102232,-0.0025350291394721225,-0.0807306448110412,0.1826424232363444,0.0330972307123345,1.4102684093689222,-2.4223551871780624,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.875,1.0,1.0,1.0,0.0,-0.05111422554501696,-0.02350365288211082,0.5969145666532653,0.9952141371026633,-0.06614150520556733,-0.04015173309540783,-0.05968216592566779,-0.020577979251198066,-0.009930280092912313,0.0027076727869911115,-0.04292737714995571,-0.02462608132798237,-0.03908711041043811,0.2878002524477343,0.3847181098529568,-0.6689415106122406,0.39510380698197484,0.4382110186121504,-0.49653087587802325,-0.13309251210307768,0.33343340674649513,0.39529826444405575,0.2813095793184604,-1.0492847333240525,0.9811537920309511,0.08820025760192474,-0.05983577045169275,0.13900532387693065,0.07298564583755329,-0.1087752413274079,0.18379260246848106,-0.002670030555821379,-0.07937745170117916,0.1809079113648826,0.02475745739892732,1.4424156090882656,-2.447369255604237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8833333333333333,1.0,1.0,1.0,0.0,-0.05129468796142297,-0.02356248501700608,0.5969321892119495,0.9951884425840379,-0.06631898848818142,-0.04025398051851888,-0.0598445700584167,-0.020308272125270477,-0.00988450055841323,0.002663920734042414,-0.04287267683616033,-0.02464397887902832,-0.03905559461450038,0.28853447160502727,0.3842225281504499,-0.6677848640764932,0.3957113776687659,0.43730682610491994,-0.4949992459902903,-0.1331153332632038,0.3327775234137354,0.39679870243580717,0.28148154085508786,-1.0371322501482565,0.9606557007956059,0.08801131462653267,-0.05910434794439534,0.1385914848990044,0.07283045096579621,-0.10823037808352476,0.18379827594897313,-0.0028092934850798557,-0.0780435462243112,0.1792199587498411,0.016609382151780983,1.473813155691559,-2.471979853159252,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8916666666666666,1.0,1.0,1.0,0.0,-0.05147288279103387,-0.023621181654981133,0.5969495778594807,0.9951626991894786,-0.0664962473818323,-0.0403563150517182,-0.06000682512425147,-0.020040203898972653,-0.009838480748314383,0.002618561309647054,-0.04281628965441355,-0.024667127791747796,-0.03902441552921605,0.2892671076915098,0.38373303738721687,-0.6666316525305905,0.3963176478314048,0.436407178977425,-0.4934675712788737,-0.13313933366116235,0.33213268097608994,0.3982852637565531,0.2815864023543234,-1.0247211807291932,0.9399541278116302,0.08782015067346549,-0.05837286693420207,0.1381803776747348,0.07267338047251104,-0.10768340106236174,0.18380306383286915,-0.0029533092936517846,-0.07672619528870772,0.17757633643193604,0.008653606222484012,1.504492079137858,-2.496223249495322,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9,1.0,1.0,1.0,0.0,-0.05164881931081938,-0.023679742812174717,0.5969667181359297,0.995136906568086,-0.06667327592762516,-0.04045875980468069,-0.060168930672292384,-0.019773071957570068,-0.00979210816660973,0.0025714004663876374,-0.042758062943864625,-0.024695931018537138,-0.038993571285261014,0.28999814078291836,0.38324964703487985,-0.6654818577819143,0.3969226006766411,0.4355121027538806,-0.49193586159307584,-0.13316455508476466,0.33149875349225694,0.3997583080430061,0.2816257676254626,-1.0120573821626255,0.9190519799706839,0.08762640143734068,-0.05763904011336307,0.13777082922478812,0.07251413466086043,-0.10713229522321122,0.18380632619833026,-0.0031026365716230186,-0.07542236135549496,0.17597458493896823,0.0008901796136984164,1.5344844376425115,-2.5201367449013845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.908333333333333,1.0,1.0,1.0,0.0,-0.051822500415650743,-0.02373816846514771,0.5969835943074624,0.9951110643378761,-0.06685006760797273,-0.04056133968506203,-0.06033088608749968,-0.019506091231890094,-0.009745253825239018,0.0025222226541107926,-0.04269782367446295,-0.024730836505316642,-0.03896305927748045,0.2907275477154655,0.3827723867186608,-0.6643354720435107,0.3975262167424191,0.4346216407237048,-0.4904041325089015,-0.1331910442706894,0.33087564162016503,0.4012181735055359,0.2816012386812184,-0.999146440101818,0.8979518487299405,0.0874296512830286,-0.05690030818087055,0.137361511511358,0.07235237067258593,-0.10657480247571849,0.1838073256505912,-0.0032579084801903635,-0.07412869051240834,0.1744120260162263,-0.006681359748781368,1.5638233320880346,-2.5437588266326894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9166666666666665,1.0,1.0,1.0,0.0,-0.051993921885592556,-0.023796458528675696,0.5970001892272947,0.9950851720833914,-0.06702661527017859,-0.040664081605958274,-0.06049269056948962,-0.019238388444667527,-0.009697770921162734,0.002470787735748321,-0.042635375700427365,-0.024772345209601573,-0.03893287628364205,0.2914553016376355,0.38230130856519867,-0.663192499256725,0.3981284735211842,0.43373585604595194,-0.488872406165566,-0.1332188535594345,0.33026327531705013,0.40266517514327654,0.2815144116296496,-0.9859936599611583,0.8766559995268057,0.08722942779742393,-0.05615381733759417,0.13695093252587442,0.07218769795658941,-0.10600840002296552,0.18380522054412873,-0.003419841620085906,-0.07284149352137281,0.1728857692188801,-0.014061948866754825,1.5925429435870275,-2.5671293465323086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.925,1.0,1.0,1.0,0.0,-0.05216307159444576,-0.023854612832995396,0.5970164841731634,0.9950592293526188,-0.06720291103996692,-0.04076701472970501,-0.060654343108768924,-0.018968994417315446,-0.009649493152348497,0.0024168273352040527,-0.04257049651348472,-0.024821020332506143,-0.03890301858672756,0.2921813715120892,0.38183648976303425,-0.6620529565014128,0.3987293450416956,0.43285483405665537,-0.4873407121664994,-0.13324804163102416,0.32966161672814215,0.40409960299251724,0.2813668728667725,-0.9726040577087008,0.8551663596210687,0.08702519516973761,-0.055396390327369094,0.1365374239810091,0.07201967276234456,-0.10543027292314266,0.1837990561401015,-0.0035892466938081125,-0.07155671908772865,0.17139271322720195,-0.021252964761019344,1.620678595091114,-2.5902897218455356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.933333333333333,1.0,1.0,1.0,0.0,-0.05232992864176579,-0.023912631100181356,0.5970324586574367,0.9950332356531257,-0.0673789462230649,-0.04087017075366925,-0.06081584245990795,-0.018696834174787662,-0.009600232614929975,0.0023600405114380927,-0.042502933397233884,-0.024877498020185112,-0.038873482104727713,0.2929057215571311,0.38137803539307585,-0.6609168755237081,0.3993288014005566,0.43197868483056623,-0.48580908856323096,-0.13327867433766463,0.32907066333225465,0.4055217203637299,0.28116019555029925,-0.958982350042973,0.8334845041627135,0.08681634619121303,-0.05462449007727077,0.13611912516171998,0.07184779148293519,-0.1048372799870545,0.18378775338851017,-0.0037670412926932295,-0.07026991841098451,0.16992954168471908,-0.028256192015702064,1.6482668382279453,-2.6132831614166996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9416666666666664,1.0,1.0,1.0,0.0,-0.052494462388045324,-0.02397051291927349,0.5970480902052062,0.995007190447304,-0.06755471119257082,-0.040973584244884766,-0.0609771871110842,-0.018420714523261238,-0.009549777210890363,0.0023000886279325216,-0.04243239886193626,-0.024942499848580463,-0.03884426253227544,0.2936283106152761,0.38092608159507974,-0.6597843044153842,0.39992680823307786,0.4311075460568711,-0.48427758294335754,-0.13331082565256905,0.3284904514212924,0.4069317620205959,0.28089593633317744,-0.9451329437382351,0.8116116402641237,0.08660219261795166,-0.05383417476579333,0.13569396238374276,0.0716714826341247,-0.10422591192210451,0.18377009495662344,-0.003954265215488362,-0.06897619983622261,0.16849271327207038,-0.035073792989671615,1.675345566865838,-2.636154919741691,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.95,1.0,1.0,1.0,0.0,-0.05265663136959697,-0.024028257719711003,0.5970633540947266,0.9949810931465869,-0.06773019525938362,-0.041077293031852834,-0.06113837524931897,-0.018139308696202904,-0.009497887479238964,0.0022365892562263177,-0.042358565211013825,-0.025016847477783676,-0.038815355499343035,0.294349091434097,0.3804807991469793,-0.6586553094839791,0.40052332611112534,0.43024158629853115,-0.48274625364728724,-0.13334457875792277,0.32792106000165094,0.40832993225159775,0.2805756323338047,-0.9310599239285424,0.7895485888336853,0.08638195358117051,-0.05302104286943776,0.1352596233803327,0.07149009720595068,-0.10359224037498671,0.18374470804042753,-0.004152098818169803,-0.06767017212606641,0.1670784456232921,-0.04170828092153189,1.701954159255945,-2.6589525816217563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9583333333333335,1.0,1.0,1.0,0.0,-0.052816382065755216,-0.024085864742547085,0.5970782230533758,0.9949549431044689,-0.06790538652240335,-0.041181338663644144,-0.06129940472059375,-0.017851137565714558,-0.009444292743167213,0.0021691089136457275,-0.04228105805545626,-0.02510147995323198,-0.038786756753206114,0.29506800984162895,0.3800423975472558,-0.6575299773590453,0.40111830985317704,0.429381008717288,-0.48121517114268375,-0.13338002729953854,0.3273626152191913,0.4097164027809841,0.2802007983178186,-0.9167670410839693,0.7672957639037611,0.08615474165484693,-0.05218016638832923,0.13481352577679573,0.07130289706160475,-0.10293185620115164,0.18371004338615715,-0.004361885011650024,-0.06634587449974694,0.16568269256108437,-0.04816249617914714,1.7281336509811318,-2.681726380397975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.966666666666667,1.0,1.0,1.0,0.0,-0.052973647486140196,-0.02414333300882295,0.5970926669008184,0.9949287396081251,-0.0680802716945136,-0.041285766948681996,-0.06146027298386432,-0.01755454679233508,-0.00938868643992578,0.002097154386635808,-0.042199448548050064,-0.02519747424557114,-0.03875846237151055,0.2957850037950111,0.3796111297071738,-0.6564084173876992,0.40171170772881876,0.4285260553618453,-0.4796844195908513,-0.13341727684145027,0.32681529542665516,0.41109131046094916,0.2797729240641523,-0.9022576964121902,0.7448531491603857,0.085919546097184,-0.051306010010132574,0.1343527786028953,0.07110904098041715,-0.1022397948827991,0.18366434981427093,-0.004585155673933472,-0.06499669111880046,0.16430111396902758,-0.054439585940612156,1.7539269413349956,-2.704529552902124,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.975,1.0,1.0,1.0,0.0,-0.05312834553964942,-0.02420066128436045,0.5971066521292083,0.9949024818683695,-0.06825483589948698,-0.04139062858837535,-0.06162097705778141,-0.01724767913156652,-0.009330720467635802,0.0020201623300311047,-0.04211324405328578,-0.025306069765795053,-0.03873046901622187,0.296500002276582,0.37918729738042023,-0.6552907643823304,0.402303460536184,0.42767701213590803,-0.47815409864577924,-0.13345644656077077,0.32627933703387796,0.4124547546804679,0.27929347188547504,-0.8875349253950527,0.7222202713553924,0.08567521266409805,-0.05039233342303717,0.13387413554376115,0.07090756784371988,-0.10151044650682839,0.183605643368,-0.00482366343029339,-0.06361524711707922,0.16292903742828657,-0.060542987649040425,1.7793790361571782,-2.7274187342912803,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9833333333333334,1.0,1.0,1.0,0.0,-0.05328037713926032,-0.024257848040085152,0.5971201414079562,0.9948761690076353,-0.06842906243386956,-0.041495979924246036,-0.06178151345866523,-0.016928440920790818,-0.009269998342238114,0.001937486754730733,-0.042021876897264186,-0.025428697776600024,-0.03870277424097129,0.2972129240060794,0.3787712574834565,-0.6541771817953032,0.4028935005262141,0.4268342145867315,-0.47662432553471795,-0.13349767123195516,0.3257550413080372,0.41380679441808726,0.2787638742700016,-0.8726013791429039,0.699396170255531,0.08542041924358923,-0.049432073293861345,0.133373938308603,0.07069737633761952,-0.10073744707025822,0.18353166999422355,-0.005079419994228895,-0.06219328253720513,0.16156141050957307,-0.06647641665809667,1.804537330531577,-2.7504543957492777,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9916666666666667,1.0,1.0,1.0,0.0,-0.053429623987248126,-0.024314891406808814,0.597133092997697,0.9948498000455804,-0.06860293248653898,-0.0416018838215513,-0.061941878127955666,-0.04019670507753584,-0.014147482150971499,0.014262533092932647,-0.05474018112680651,0.005127622574227356,-0.03936503168603399,0.29792367593064184,0.3783634294921892,-0.6530678654105203,0.403481750141811,0.42599805468473706,-0.47509523747920884,-0.13354110356067458,0.32524278232492454,0.41514744485562743,0.2781855316078401,-0.8574593032195265,0.6763793647595711,0.10902814416632545,-0.13867918550914848,0.1690507969908417,0.09034102261198607,-0.18765047520319378,0.21120498912987729,0.027523034709158734,-0.1410088606431037,0.14640227616632862,-0.0004316609588739251,0.9920022611206014,-1.6424772113149966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0,1.0,1.0,1.0,1.0,-0.05399092472493705,-0.02437719461100779,0.597324611514928,0.9948263022593893,-0.06886654034365762,-0.04144770761892703,-0.062129827891527836,-0.05896463423697898,-0.020078090890841158,0.02536798139674793,-0.05307198451758222,-0.0017014000990702247,-0.050245836818682055,0.29903005974218483,0.3764599377249707,-0.6513596685121225,0.40439918423641386,0.42370670666667826,-0.47310424238255333,-0.13303895398680252,0.3234048936306521,0.41624683235419274,0.27875667992068703,-0.8560680081242272,0.6720215500669477,0.14936118454813352,0.08720829215314918,-0.3633552680745389,0.09569573667831177,-0.285083112884863,0.3449206385134562,0.024021833759201305,-0.18758715730536557,0.1843812712076387,0.05846903185435903,0.12577712113705397,-0.3844697559009558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0083333333333333,0.0,1.0,1.0,1.0,-0.05447592995209889,-0.02446778554005673,0.5975051048955194,0.9947927449261423,-0.0690265074612773,-0.04161738145711229,-0.06237571218561407,-0.046583886216481886,-0.01947727990736672,0.019644419607211853,-0.0413688403535916,-0.0422984554511816,-0.06068278747540939,0.30041302900644407,0.379816901028075,-0.659123786545096,0.4050766790864495,0.42124666946998934,-0.46934656017065124,-0.1331407396646879,0.32211632970316845,0.4182204660424214,0.2791600154720794,-0.8553630178672422,0.6699715354945551,0.16547879830495216,0.45032598029167703,-0.9904615105147685,0.08353265292625034,-0.26541121617925545,0.42688851661721094,-0.015906740101221395,-0.13326308659910802,0.23494113678063866,0.05069346504257055,0.06711119706983792,-0.18976364726252415,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0166666666666666,0.0,1.0,1.0,1.0,-0.05482503342682648,-0.024557640807858813,0.5976196881273111,0.9947562845014797,-0.06921043191407684,-0.04181175573631143,-0.06262290029474378,-0.032986700162748246,-0.016805012618206508,0.013542203063150474,-0.04365929828605487,-0.04658685237615384,-0.06099650129957794,0.30178803971393403,0.383965370729832,-0.6678673603540353,0.40579139511851803,0.419283186397024,-0.4659894337722665,-0.13330406632182287,0.32118384218733365,0.4201625179672034,0.2796015710047299,-0.8549494881730633,0.6688588226125723,0.1608370700867645,0.5242938192128521,-1.077606382656855,0.08446261571949942,-0.21751423727083163,0.3910490046318793,-0.023323855779236458,-0.08940971952114074,0.21244415545868867,0.05157362111989139,0.04400489340754099,-0.10467347480797695,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.025,0.0,1.0,1.0,1.0,-0.055072808995764076,-0.024645414433817785,0.5977144572570041,0.9947194990754522,-0.06939148816357248,-0.04201596608215264,-0.06286969161455912,-0.022533965422655563,-0.014994493099313794,0.011208745201245476,-0.04287116532592718,-0.04810017516581948,-0.06109186920393867,0.3030936468412235,0.38855513134828923,-0.6770838929227102,0.40648438934844117,0.41762143218214215,-0.4628290767601199,-0.13352947059434184,0.32062616771114943,0.4217612019667329,0.2800195758240776,-0.8546296029771165,0.6682269775810888,0.15280454995423853,0.5703534362324081,-1.1270597505850288,0.08199314255320056,-0.1875242440630731,0.37305738411672396,-0.02953135301277776,-0.047883363924123845,0.17033826111301442,0.048817724953907904,0.036573746519650285,-0.05837028560992108,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.033333333333333,0.0,1.0,1.0,1.0,-0.055243004533733334,-0.024731606204977996,0.59780255168436,0.9946826452240476,-0.06956961595405252,-0.04222334095845624,-0.06311650580001461,-0.014411966293248193,-0.013688367448699067,0.010050289902015036,-0.04225436635370117,-0.04849817997413819,-0.06117727488601393,0.30433478221317134,0.39347126133370547,-0.6866516895304524,0.4071579474944047,0.4161577823293061,-0.4597718107036544,-0.1337962555387025,0.3203857861219316,0.4230014889857536,0.2804151997539617,-0.8543399257310691,0.6678859845190737,0.1454298061864523,0.6055937618349527,-1.1656438246464407,0.07996120664897965,-0.16696878350843658,0.3627455810229674,-0.03377106251186923,-0.013561251345124425,0.13036792972001332,0.04641703939712416,0.034107938830150175,-0.028866825201234736,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0416666666666665,0.0,1.0,1.0,1.0,-0.05535282309914829,-0.024816703778140884,0.5978878161715436,0.9946457603544215,-0.06974571834294359,-0.042431211868650835,-0.06336354189247456,-0.008039647496530852,-0.012696475827768741,0.00931325134642574,-0.04183967718583102,-0.04846278168316784,-0.06125140989746397,0.305517476944331,0.3986483607122051,-0.6965112900001509,0.40781707612592416,0.4148386191236682,-0.4567833170764038,-0.13409232163620632,0.32040014685539736,0.4239340007953998,0.280793193147363,-0.8540611373299474,0.6677458638277349,0.1386453593003445,0.6341928363154359,-1.1982453361479717,0.07844120342919259,-0.15162348155646654,0.3554497565523218,-0.0368580581781347,0.013860362250525116,0.09682465698845899,0.04452603183317749,0.03315146569649485,-0.007821197628576915,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.05,0.0,1.0,1.0,1.0,-0.05541509549508304,-0.02490098884676402,0.5979714305684878,0.994608849048062,-0.06992034461051129,-0.04263854315403767,-0.06361082802902629,-0.0029914567534797,-0.011915020698147417,0.008763371013319629,-0.041542556904035785,-0.04825962532841401,-0.061306691265356233,0.3066455382015104,0.40404114193896273,-0.7066224451329186,0.40846530088489125,0.413630724303365,-0.45384764809444905,-0.13441055650833808,0.32061679215944033,0.4246152332688946,0.28115730028451463,-0.8537874013027942,0.667755631225264,0.13223207417563554,0.6580259345401862,-1.2265469736888002,0.07727697926179444,-0.13965692223878445,0.3496821294202834,-0.03923587981454313,0.035663489092000455,0.06956813059661004,0.04302649366571987,0.032652805533046614,0.008165477566288715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.058333333333333,0.0,1.0,1.0,1.0,-0.05543949683285597,-0.02498462042508497,0.5980537840333033,0.9945719093818365,-0.07009383808872309,-0.042844907848930545,-0.06385831818938557,0.0010515190932305699,-0.01128307067020053,0.008317050530361128,-0.041318827822080816,-0.047986034876119146,-0.06133940265846203,0.30772134484725827,0.4096154596212082,-0.7169537395616309,0.4091050257802874,0.4125110037530218,-0.45095528158606574,-0.1347462529664487,0.32099453834026404,0.4250934696386766,0.281510301375125,-0.8535169239043966,0.6678819551205064,0.1260529705493263,0.678201906161785,-1.2514037173150738,0.07635872915671804,-0.13009129010189024,0.3448750609610274,-0.041127445876762425,0.05309318587490064,0.04750757173515363,0.041818713738386304,0.03229630791698579,0.020729659056086813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0666666666666664,0.0,1.0,1.0,1.0,-0.05543336655307919,-0.025067693837707045,0.5981350178860149,0.9945349395590916,-0.070266434075262,-0.04305009778624932,-0.0641059382517369,0.004328904891696813,-0.01076100323677458,0.00793772453259098,-0.041145348548159016,-0.04767640068771682,-0.06134840245611708,0.3087464210439992,0.41534450704165915,-0.7274791737548365,0.40973794637083655,0.41146253613500017,-0.44809973041176526,-0.13509601393961745,0.3215016785906887,0.42540702613114717,0.28185427884682107,-0.8532491295041778,0.6681011255428655,0.12002368439362976,0.6954763199379554,-1.2733711395083325,0.07561585193896714,-0.12230109476339512,0.34073339947958914,-0.04266096218417337,0.06716158745194822,0.029526748984057827,0.04083031608190235,0.03198634424391722,0.030814409383974617,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.075,0.0,1.0,1.0,1.0,-0.05540229960321278,-0.02515026811866529,0.5982151876223147,0.99449793970871,-0.07043830254353112,-0.043253982366433075,-0.06435360486687164,0.007020732746809479,-0.010321027667377681,0.007605509081682439,-0.041008104034419034,-0.047342638036009146,-0.06133378692799195,0.3097217395871521,0.42120673162017414,-0.7381765918867698,0.4103652899792702,0.4104726521736319,-0.44527639159473925,-0.1354572690028516,0.32211389813112984,0.42558558212174424,0.2821908066431567,-0.852983818166998,0.6683955286102393,0.11408828274089178,0.7103982794176344,-1.2928527114866384,0.07500059463331432,-0.11584577280789987,0.337063965126978,-0.04392059223094491,0.0786496488547761,0.014697681342613622,0.040008109267439806,0.03169298708298074,0.039039300026915136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0833333333333335,0.0,1.0,1.0,1.0,-0.0553505836789428,-0.025232378953598353,0.5982943140627122,0.9944609120568456,-0.070609568868905,-0.04345645947483741,-0.0646012330000463,0.009262205764523348,-0.009942874524004988,0.007307729827791329,-0.040897558507937075,-0.046989038924637114,-0.061296218438733334,0.31064789242301405,0.4271844783652864,-0.7490267189462805,0.4109879562813918,0.4095317732548685,-0.44248199765964896,-0.1358280238101332,0.3228125060716016,0.4256519874868574,0.28252108066794507,-0.8527209130527947,0.6687517805433141,0.10820752370745979,0.7233777309022138,-1.310153231498179,0.07447904777890368,-0.11040243646064707,0.33372768026011856,-0.04496625225090978,0.08814925333012202,0.0022971459029164087,0.039312390610298786,0.03140610483311157,0.04584244964005002,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.091666666666667,0.0,1.0,1.0,1.0,-0.05528152596593303,-0.02531404586649504,0.5983724013877346,0.9944238605736865,-0.07078032602258681,-0.043657439392344226,-0.0648487390437607,0.011154803614067663,-0.009611525877180716,0.007035601862541275,-0.040806808147854604,-0.046617530268478334,-0.06123662779645976,0.31152519831560976,0.43326302713521103,-0.7600124790784061,0.4116066074422519,0.40863261156595443,-0.43971426359040394,-0.13620670654036676,0.32358305235329854,0.42562386788679285,0.28284601315332836,-0.8524603830864461,0.6691595694375735,0.1023530920918303,0.73472434211172,-1.3255062167363696,0.07402645776957706,-0.10573121080669545,0.33062225842561355,-0.0458423233023697,0.09610609776219525,-0.008224903571208975,0.03871334096047341,0.031121725034102266,0.0515447661691093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1,0.0,1.0,1.0,1.0,-0.055197698318881674,-0.025395276906394485,0.5984494447711111,0.9943867905125199,-0.0709506428525026,-0.043856840083345144,-0.06509604220634814,0.012774639238862573,-0.009315808048872111,0.006782825540367478,-0.04073071929649718,-0.04622944696668584,-0.06115608185992587,0.3123537772912112,0.4394298840671484,-0.77111848922522,0.4122217305775514,0.40776958640809025,-0.43697162668588874,-0.13659206253183936,0.3244142743676382,0.4255149057606706,0.2831663030172863,-0.8522022176355597,0.6696108599794659,0.09650439323277027,0.7446735416668682,-1.339091997360602,0.07362453730262897,-0.1016533552646226,0.32767293151762633,-0.04658226844957758,0.10285498788445313,-0.0172826006975646,0.038188545903808935,0.03083798247580649,0.056384925480883474,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1083333333333334,0.0,1.0,1.0,1.0,-0.055101121505234364,-0.025476071997878432,0.5985254343884511,0.9943497079870802,-0.07112057011620099,-0.04405458616995864,-0.06534306520013337,0.01417875032188044,-0.009047417077569167,0.006544844621755124,-0.040665436513886044,-0.04582607576682684,-0.06105571984218791,0.31313360486948927,0.44567425282965883,-0.7823306790344161,0.4128336830639624,0.4069383889782107,-0.43425304806511017,-0.13698307768119306,0.32529730215137276,0.42533582454183344,0.28348248891839184,-0.8519464167118493,0.6700993181955882,0.09064651955585479,0.7534052455905882,-1.3510509872724286,0.07325973452527279,-0.09803584455091663,0.3248259365114081,-0.04721152788337235,0.1086471808602607,-0.025186325117002584,0.037721181089559463,0.030553896642102618,0.060541526758648434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1166666666666667,0.0,1.0,1.0,1.0,-0.05499340368439736,-0.025556425425921854,0.5986003579108626,0.9943126196261275,-0.07129014499492163,-0.044250608942863555,-0.06558973461615045,0.015409838348974362,-0.008800205779046647,0.006318377221123306,-0.0406080559958055,-0.045408783462521723,-0.060936718422674,0.31386455261714213,0.45198663816032486,-0.7936360056797604,0.4134427261529726,0.40613565566557497,-0.43155786107736527,-0.13737892132989557,0.3262250607153092,0.4250951336753872,0.28379498936877895,-0.851692986024858,0.6706198854254434,0.08476884029046006,0.7610577202404167,-1.3614936852501303,0.07292202534270764,-0.09477998630159967,0.32204350125950576,-0.04774953375416113,0.11367114454219895,-0.03216812729109231,0.03729864803217686,0.03026897329787781,0.06414849457082594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.125,0.0,1.0,1.0,1.0,-0.054875844438427177,-0.02563632769772781,0.5986742022017776,0.9942755323053695,-0.07145939450017556,-0.04444484654484122,-0.0658359811360644,0.01649983954342508,-0.008569650199061994,0.006101086792808861,-0.04055639097929571,-0.04497901557087733,-0.06080026971360474,0.31454641887433027,0.4583585481669991,-0.8050222404552516,0.4140490501530075,0.4053587225398507,-0.42888565637745174,-0.1377789032437624,0.3271918212270761,0.4247996890869819,0.28410413305226145,-0.8514419338235514,0.6711684597717686,0.07886397590156635,0.76773795466612,-1.3705082272019187,0.07260403270117233,-0.09181287623191925,0.31929993151489255,-0.048211184891780445,0.11806821200950446,-0.03840120356913945,0.03691154070578295,0.02998304252180839,0.06730630484474753,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1333333333333333,0.0,1.0,1.0,1.0,-0.05474951284797835,-0.025715766937636327,0.5987469545065729,0.994238452945181,-0.07162833805042716,-0.044637244078015365,-0.06608173964437447,0.01747261600879423,-0.008352446934584656,0.005891339965997257,-0.040508797516261796,-0.04453826251699806,-0.060647565673366675,0.3151789522155016,0.46478227073809353,-0.8164778094664591,0.4146527933646588,0.40460544106170965,-0.42623619555211706,-0.1381824410780919,0.32819286424880095,0.42445511361590155,0.28441018171387533,-0.8511932686494945,0.6717416571728558,0.07292703584827143,0.7735294481164301,-1.378166067181208,0.07230037058016725,-0.08908094901482144,0.31657857477626394,-0.048607949362868275,0.12194436219970961,-0.04401463345688805,0.03655286197086327,0.029696165923758233,0.07009034434163341,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1416666666666666,0.0,1.0,1.0,1.0,-0.05461530600677185,-0.025794729927858532,0.5988186032823113,0.9942013883609244,-0.07179698942088023,-0.04482775358756618,-0.06632694927102428,0.018345983820572127,-0.00814620835666356,0.005688024794049937,-0.04046404342215895,-0.044088024012971155,-0.06047978630064199,0.31576186947180146,0.4712507056356063,-0.8279916749082717,0.41525405632934365,0.40387404005627037,-0.42360934679784734,-0.13858903573314355,0.3292242272637379,0.42406611186270043,0.2847133474184425,-0.8509469977248221,0.6723366321774625,0.06695504685957254,0.7784980610821546,-1.3845262319524543,0.07200715064903829,-0.08654510462004272,0.3138694822136634,-0.04894869567557081,0.12537908140400345,-0.04910448061761552,0.03621742981158138,0.02940856804150238,0.07255719142755579,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.15,0.0,1.0,1.0,1.0,-0.05447399279289973,-0.025873202879900983,0.5988891387600673,0.9941643451542158,-0.07196535821878983,-0.045016333934410485,-0.06657155338157981,0.019133241201467394,-0.007949231751713186,0.0054904134083815035,-0.04042120921956174,-0.043629779801309734,-0.06029809040755835,0.3162948696631611,0.4777572384227961,-0.8395532466656667,0.4158529125421428,0.4031630226513756,-0.42100503751522267,-0.13899825267268476,0.33028251560553434,0.42363670560560795,0.28501380554406835,-0.8507031258488028,0.6729509436966484,0.06094652267681355,0.7826964100162115,-1.3896384946666718,0.07172160964169949,-0.08417702565298057,0.31116761888441147,-0.04924032139347001,0.12843202940850063,-0.05374214178706871,0.035901427697065946,0.02912058082825908,0.07474935056812848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.158333333333333,0.0,1.0,1.0,1.0,-0.05432624653059214,-0.025951172001238195,0.59895855330571,0.9941273296356876,-0.0721334509994816,-0.045202950582275025,-0.06681549952652396,0.019844319662985204,-0.0077603244533724445,0.0052980580723743865,-0.040379613101610624,-0.04316496774594437,-0.06010360835089798,0.31677764484974835,0.48429564580254314,-0.8511523164860496,0.41644941649003864,0.4024710896287207,-0.4184232198164405,-0.13940970775636805,0.3313647610872129,0.4231704094995826,0.28531170454672694,-0.8504616547110178,0.6735824546869313,0.05490114004945479,0.7861671657514047,-1.3935457337495571,0.07144182733611615,-0.08195639638097885,0.30847149981676925,-0.04948822910327888,0.13114805486788117,-0.05798062334490983,0.03560206421066914,0.028832598594858982,0.07669882401422079,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1666666666666665,0.0,1.0,1.0,1.0,-0.05417266928370225,-0.026028623906420145,0.5990268416287949,0.9940903477718573,-0.07230127211019004,-0.04538757532346517,-0.06705873935836214,0.020486650716636176,-0.0075786714349387,0.0051107125832836895,-0.040338754010496344,-0.04269496826713417,-0.05989743633915065,0.31720988866398536,0.49086002451865285,-0.862779008894826,0.4170436096644114,0.4017970827116926,-0.41586384585160985,-0.13982305649107274,0.33246831651999903,0.4226703618831928,0.28560717328091284,-0.8502225825388885,0.6742292574302188,0.048819494930406604,0.7889455266864098,-1.3962856800486634,0.0711665128889627,-0.07986880457390155,0.30578215453646473,-0.04969668697379248,0.1335609688406647,-0.06185925965938477,0.035317315438527785,0.028545042358503192,0.07842980525417875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.175,0.0,1.0,1.0,1.0,-0.054013809849546214,-0.02610554591008197,0.5990940008777651,0.9940534051503916,-0.07246882432758293,-0.04557018596320446,-0.0673012285234711,0.021065817960388346,-0.0074037351196737005,0.004928272972222426,-0.040298268401665,-0.042221093795977355,-0.059680632040401346,0.31759130309858846,0.4974447379139833,-0.8744237444868607,0.417635525038188,0.40113994288582233,-0.41332685057416607,-0.14023798587259792,0.3335907772345573,0.4221394218385929,0.2859003264707024,-0.8499859040050427,0.6748896181078343,0.042702919331862876,0.7910610710550792,-1.397892206157254,0.07089484286939562,-0.07790416039299086,0.3031023438600433,-0.049869101943598726,0.13569638352343816,-0.06540725976100448,0.03504573001861133,0.02825833257720678,0.07996070814613399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.183333333333333,0.0,1.0,1.0,1.0,-0.05385017701457181,-0.026181926230394278,0.5991600306509965,0.9940165069593815,-0.07263610933877812,-0.045750765977962696,-0.06754292653435037,0.021586047174503156,-0.007235179646884681,0.004750732908948753,-0.04025789735761697,-0.04174458207393285,-0.059454211272453365,0.3179216039861831,0.5040443757029042,-0.8860772123307802,0.4182251903789013,0.4004986800384761,-0.4108121401206091,-0.14065420819013272,0.33472992291205633,0.42158024088717605,0.28619126878122303,-0.8497516103292684,0.675561935899321,0.036553344100449525,0.7925391422827011,-1.3983962740870903,0.07062633845087318,-0.07605550678599582,0.3004359700001047,-0.05000822672143357,0.1375738468511889,-0.06864637250693084,0.034786281639413996,0.027972869106125398,0.0813056933375611,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1916666666666664,0.0,1.0,1.0,1.0,-0.053682249250795275,-0.026257754124698402,0.5992249329465046,0.9939796579772676,-0.07280312810352751,-0.04592930415948882,-0.06778379662692766,0.022050574125081497,-0.00707281370886214,0.004578150311362181,-0.040217461535323164,-0.04126659235882827,-0.05921914559277803,0.3182005255002626,0.510653723618695,-0.8977303490549788,0.4188126306790359,0.39987235110605573,-0.40831958440749766,-0.14107145631795515,0.33588367468207714,0.42099531563014403,0.2864800978313593,-0.8495196895199406,0.6762447129967937,0.0303731964553855,0.7934018834816992,-1.3978266287187147,0.07036077229345183,-0.07431812632586077,0.2977876346030861,-0.050116316623370905,0.1392084463886878,-0.07159288805173247,0.03453825748477635,0.027689017169982844,0.08247581428165951,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2,0.0,1.0,1.0,1.0,-0.05351048174332504,-0.026333019973905174,0.5992887120678879,0.9939428625708254,-0.07296988112608888,-0.046105794253371156,-0.06802380560674066,0.02246192002744398,-0.006916547495166514,0.004410622489437363,-0.040176842048779936,-0.04078820381197361,-0.0589763606333837,0.31842782392710617,0.5172677404275992,-0.9093743228094254,0.4193978699171255,0.39926004459971176,-0.40584901287722436,-0.14148948013385557,0.33705006368520113,0.42038702608631384,0.2867669064059693,-0.8492901267097687,0.6769365328040153,0.02416532383195502,0.7936690085109088,-1.3962103026882366,0.07009809795805566,-0.07268887251335454,0.2951623098913281,-0.05019524837392819,0.14061201300317405,-0.07425913925178884,0.03430117392619447,0.02740709821151821,0.08347987546363012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2083333333333335,0.0,1.0,1.0,1.0,-0.05333531142143643,-0.02640771532830542,0.599351374499996,0.9939061246992278,-0.07313636865839448,-0.046280234598716094,-0.06826292368712536,0.022822097277020063,-0.00676636035726045,0.0042482677855256055,-0.04013596585355371,-0.04031041551066461,-0.05872673504837095,0.31860328089746187,0.5238815404272101,-0.9210005207664494,0.41998093231167016,0.3986608698974998,-0.4034002125759755,-0.14190804379085395,0.33822720823213004,0.4197576633092809,0.28705178406346255,-0.8490629045497486,0.6776360442545208,0.017932937608651223,0.7933583754345475,-1.3935729819311082,0.06983839643532219,-0.07116567103460647,0.29256509620898097,-0.05024661005088138,0.1417940225841674,-0.07665462604312112,0.03407471288283004,0.02712738460124431,0.084325072969067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.216666666666667,0.0,1.0,1.0,1.0,-0.05315716050115906,-0.026481832924448986,0.5994129287646193,0.9938694479226523,-0.0733025908509092,-0.04645262777382569,-0.06850112432196151,0.023132762519653925,-0.006622276621878627,0.004091212155321943,-0.04009479455074067,-0.03983414765980837,-0.05847109996168587,0.3187267062205837,0.530490380018175,-0.9326005391749439,0.42056184319104756,0.3980739500824683,-0.400972927940408,-0.1423269236347036,0.33941329739493725,0.41910944898559516,0.2873348182873498,-0.8488380036330813,0.6783419506868331,0.011679571834477542,0.7924864119440822,-1.3899392687202416,0.06958183568613996,-0.06974714968236206,0.2900010455083579,-0.0502717691251503,0.14276226986279505,-0.07878685540199992,0.03385867386788921,0.026850097339086165,0.08501747050444708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.225,0.0,1.0,1.0,1.0,-0.05297643892305299,-0.026555366680467412,0.5994733852640234,0.9938328354142542,-0.0734685478636254,-0.04662298025142802,-0.06873838403504369,0.02339532995896725,-0.006484347599426471,0.003939579501664929,-0.040053315792106144,-0.03936024367419408,-0.05821023881977217,0.3187979404280365,0.5370896472929448,-0.9441661752451201,0.42114062957310583,0.3974984174027938,-0.3985668618175029,-0.14274590660960645,0.34060657939650996,0.4184445490525809,0.28761609529459403,-0.8486154029274305,0.6790530020962616,0.005409053236485883,0.7910684300411597,-1.3853328697179434,0.06932864008358242,-0.06843236564904265,0.28747503509200745,-0.05027192386152568,0.14352337017652816,-0.0806619666584063,0.03365293794970747,0.026575406025703963,0.08556235108858612,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2333333333333334,0.0,1.0,1.0,1.0,-0.052793545974915604,-0.02662831167547551,0.5995327561182229,0.9937962899745952,-0.07363423994666254,-0.04679130206598882,-0.06897468224774342,0.023611054649839473,-0.006352638302166623,0.003793484854573542,-0.04001153666755783,-0.03888947287737033,-0.05794488756851137,0.31881685710785845,0.5436748538521943,-0.9556894203369096,0.42171732052577393,0.3969334106549843,-0.3961816773555412,-0.14316478903239568,0.34180535356454606,0.4177650828746217,0.2878957005865116,-0.8483950801993195,0.6797679898716429,-0.0008745203325033479,0.7891188580338282,-1.3797767295519248,0.0690790673969055,-0.0672206064679659,0.284991679582014,-0.05024814207107875,0.1440831313250912,-0.0822851947747072,0.03345744076737156,0.026303430512233383,0.08596447487813297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2416666666666667,0.0,1.0,1.0,1.0,-0.05260887131811453,-0.026700664117355728,0.5995910550004072,0.9937598140478289,-0.07379966749768052,-0.046957606494829184,-0.06921000110629477,0.023781093150694828,-0.0062272177421667735,0.0036530297046301853,-0.039969478606121385,-0.03842253362018226,-0.05767573508701713,0.31878336508916144,0.5502416282601753,-0.9671624540709856,0.42229194736305425,0.396378073961661,-0.393817000491136,-0.14358337564412443,0.3430079649185948,0.4170731291396691,0.28817371930738356,-0.8481770124188933,0.6804857433442305,-0.00716679517947405,0.786651410936352,-1.3732931251696723,0.06883339152613521,-0.06611124660633294,0.2825552718882318,-0.05020139024163761,0.14444682734218062,-0.08366121129207316,0.03327215243074111,0.026034243752224295,0.08622826620228397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.25,0.0,1.0,1.0,1.0,-0.052422795582494984,-0.02677242130221181,0.5996482969737676,0.9937234097391008,-0.07396483110160522,-0.0471219097541518,-0.06944432530976052,0.023906547112567574,-0.0061081519487845865,0.003518298960563113,-0.039927173435449964,-0.03796005666638916,-0.057403423822075854,0.3186974105215339,0.5567857107011335,-0.9785776390897375,0.4228645437178762,0.3958315565448787,-0.3914724228240707,-0.1440014788697563,0.34421280068691573,0.41637072935308717,0.2884502364603573,-0.8479611761367825,0.681205127641681,-0.013463172458748618,0.7836792151119476,-1.365903732272693,0.06859188962616725,-0.06510364604931596,0.28016974608677914,-0.050132555342513596,0.14461939823038006,-0.08479437292766123,0.033097062658370424,0.025767875476041535,0.0863579472916376,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2583333333333333,0.0,1.0,1.0,1.0,-0.05223569065412097,-0.026843581567997894,0.5997044983320933,0.9936870788327499,-0.07412973155686907,-0.04728423071058997,-0.06967764193951052,0.02398849402701963,-0.00599549905041217,0.00338935912725896,-0.03988466033038861,-0.037502608726839644,-0.057128550576557094,0.31855897888151563,0.5633029485120411,-0.9899275162755304,0.4234351455234904,0.3952930131941724,-0.389147504723023,-0.14441891823316633,0.3454182882224345,0.41565988959087474,0.2887253370183564,-0.847747547827626,0.6819250424657578,-0.019758815547851194,0.7802148990416158,-1.3576296721718273,0.0683548325847938,-0.06419708050573125,0.27783865676809794,-0.05004246104755583,0.14460559383799754,-0.08568890048038846,0.03293216990055914,0.02550431638874029,0.08635763194954515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2666666666666666,0.0,1.0,1.0,1.0,-0.052047919749302514,-0.02691414424423171,0.5997596764458164,0.9936508228109922,-0.07429436989138238,-0.047444590608514386,-0.06990994029085792,0.024028008329687763,-0.005889305920916226,0.0032662573950507567,-0.03984198344582268,-0.03705069605119751,-0.05685166741359855,0.3183680969290697,0.5697892923518271,-1.0012048002926013,0.42400379092762275,0.39476160520311654,-0.3868417785446024,-0.14483551988721557,0.346622893917549,0.41494258101174736,0.28899910595869993,-0.8475361041969701,0.6826444215075067,-0.02604865510736687,0.7762706591252,-1.3484915451902624,0.06812247806615823,-0.06339069535650999,0.2755651706734741,-0.049931879702082016,0.14441007562804864,-0.08634900517510702,0.03277747349520688,0.025243522657230066,0.08623138920650586,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.275,0.0,1.0,1.0,1.0,-0.051859837345020164,-0.02698410959924197,0.5998138496146569,0.9936146428728452,-0.07445874737070327,-0.04760301281304379,-0.07014121170735069,0.02402617528030449,-0.005789606009910136,0.0031490214047836034,-0.03979919007838162,-0.03660476800756216,-0.05657328264556575,0.3181248346297262,0.5762407928307944,-1.0124023753620348,0.42457052015792635,0.39423650160489726,-0.3845547518784651,-0.14525111622820103,0.3478251228162353,0.41422073950462296,0.2892716282432765,-0.8473268224500055,0.6833622322858662,-0.03232739259980355,0.771858307173956,-1.3385094550788823,0.0678950655197108,-0.06268347735970847,0.2733520674058654,-0.04980154104183898,0.14403748674161831,-0.08677897540051771,0.032632968131881546,0.024985420505359013,0.08598328456842497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.283333333333333,0.0,1.0,1.0,1.0,-0.05167178901818425,-0.02705347878604877,0.599867036927621,0.9935785399531084,-0.0746228655003048,-0.04775952256848162,-0.07037144941809442,0.02398409945267427,-0.005696418066279112,0.003037659508728921,-0.039756329238405594,-0.0361652205972658,-0.05629386188295395,0.3178293070524063,0.582653597471393,-1.0235132912105827,0.42513537535295126,0.39371688058045473,-0.38228591075450463,-0.14566554557124622,0.349023518696576,0.41349626475507206,0.28954298876089796,-0.8471196805218808,0.6840774762503138,-0.03858950287528029,0.7669893045646048,-1.3277030276734836,0.0676728126964854,-0.062074239564818834,0.27120174675027586,-0.04965213843237837,0.1434924982290131,-0.08698323364371707,0.032498640071729756,0.02472991077900888,0.08561740462271761,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2916666666666665,0.0,1.0,1.0,1.0,-0.05148411123276811,-0.027122253787706108,0.5999192581307957,0.9935425147412607,-0.07478672602340265,-0.047914146771736284,-0.07060064837838863,0.02390290922314729,-0.005609745533241339,0.002932161390028167,-0.039713450542005556,-0.0357323998658799,-0.05601382912368506,0.3174816762484715,0.5890239479068712,-1.0345307591565929,0.42569840036953444,0.3932019309454836,-0.3800347227659605,-0.14607865186874067,0.3502166644533855,0.41277101894389434,0.289813272244472,-0.8469146572703553,0.6847891890295782,-0.04482923630299562,0.7616747867523777,-1.3160914261007983,0.06745591332341316,-0.06156161598115051,0.26911624071207285,-0.04948433321494694,0.1427798374085132,-0.08696637103867144,0.03237446470212624,0.024476873376970687,0.08513786936893863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3,0.0,1.0,1.0,1.0,-0.051297131103714436,-0.027190437362730076,0.5999705335031544,0.9935065677001704,-0.07495033091547768,-0.048066913760160916,-0.0708288051138829,0.02378375830846044,-0.005529576445894153,0.0028324989364365938,-0.03967060335413029,-0.03530660518208978,-0.055733567867792155,0.31708215311402305,0.5953481772505993,-1.0454481483122626,0.42625964057500815,0.39269085364743556,-0.3778006400759701,-0.146490284458162,0.35140318265338455,0.41204682523776087,0.29008256317260006,-0.8467117326322646,0.6854964407397961,-0.05104062083057026,0.7559255808857923,-1.3036933641557935,0.06724453566965605,-0.061144063378433255,0.26709722882733655,-0.049298757606924815,0.14190430286399547,-0.08673316514243412,0.03226040510482919,0.02422617147166184,0.08454883557716286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.308333333333333,0.0,1.0,1.0,1.0,-0.051111166158834875,-0.027258032991078682,0.6000208837404136,0.9934706990845432,-0.07511368237637234,-0.04821785311316373,-0.07105591756840485,0.02362782514810648,-0.005455883702297771,0.0027386272890172736,-0.039627836130208864,-0.03488809236496243,-0.0554534222464227,0.3166309992346287,0.601622707588301,-1.0562589818925228,0.42681914263069537,0.3921828632225097,-0.3755831022855049,-0.14690029782885608,0.35258173616778543,0.41132546619152044,0.29035094566288583,-0.8465108877458276,0.6861983362891976,-0.057217464277738994,0.7497522185453231,-1.2905271189656276,0.0670388218013529,-0.06081986822923713,0.2651460556393037,-0.04909601649940587,0.1408707694962763,-0.08628858518717086,0.03215641139296732,0.023977655464781922,0.08385449367201758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3166666666666664,0.0,1.0,1.0,1.0,-0.05092652411411467,-0.027325044821030254,0.6000703298468553,0.9934349089590484,-0.07527678282065192,-0.048366995466884916,-0.07128198495556898,0.023436310732269303,-0.0053886256098316645,0.0026504860057227223,-0.03958519591594388,-0.034477076646647994,-0.05517369815731522,0.31612852870939406,0.607844047559688,-1.0669569336283564,0.42737695427169736,0.39167718917694827,-0.37338153914864836,-0.14730855139981877,0.3537510288116558,0.410608682151308,0.29061850336248285,-0.8463121050411849,0.6868940156343297,-0.06335335711301293,0.7431649450923694,-1.276610543686747,0.0668388873696224,-0.060587157288946036,0.2632637495063661,-0.04887668841563775,0.13968418621272627,-0.085637788022489,0.032062420629088706,0.02373116664107,0.08305906002560093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3249999999999997,0.0,1.0,1.0,1.0,-0.05074350267344454,-0.027391477617216577,0.6001188930349345,0.9933991972160859,-0.07543963486676812,-0.04851437234120089,-0.07150700761424808,0.023210435328870842,-0.005327746632091752,0.0025680002945675795,-0.03954272797437347,-0.03407373546336636,-0.05489466440169448,0.3155751099494118,0.6140087900065072,-1.0775358242873019,0.42793312408685574,0.39117307726769396,-0.37119537312706546,-0.14771490930245004,0.35490980593799754,0.40989816972447896,0.2908853193400373,-0.8461153683018098,0.6875826539562909,-0.06944167591721229,0.7361737267124613,-1.2619610807066195,0.06664482181386377,-0.060443910674682355,0.2614510421087002,-0.048641325833898574,0.13834956821122235,-0.0847861071800815,0.03197835718152242,0.02348654049815435,0.08216676607657902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3333333333333335,0.0,1.0,1.0,1.0,-0.05056238936049372,-0.027457336710000183,0.6001665946324293,0.9933635635931618,-0.07560224132545583,-0.048660015978306465,-0.07173098686796961,0.022951504427351513,-0.00527323602103636,0.002491149046962549,-0.03950090603204998,-0.033678437566484025,-0.054616469199060935,0.3149711674441072,0.6201136096715624,-1.0879896183068,0.4284877013019284,0.39066979066570356,-0.36902402178017,-0.14811924016371708,0.3560568549485095,0.40919558036497333,0.2911514759821749,-0.845920662699549,0.688263461735606,-0.07547499778899347,0.7287893910571741,-1.2465967031866176,0.06645706662181672,-0.06038694401434341,0.2597071502390935,-0.04838952308265532,0.1368721298582498,-0.08373852499831025,0.03190472089978025,0.023244016250842936,0.08118172179576222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.341666666666667,0.0,1.0,1.0,1.0,-0.05038346047893495,-0.02752262887050845,0.600213457354821,0.9933280077850353,-0.07576460895277057,-0.04880396077547453,-0.07195392424949784,0.022660653368456622,-0.005224902286995747,0.0024196806710283297,-0.03945890316537557,-0.033290832669834874,-0.054339419136988296,0.31431719331959523,0.6261552798574601,-1.0983124360070788,0.429040741863886,0.39016662820078823,-0.3668669206230806,-0.14852140135382763,0.3571910081023017,0.4085025276411738,0.291417064688367,-0.8457279680309624,0.688935682652887,-0.08144751285216634,0.7210191019818568,-1.230532247820455,0.06627488479786336,-0.06041599758420335,0.25803471569290193,-0.04812355757521258,0.13525675413826876,-0.082501755549097,0.031840265965117354,0.023002564806358095,0.08010856475806127,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.35,0.0,1.0,1.0,1.0,-0.05020698416695363,-0.027587358751618187,0.6002594995585894,0.9932925290913607,-0.0759267333377334,-0.04894623672180413,-0.07217582341968522,0.02233908506002036,-0.005182642747675278,0.0023535178716786185,-0.03941674307195423,-0.03291101314763152,-0.054063783276673445,0.3136137088965711,0.6321305947045933,-1.1084984891038077,0.42959228271522615,0.3896628573726335,-0.3647234431852883,-0.1489212994566373,0.35831113418414734,0.4078205511058217,0.2916821470815935,-0.845537286619443,0.6895986044815737,-0.08735195008835683,0.7128719365225322,-1.2137838626484099,0.06609829279186186,-0.06052888905454856,0.2564339201033372,-0.04784409690190006,0.13350849524421338,-0.08108151410982645,0.031784800531997615,0.022762094763046914,0.07895122258276599,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3583333333333334,0.0,1.0,1.0,1.0,-0.05003321670213436,-0.02765153363685838,0.6003047442080034,0.9932571269544415,-0.0760886214076094,-0.04908687912658751,-0.07239668807038986,0.021988171798115408,-0.005146473969097057,0.0022926823384401777,-0.03937535108781298,-0.03253948315262848,-0.053789559126198296,0.3128613274847893,0.6380364787995023,-1.118542167051219,0.4301423800770837,0.3891578133832124,-0.3625930219546916,-0.1493188029688593,0.35941614968970526,0.4071511690726767,0.29194681136390027,-0.8453485997849116,0.6902515363625997,-0.0931796332180368,0.7043590931164112,-1.196369411098872,0.0659280835245446,-0.06072107466134402,0.2549019163845123,-0.047549728703586425,0.13163270369426883,-0.07948251998617151,0.031739399979430205,0.02252328945137494,0.07771347701007736,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3666666666666667,0.0,1.0,1.0,1.0,-0.04986240386147942,-0.02771516079772353,0.6003492121644934,0.9932218006621311,-0.0762502768004619,-0.049225921638229586,-0.07261652193610962,0.021609145869468934,-0.005116240563888661,0.002236944220808587,-0.039334347243472255,-0.03217602613386357,-0.053516815501731235,0.3120607150096038,0.6438699129232002,-1.1284379792887889,0.4306910841073019,0.3886508394616111,-0.3604750779122131,-0.1497137949350304,0.3605050125790518,0.4064958424393855,0.2922111370812507,-0.8451618984619201,0.6908938290984084,-0.09892358453219563,0.6954881712362782,-1.1783037602863011,0.06576384849027561,-0.06099085343825528,0.25343921415692305,-0.047241580461047095,0.12963444794930945,-0.07771124546050556,0.03170344438029882,0.022285506433425972,0.07639983502392145,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.375,0.0,1.0,1.0,1.0,-0.049694781067097196,-0.027778247722160077,0.6003929241434351,0.993186549429335,-0.07641170313028471,-0.04936339801921417,-0.07283532920491333,0.02120324156839632,-0.005091818456291891,0.0021861785366027106,-0.039293742479009935,-0.0318206468544641,-0.0532456435507231,0.31121260107591936,0.649627948320107,-1.1381805630559907,0.4312384442185883,0.3881412991592415,-0.35836903505207623,-0.15010616264321008,0.36157672382219375,0.4058559816483349,0.2924752021035719,-0.8449771746776878,0.6915248669463318,-0.10457605368357936,0.6862675222435022,-1.1596021364150744,0.06560551160252115,-0.06133572653446606,0.25204529509173623,-0.0469201058267843,0.1275188497483415,-0.07577371520029352,0.0316767593362377,0.02204861348045206,0.07501428264758969,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3833333333333333,0.0,1.0,1.0,1.0,-0.04953057343610433,-0.02784080216810657,0.6004359005884141,0.9931513724081138,-0.07657290411421065,-0.049499342005297486,-0.07305311434336847,0.02077168182323196,-0.005073082709778449,0.002140247762489072,-0.039253563669087124,-0.03147332380629721,-0.052976093456065826,0.31031778078154415,0.6553077049605919,-1.1477646815623734,0.43178450930067724,0.38762857735270334,-0.3562743229940175,-0.15049579669881014,0.3626303267415242,0.4052329471860473,0.292739083070188,-0.8447944215705793,0.6921440671425348,-0.11012910309337709,0.6767052722202838,-1.1402795246327413,0.06545300363702822,-0.06175311085480528,0.25071938496896373,-0.04658567675658587,0.12529095692530912,-0.07367591741485713,0.03165920066774519,0.021812477666709462,0.07356073704717359,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3916666666666666,0.0,1.0,1.0,1.0,-0.049369995896504586,-0.02790283214497543,0.6004781616006882,0.9931162687034606,-0.07673388357772082,-0.049633787193437896,-0.07326988195582106,0.020315671376758278,-0.005059904212136831,0.0020990078061957455,-0.03921383755501675,-0.031134012709655105,-0.05270818214463015,0.3093771160243631,0.6609063695237783,-1.1571852217998697,0.4323293276125388,0.38711208064499475,-0.35419037863592684,-0.15088259058915318,0.36366490643761556,0.40462804969142063,0.29300285544803434,-0.8446136333832427,0.6927508792304513,-0.11557464763267578,0.6668093049581825,-1.120350649875106,0.06530624077824565,-0.06224038935367604,0.24946053222386189,-0.04623861895553305,0.12295574249233776,-0.07142382145025716,0.03165062781065098,0.021576970199761458,0.07204302323973621,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4,0.0,1.0,1.0,1.0,-0.04921325334890237,-0.027964345881097506,0.6005197268895667,0.9930812373880005,-0.07689464544781409,-0.04976676694433674,-0.07348563666454647,0.01983639171210895,-0.005052149893528816,0.0020623104448642448,-0.03917458917995918,-0.0308026488376408,-0.05244189750209564,0.3083915366543329,0.6664211933765616,-1.1664371923936252,0.43287294664698134,0.3865912375301421,-0.35211664745695315,-0.15126644034806902,0.3646795891163965,0.40404255016187635,0.2932665935336988,-0.8444348054005832,0.6933447841965305,-0.12090447162339757,0.6565872633683223,-1.0998299868191452,0.06516512361398497,-0.06279493439835693,0.24826764023571313,-0.04587921938901063,0.12051809033673533,-0.06902336069236958,0.03165090024885964,0.021341970801287413,0.07046485462610441,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.408333333333333,0.0,1.0,1.0,1.0,-0.04906054086937571,-0.02802535178969826,0.6005606157315461,0.9930462775157128,-0.07705519374494174,-0.0498983142931116,-0.07370038300194846,0.019334996429624156,-0.005049683650696886,0.002030004669503103,-0.03913584181489876,-0.030479148543707747,-0.0521772009016113,0.30736204149730645,0.671849490579917,-1.1755157215801888,0.4334154130061052,0.38606549840502213,-0.3500525846319983,-0.1516472442456367,0.36567354127656115,0.4034776603465478,0.293530370452182,-0.8442579338698879,0.6939252934742197,-0.12611024480381205,0.6460465532336168,-1.0787317767470395,0.06502953872910888,-0.0634141244005515,0.24713948682453024,-0.04550772801602376,0.11798277796380319,-0.06648040902190622,0.03165987779982893,0.021107369130717313,0.06882981851975778,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4166666666666665,0.0,1.0,1.0,1.0,-0.04891204395102673,-0.02808585843604696,0.6006008469348694,0.9930113881349155,-0.07721553257544758,-0.05002846186603279,-0.07391412531076998,0.018812606898201686,-0.005052367391809302,0.00200193771661642,-0.039097617126248756,-0.03016341050253149,-0.0519140290098942,0.306289699240936,0.6771886359304552,-1.1844160553394092,0.4339567722924665,0.38553433545679955,-0.34799765600987764,-0.15202490248166942,0.3666459687491265,0.4029345433448446,0.293794258163696,-0.8440830159150713,0.6944919478385264,-0.13118353971028562,0.635194347656598,-1.0570700464838767,0.06489936060140145,-0.06409535797877286,0.24607473939755042,-0.045124357821463845,0.11535445884791384,-0.06380075615653902,0.03167742174410959,0.02087306524597654,0.06714136366776424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.425,0.0,1.0,1.0,1.0,-0.04876793878207837,-0.02814587450636846,0.6006404388084476,0.9929765683006315,-0.07737566612489419,-0.05015724180242306,-0.0741268676506414,0.018270308156865023,-0.0050600620835024885,0.0019779559814292825,-0.0390599354013575,-0.029855316803696786,-0.051652295303908406,0.3051756491688017,0.6824360630408604,-1.1931335556882534,0.43449706901612856,0.38499724243870925,-0.34595133897537245,-0.15239931687599442,0.36759611559069305,0.4024143144106055,0.2940583274812505,-0.8439100494491216,0.6950443162020158,-0.13611585070309573,0.6240375918957941,-1.0348586279417926,0.06477445349921007,-0.06483606687057497,0.24507196826443423,-0.044729284308201445,0.11263764517479902,-0.06099008329920608,0.03170339615761297,0.020638969705404353,0.06540278889939355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.433333333333333,0.0,1.0,1.0,1.0,-0.04862839255841268,-0.02820540877867817,0.6006794091346818,0.992941817086379,-0.07753559865240255,-0.050284685681189,-0.07433861371035365,0.01770914506820243,-0.005072628774504399,0.0019579058619102513,-0.03902281580015903,-0.029554733943401412,-0.051391891487097434,0.30402110172921776,0.6875892624620518,-1.201663699138439,0.4350363465174533,0.38445373434228997,-0.3439131232054704,-0.15277039055347277,0.3685232628353732,0.4019180419565245,0.2943226480996562,-0.8437390330866479,0.695581994320183,-0.14089861457843966,0.6125830085446271,-1.012111177732189,0.0646546733691522,-0.06563372795932554,0.24412965891940086,-0.04432264485717319,0.10983669127272333,-0.05805393956330618,0.03173766928131205,0.020405003480390427,0.06361723268840658,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4416666666666664,0.0,1.0,1.0,1.0,-0.04849356382839655,-0.0282644700956032,0.6007177751458836,0.9929071335953936,-0.07769533448607217,-0.050410824451596996,-0.07454936672570499,0.017130118730726587,-0.005089929588274806,0.00194163454629249,-0.03898627662564447,-0.029261513733945664,-0.05113268888661262,0.3028273389258277,0.6926457798499375,-1.2100020753171232,0.4355746469056144,0.3839033469727205,-0.34188251132671577,-0.15313802762361398,0.3694267271119051,0.40144674875121705,0.294587288635939,-0.8435699660577818,0.6961046034134892,-0.14552323269266698,0.600837103063927,-0.9888411965954047,0.06453986972687287,-0.06648587452663168,0.24324622357054237,-0.0439045381204306,0.10695577788244037,-0.054997719389696664,0.03178011487512511,0.02017109773688297,0.06178766358097221,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4499999999999997,0.0,1.0,1.0,1.0,-0.048363602867772006,-0.028323067339226536,0.6007555535040477,0.9928725169712763,-0.07785487801952641,-0.05053568836798219,-0.07475912940296797,0.016534183158266474,-0.005111828680766702,0.0019289907476040986,-0.038950335609722914,-0.02897549414331165,-0.05087453986661602,0.3015957145176733,0.6976032141797839,-1.2181443857483625,0.4361120110129012,0.38334563643351277,-0.3398590194792947,-0.15350213285547995,0.37030585913341385,0.40100141330002953,0.2948523166809083,-0.8434028481243665,0.6966117887131992,-0.1499810945332114,0.5888061696915448,-0.9650620484972139,0.06442988755662848,-0.06739010676407142,0.24242001203525487,-0.04347502352223753,0.10399889736902534,-0.05182664109846025,0.03183061353260408,0.019937193514205642,0.05991687148721336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4583333333333335,0.0,1.0,1.0,1.0,-0.04823865208231724,-0.028381209407979974,0.6007927602837457,0.9928379664080498,-0.07801423370961375,-0.05065930692812964,-0.07496790384810761,0.01592224223487518,-0.005138193160091929,0.0019198253861415267,-0.03891501021143507,-0.02869650007460075,-0.05061727927255124,0.30032765401694084,0.7024592160114632,-1.2260864427920768,0.43664847836489157,0.38278017852665264,-0.33784217779279485,-0.1538626113489846,0.37116004206805553,0.40058297139957605,0.2951177988614824,-0.8432376794992117,0.6971032179382761,-0.15426360267038808,0.5764962977599586,-0.9407869792835166,0.06432456921718566,-0.06834410155426629,0.2416493220675442,-0.04303412090766623,0.10096983996436659,-0.04854572670136337,0.03188905394311825,0.019703241321460396,0.05800745984601452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.466666666666667,0.0,1.0,1.0,1.0,-0.04811884643590801,-0.02843890519560428,0.6008294109579283,0.9928034811596076,-0.07817340607528432,-0.05078170881510868,-0.0751756915019132,0.01529514695423403,-0.005168893964945921,0.0019139922203134962,-0.03888031792436295,-0.028424344093833726,-0.050360725912059895,0.29902465447316684,0.7072114858091165,-1.233824168736421,0.43718408716652096,0.382206568074275,-0.33583153077816896,-0.15421936820394105,0.3719886897994866,0.4001923178550068,0.2953838009132936,-0.8430744607690088,0.6975785797106328,-0.15836219901649184,0.563913378454175,-0.9160291347991256,0.06422375634705046,-0.06934562152163481,0.24093240916561065,-0.04258181036181696,0.09787218112420226,-0.04515978309505009,0.031955334091188226,0.019469200671993203,0.05606183867358894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.475,0.0,1.0,1.0,1.0,-0.04800431390152934,-0.028496163572187556,0.6008655203864325,0.9927690605485335,-0.07833239969764805,-0.050902921842375805,-0.0753824930812151,0.014653692952959253,-0.005203806698527541,0.0019113484257478389,-0.03884627659014553,-0.028158827114369362,-0.050104684073957524,0.29768828403333264,0.7118577723190328,-1.2413535950387289,0.4377188743040091,0.3816244181679587,-0.3338266376400347,-0.15457230818834822,0.37279124508679223,0.3998303083479919,0.29565038776300223,-0.8429131928213451,0.6980375819161693,-0.16226839230760404,0.5510631120481668,-0.8908015783928835,0.06412729176069165,-0.07039252334672508,0.2402674958943385,-0.04211803221560839,0.0947092700808172,-0.04167338475164484,0.03202936238424714,0.01923503957354189,0.05408221851250561,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4833333333333334,0.0,1.0,1.0,1.0,-0.04789517593270286,-0.028552993367286103,0.6009011028069954,0.9927347039742751,-0.07849121922121251,-0.05102297290199866,-0.07558830852635512,0.013998618347360922,-0.0052428124144406636,0.001911755122521544,-0.03881290471463841,-0.027899739045261697,-0.04984894508397784,0.2963201812680401,0.7163958710099193,-1.2486708617096358,0.4382528753625325,0.3810333593518296,-0.3318270725132633,-0.15492133540753453,0.3735671776341669,0.3994977614424794,0.2959176236196977,-0.8427538767761165,0.6984799500191745,-0.16597378671146523,0.5379510156594702,-0.8651173077391006,0.06403502132480643,-0.07148276533644582,0.2396527807526594,-0.04164268725093179,0.09148421967293485,-0.038090858025355834,0.03211105870029596,0.01900073399055291,0.052070605298482064,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4916666666666667,0.0,1.0,1.0,1.0,-0.04779154795271251,-0.02860940335512106,0.6009361718285886,0.9927004109206479,-0.07864986935628276,-0.051141887915878724,-0.0757931369550646,0.013330601883675257,-0.005285798350873255,0.001915077850497027,-0.03878022178313414,-0.027646859410440493,-0.049593288894371944,0.2949220542548082,0.720823622580024,-1.2557722168343806,0.4387861246594225,0.3804330387456846,-0.32983242462749035,-0.15526635297586375,0.37431598208134115,0.39919546071423595,0.29618557207467383,-0.8425965139215026,0.6989054253378106,-0.16947011145088564,0.5245824315634406,-0.8389892709107638,0.06394679580238871,-0.07261441423983106,0.2390864466122289,-0.04115563711485637,0.08819989753217072,-0.034416267191166305,0.03220035534673649,0.01876626729580666,0.050028796161969424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5,0.0,1.0,1.0,1.0,-0.04769353985891851,-0.028665402241835242,0.6009707404268925,0.9926661809626546,-0.07880835488249657,-0.051259691789882544,-0.07599697662288857,0.012650261411805835,-0.0053326586091193414,0.0019211869921531605,-0.038748248571000996,-0.027399957945274236,-0.04933748570297803,0.29349567941052535,0.7251389115359766,-1.2626540162248152,0.4393186552925723,0.37982311911449906,-0.3278422984030595,-0.15560726269278213,0.37503717592636976,0.3989241569892933,0.29645429620881,-0.8424411056545197,0.6993137632885407,-0.17274925131870233,0.5109625361093073,-0.8124303816493628,0.06386247265204315,-0.07378565129452008,0.23856666874342292,-0.040656704951367306,0.08485891870420814,-0.03065340232874969,0.03229719792208541,0.018531629725653254,0.047958376186398866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5083333333333333,0.0,1.0,1.0,1.0,-0.047601256539365346,-0.028720998654781667,0.6010048209417318,0.992632013772604,-0.07896668065345355,-0.051376408370813795,-0.07619982489026977,0.01195815269248496,-0.005383294772329312,0.001929958142688436,-0.03871700744590115,-0.027158795176201435,-0.04908129759640643,0.2920429000661632,0.7293396648485124,-1.2693127231952033,0.43985049920362324,0.37920327789077596,-0.32585631348176664,-0.1559439647250532,0.37573029739307795,0.39868457067542346,0.2967238587067086,-0.842287653426075,0.699704731607584,-0.17580327794746609,0.49709634927821433,-0.7854535337797452,0.06378191776876596,-0.07499477748862171,0.2380916224417573,-0.040145676256843066,0.08146363978084215,-0.02680576916427535,0.0324015460718563,0.018296817852407887,0.045860716144332514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5166666666666666,0.0,1.0,1.0,1.0,-0.0475147983987987,-0.028776201133802325,0.6010384250763057,0.992597909125511,-0.07912485160238453,-0.05149206040618157,-0.07640167819637904,0.01125476854766563,-0.005437616460198715,0.0019412724268323526,-0.03868652265750785,-0.026923122988586106,-0.04882448021048921,0.2905656247780676,0.7334238506906136,-1.2757449084544776,0.44038168725538507,0.37857320615635537,-0.3238741046956969,-0.15627635729706285,0.37639490325605046,0.3984773941698887,0.29699432197667425,-0.8421361586903129,0.7000781085576129,-0.17862448168298184,0.4829887449227366,-0.758071614726239,0.06370500715149441,-0.07624021802095649,0.23765949026292366,-0.03962229996459288,0.0780161546140612,-0.022876580974764416,0.0325133741300665,0.01806183408672224,0.04373697123132292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.525,0.0,1.0,1.0,1.0,-0.04743426189112281,-0.028831018124440885,0.6010715638980398,0.9925638669037704,-0.0792828727487929,-0.05160666950673866,-0.07660253203974568,0.010540538363433162,-0.005495541815268113,0.0019550167619616244,-0.03865682061075034,-0.02669268518730024,-0.0485667844003446,0.2890658253714468,0.7373894772638914,-1.2819472501073073,0.4409122493228148,0.3779326075904267,-0.3218953219773846,-0.15660433639112975,0.37703056663664564,0.39830329432584405,0.29726574827554303,-0.841986622857963,0.700433681128106,-0.18120540389958917,0.46864446172125707,-0.7302975180894045,0.06363162848261994,-0.07752052594032222,0.23726846886695463,-0.039086289761120496,0.07451829167851032,-0.018868752653500298,0.03263267163786221,0.017826686221242838,0.04158808081869747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.533333333333333,0.0,1.0,1.0,1.0,-0.047359740055247485,-0.028885457973018062,0.6011042478409024,0.992529887101095,-0.07944074920598744,-0.05172025611178031,-0.0768023809657063,0.009815827953812629,-0.005556997916517439,0.001971084067011217,-0.03862793011873057,-0.026467218054009665,-0.04830795791154437,0.2875455347130744,0.7412345917193012,-1.2879165337559677,0.44144221439676207,0.37728119739068333,-0.319919630214581,-0.1569277954597482,0.37763687478402563,0.398162914958997,0.2975381998373053,-0.8418390472532922,0.7007712432379245,-0.1835388695818463,0.4540681148763759,-0.702144155249087,0.06356168260439721,-0.07883438494325934,0.2369167754657031,-0.038537325635423225,0.0709716131430238,-0.014784897027564359,0.03275944373142159,0.01759138702514873,0.039414769245671444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5416666666666665,0.0,1.0,1.0,1.0,-0.04729132305120525,-0.028939528923481957,0.6011364867090165,0.9924959698257121,-0.07959848618941193,-0.05183283945720671,-0.07700121856064986,0.009080939793171709,-0.005621921115907294,0.001989373416685625,-0.03859988263103479,-0.026246450904049128,-0.0480477470426393,0.2860068442117494,0.7449572791784976,-1.293649652694792,0.44197161069955476,0.3766187011747057,-0.3179467090529562,-0.15724662515172014,0.37821342685569603,0.39805687937538464,0.29781173900440006,-0.8416934330742105,0.7010905939488672,-0.18561801998744243,0.4392642085779741,-0.6736244659632717,0.06349508487645483,-0.08018061131168763,0.2366026538659649,-0.03797505566092152,0.06737741570318923,-0.010627323507036435,0.032893711391135394,0.017355953898194887,0.03721754766690344,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.55,0.0,1.0,1.0,1.0,-0.04722909869334805,-0.02899323911592876,0.6011682896814137,0.9924621153028218,-0.0797560890256631,-0.051944437546360675,-0.07719903745299425,0.008336113623406893,-0.00569025729374848,0.00200979014071962,-0.0385727124337484,-0.026030106645485718,-0.04778589828892402,0.28445190104661705,0.7485556618622674,-1.299143608188689,0.44250046581136965,0.37594485386882187,-0.3159762526501482,-0.15756071305409688,0.3787598317124121,0.3979857929005464,0.2980864283604909,-0.8415497813549889,0.7013915356990396,-0.18743634519600483,0.4242371492442154,-0.6447514279364963,0.06343176639936998,-0.08155815496977414,0.23632438009215773,-0.037399098006855036,0.0637367332178751,-0.006398039132543554,0.03303551154479778,0.017120408592408154,0.03499671696855611,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.558333333333333,0.0,1.0,1.0,1.0,-0.04717315297738952,-0.02904659658667236,0.601199665317767,0.9924283238763181,-0.07991356316207716,-0.05205506712366078,-0.07739582932078434,0.007581527440563007,-0.005761962029024446,0.0020322458677503046,-0.03854645681750885,-0.025817902341957695,-0.04752215995655053,0.2828829051251493,0.7520278983325679,-1.304395509827067,0.44302880680621093,0.3752593985918761,-0.31400796938475356,-0.1578699434518344,0.3792757057426606,0.39795024538984225,0.29836233086348,-0.8414080929310037,0.7016738725650098,-0.1889877163394671,0.40899125954247717,-0.615538065337331,0.06337167508962516,-0.08296609964203672,0.23608026756886558,-0.03680904317462874,0.06005034118274577,-0.0020987520747905997,0.03318489701877536,0.016884777006538343,0.03275237176495249,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5666666666666664,0.0,1.0,1.0,1.0,-0.04712357059801342,-0.029099609269725286,0.601230621564948,0.9923945960097843,-0.08007091417675237,-0.052164743651049734,-0.07759158490575406,0.006817298863963971,-0.005837000681087779,0.002056658513837718,-0.03852115621008915,-0.02560954978029939,-0.04725628373566659,0.2813021057742926,0.755372182854642,-1.309402575944311,0.44355666039619673,0.3745620855414546,-0.31204158152400047,-0.15817419710700736,0.37976067073212455,0.3979508136992999,0.29863950997747046,-0.84126836840488,0.7019374085617888,-0.19026641730290783,0.3935307931807719,-0.5859974562462478,0.06331477659164197,-0.08440366209573336,0.2358686718400338,-0.03620445645176329,0.05631876306205985,0.0022691223746984512,0.033341936331439115,0.01664908905901985,0.030484405478852228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5749999999999997,0.0,1.0,1.0,1.0,-0.04708043545375263,-0.029152284999536256,0.6012611657642496,0.992360932286779,-0.08022814778886511,-0.05227348128728177,-0.07778629403364663,0.00604348688862147,-0.0059153483795747735,0.0020829522157219077,-0.038496854270323774,-0.02540475604303712,-0.0469880262209937,0.27971179817010083,0.7585867448855808,-1.3141621340978378,0.4440840530827383,0.37385267089028057,-0.31007682485408633,-0.15847335105936378,0.38021435179369495,0.3979880640960872,0.29891802980233734,-0.8411306081133534,0.7021819459896573,-0.19126717567904294,0.37785995044756326,-0.5561427390208884,0.06326105501350932,-0.08587019045428135,0.23568799479846247,-0.03558488057463005,0.0525422784862295,0.0067044533032434295,0.03350671332412958,0.01641337864302095,0.02819251650506116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5833333333333335,0.0,1.0,1.0,1.0,-0.04704383113583649,-0.029204631514814547,0.6012913046591226,0.9923273334104296,-0.08038526986912596,-0.05238129287006354,-0.0779799456405381,0.005260094019585299,-0.005996989919920164,0.002111057208834907,-0.0384735979408406,-0.025203224085369007,-0.04671715036820801,0.2781143195129752,0.7616698486954347,-1.3186716215946592,0.44461101131308856,0.3731309157005499,-0.3081134482773594,-0.15876727844991786,0.3806363753735617,0.3980625545876873,0.2991979551995393,-0.8409948120941629,0.7024072838368731,-0.19198519275586134,0.3619828944658243,-0.5259871175708453,0.06321051347461526,-0.0873651615704718,0.23553668839504605,-0.03494983858850331,0.048720933309085446,0.011206383166831868,0.03367932662673434,0.01617768366570571,0.025876215450733042,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.591666666666667,0.0,1.0,1.0,1.0,-0.04701384139772396,-0.029256656463257782,0.6013210444032661,0.9922938002023624,-0.08054228645021738,-0.052488189901063,-0.0781725278048608,0.004467068784358282,-0.006081919562465614,0.002140909650813637,-0.03845143745716294,-0.025004653315458487,-0.04644342687443632,0.27651204495750314,0.7646197931266778,-1.3229285860573519,0.44513756164064855,0.37239658486410604,-0.30615121338083556,-0.15905584836917216,0.3810263673488464,0.39817483714886776,0.2994793519127829,-0.8408609800522583,0.7026132162471695,-0.19241617231439578,0.3459037681096855,-0.4955438655347866,0.06316317445488773,-0.0888881774529815,0.2354132577960677,-0.03429883689130886,0.04485455150492701,0.015774314286437496,0.033859888955932727,0.015942046173087476,0.02353483343782825,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6,0.0,1.0,1.0,1.0,-0.04699055060207762,-0.02930836740698608,0.6013503905689238,0.992260333601,-0.08069920373704477,-0.052594182533784985,-0.07836402778477544,0.0036643086167564088,-0.006170140733834302,0.002172451391286122,-0.03843042631141809,-0.024808740176080608,-0.04616663547173037,0.2749073833077353,0.7674349114972628,-1.326930686020239,0.4456637308873367,0.37164944607633355,-0.3041898939807583,-0.15933892573143968,0.38138395123197716,0.3983254598257946,0.29976228668213817,-0.8407291113246115,0.7027995310608369,-0.19255634801440658,0.3296267115191376,-0.4648263293605792,0.06311907993629462,-0.09043896074540259,0.23531626395739025,-0.0336313684461409,0.040942748868160184,0.020407892892866375,0.034048526245501476,0.015706512561199926,0.021167531444894472,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6083333333333334,0.0,1.0,1.0,1.0,-0.046974044142000015,-0.029359771828475646,0.6013793481552319,0.9922269346592634,-0.08085602811663187,-0.05269927956430499,-0.07855443206049628,0.0028516631029064507,-0.006261665630030001,0.0022056296888942777,-0.0384106211696202,-0.02461517872541198,-0.045886566122691895,0.27330277249059637,0.7701135716519968,-1.3306756915466948,0.44618954630625346,0.37088926885168266,-0.3022292756482124,-0.15961637117660785,0.38170874649664904,0.3985149686970822,0.30004682735020793,-0.840599204842905,0.7029660084379178,-0.19240250914739465,0.31315588013459905,-0.4338479302921394,0.06307829133037846,-0.09201734925990857,0.23524432558027497,-0.03294691614460832,0.03698494846282596,0.025106990783912986,0.03424537660987714,0.015471133872060339,0.018773310658479758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6166666666666667,0.0,1.0,1.0,1.0,-0.04696440883343769,-0.029410877136776207,0.6014079215964702,0.9921936045417195,-0.08101276616748761,-0.05280348842483482,-0.07874372638112975,0.002028937577007675,-0.0063565147215351335,0.0022403968770305415,-0.03839208174180723,-0.024423661213798,-0.04560302010811169,0.2717006748219454,0.7726541761661728,-1.3341614848584413,0.446715035742843,0.3701158235886684,-0.30026915522108705,-0.15988804100051648,0.3820003670396909,0.39874390967219314,0.30033304295896945,-0.8404712590934105,0.7031124195718116,-0.19195202454100668,0.29649546315423825,-0.40262216527001904,0.06304088918724249,-0.09362328957745691,0.23519612041975835,-0.032244956302190375,0.032980397753090696,0.0298716846769298,0.034450589144195964,0.015235966172479909,0.016351023795762032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.625,0.0,1.0,1.0,1.0,-0.046961733275778086,-0.02946169067379032,0.6014361147700694,0.9921603445212251,-0.08116942466827257,-0.05290681518007883,-0.07893189581554903,0.0011958970515295797,-0.006454716161670369,0.00227670998019045,-0.03837487060524943,-0.024233878653277263,-0.04531581099761761,0.2701035720815796,0.7750551627045674,-1.3373860609678618,0.4472402277927075,0.3693288806920584,-0.2983093403078831,-0.16015378711497769,0.3822584197925339,0.39901283010836436,0.30062100383594453,-0.8403452720733636,0.7032385255011805,-0.191202864405563,0.2796497023057376,-0.37116260675861046,0.06300697268375344,-0.09525682972928662,0.23517038591279293,-0.03152496226450863,0.028928187328637334,0.03470223336712874,0.03466432256515106,0.015001071013283074,0.013899387349354253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6333333333333333,0.0,1.0,1.0,1.0,-0.04696610817779983,-0.029512219720390517,0.6014639310042362,0.9921271559751164,-0.08132601060559683,-0.05300926452632123,-0.0791189248067928,0.000352270463525468,-0.006556305100304041,0.0023145302828544356,-0.03835905298148672,-0.024045521375907247,-0.04502476549510276,0.268513960415186,0.7773150045379351,-1.3403475283044182,0.4477651519542389,0.36852820975984696,-0.29634964878920717,-0.1604134570382583,0.3824825034951682,0.39932228022831195,0.30091078166838864,-0.8402212412431891,0.7033440760276342,-0.19015361992241853,0.26262291080896505,-0.3394829015177159,0.06297665889148041,-0.0969181109838213,0.23516591909930717,-0.03078640810257105,0.02482727112118388,0.0395990528248813,0.034886743699278355,0.014766515963753335,0.011416994700021998,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6416666666666666,0.0,1.0,1.0,1.0,-0.046977626646308134,-0.02956247150214873,0.6014913730850519,0.9920940403810005,-0.08148253118078456,-0.05311083979316375,-0.07930479722944567,-0.0005022447844332154,-0.006661322906084335,0.0023538228535361244,-0.0383446964686138,-0.02385827957690614,-0.04472972415214241,0.2669343450828726,0.7794322112180502,-1.3430441093264904,0.4482898387742322,0.367713578842328,-0.29438990832289463,-0.1606668939166872,0.3826722076445536,0.3996728143221124,0.30120244956426584,-0.8400991634739677,0.7034288087461809,-0.1888035203853311,0.24541949239278216,-0.30759676833987726,0.06295008182748751,-0.09860735877074922,0.2351815758141651,-0.03002877237356205,0.02067648799426669,0.044562689384138876,0.035118025827144406,0.014532375217048976,0.008902330031066441,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.65,0.0,1.0,1.0,1.0,-0.04699638443497853,-0.029612453194456774,0.6015184432629206,0.9920609993122123,-0.08163899381545081,-0.05321154294781543,-0.07948949644943579,-0.001367978013003313,-0.00676981630137299,0.0023945560269985297,-0.03833187073120775,-0.023671843838380637,-0.04443054194408494,0.2653672350754305,0.7814053294111482,-1.3454741411100828,0.448814319984697,0.36688475378033447,-0.2924299558589711,-0.16091393657781766,0.382827111628406,0.4000649917180476,0.30149608209884105,-0.8399790349895716,0.7034924481948186,-0.187152447719251,0.22804396021955275,-0.2755179947811781,0.06292739129419522,-0.10032487277915725,0.2352162691273174,-0.029251541921980206,0.016474584569924344,0.04959379120344498,0.03535834689339823,0.014298730260586812,0.006353782971058042,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.658333333333333,0.0,1.0,1.0,1.0,-0.0470224801511525,-0.02966217192682207,0.601545143258238,0.9920280344329933,-0.08179540615574522,-0.0533113746018128,-0.07967300538566742,-0.002245280211714631,-0.006881836414958041,0.00243670084766431,-0.038320647150669136,-0.0234859056292494,-0.04412708870474519,0.2638151376208851,0.783232943888376,-1.3476360759061767,0.44933862862913543,0.36604149762934207,-0.2904696371707727,-0.16115441961538687,0.38294678405405236,0.40049937750883646,0.3017917553458225,-0.839860851302958,0.7035347051290318,-0.1852009482171324,0.2105009555585058,-0.2432604329181176,0.06290875151636732,-0.10207101627707105,0.23526896702010358,-0.02845421569709461,0.012220239142605172,0.054693078196428324,0.035607887594907295,0.01406567060380004,0.003769663885211383,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6666666666666665,0.0,1.0,1.0,1.0,-0.04705601541857063,-0.029711634786132708,0.6015714742661662,0.9919951474934644,-0.08195177607513078,-0.05341033402003091,-0.07985530657289498,-0.0031345187714462656,-0.006997437758771295,0.00248023047821694,-0.0383110984395536,-0.02330015777699558,-0.043819249417483566,0.26228055260514493,0.7849136786704566,-1.349528481658718,0.44986279917663646,0.3651835701757166,-0.288508806408636,-0.16138817350610257,0.38303078228078274,0.4009765430213214,0.3020895468920895,-0.8397446071461749,0.7035552759262388,-0.18295024135353333,0.1927952660427179,-0.21083799416622195,0.06289433958706736,-0.103846204706175,0.23533868928963475,-0.02763630856034427,0.007912086516382866,0.05986131065204403,0.03586682936040031,0.01383329455612925,0.0011482197256862392,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.675,0.0,1.0,1.0,1.0,-0.047097094994298275,-0.02976084881869878,0.601597436960409,0.9919623403244525,-0.08210811167558066,-0.053508419131822665,-0.08003638222524238,-0.004036072036098567,-0.007116677135602953,0.0025251195770514263,-0.03830329822416269,-0.02311429490713756,-0.04350692436211765,0.26076596693165954,0.7864461983224214,-1.3511500424756138,0.4503868676222532,0.3643107275509058,-0.2865473256826121,-0.16161502475805928,0.38307865216265874,0.40149706601970386,0.3023895358351625,-0.8396302963936891,0.7035538421244599,-0.18040222555328778,0.17493184334042455,-0.17826464320607638,0.06288434373644014,-0.10565089361288305,0.23542450367921242,-0.026797355056846217,0.0035487435870795725,0.0650992567849007,0.03613535223704445,0.01360171004646693,-0.0015123496534963365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.683333333333333,0.0,1.0,1.0,1.0,-0.04714582683838243,-0.029809821030892313,0.6016230314958899,0.9919296148322422,-0.0822644212870944,-0.05360562654410897,-0.08021621429977528,-0.00495032370804603,-0.0072396124858638096,0.0025713436492598206,-0.038297320600143826,-0.022928013846507146,-0.04319002911870353,0.25927384884592347,0.787829209392797,-1.352499559045486,0.4509108715722438,0.36342272194883524,-0.28458506468064915,-0.16183479609038334,0.38308992800723407,0.4020615306344031,0.3026918027627069,-0.8395179119787338,0.7035300700986805,-0.17755948081565331,0.1569158200650933,-0.14555439106302082,0.06287896143976845,-0.10748556598476844,0.23552552124126103,-0.025936913125917394,-0.000871164517287637,0.07040765946842775,0.03641363270063702,0.013371035473943582,-0.004213874816669794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6916666666666664,0.0,1.0,1.0,1.0,-0.047202322135088876,-0.02985855838822762,0.601648257510253,0.9918969729933158,-0.08242071346545317,-0.053701951556221594,-0.0803947845595434,-0.005877657143946124,-0.007366301682217509,0.0026188783757959723,-0.03829323966637629,-0.022741013986728516,-0.04286849443107943,0.25780664225139865,0.7890614619901729,-1.3535759489933308,0.451434850312916,0.3625193014511597,-0.2826219003285911,-0.16204730664349123,0.3830641327540373,0.4026705270108443,0.30299642971350643,-0.8394074458024567,0.7034836108775154,-0.1744252681177283,0.13875252575059172,-0.11272128739507892,0.06287839738336687,-0.10935071906699956,0.2356408909452079,-0.025054567724799304,-0.005348977936567856,0.07578720242333192,0.03670184140714072,0.013141400580889417,-0.0069581998074452756,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6999999999999997,0.0,1.0,1.0,1.0,-0.047266695264887214,-0.02990706781274484,0.6016731141241138,0.9918644168491497,-0.08257699698815593,-0.053797388176289124,-0.08057207463553001,-0.006818449578921342,-0.007496801281547139,0.00266769892558942,-0.03829112904289954,-0.022552997604745006,-0.04254226593468791,0.25636676104396133,0.7901417514886402,-1.3543782471687373,0.4519588448619666,0.36160020996438524,-0.280657716498229,-0.16225237221913,0.38300077837495794,0.40332465067479195,0.3033035001194926,-0.839298888635719,0.7034141001018898,-0.17100352554588305,0.12044750171992691,-0.07977941204925898,0.06288286130921583,-0.1112468507413289,0.23576979355275918,-0.024149934341173296,-0.009885975424250848,0.08123847614286084,0.03700014090501025,0.01291294733642756,-0.009747165058162643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7083333333333335,0.0,1.0,1.0,1.0,-0.04733906372668753,-0.029955356178583314,0.6016975999400068,0.9918319485011273,-0.08273328084849968,-0.05389192913894019,-0.08074806608696838,-0.0077730663184384765,-0.007631165244510173,0.002717779256028435,-0.038291061378916996,-0.022363670137845383,-0.042211303754774936,0.2549565834923006,0.7910689203521717,-1.3549056058608184,0.45248289800140296,0.36066518727213753,-0.2786924037693784,-0.16244980554917746,0.38289936649696643,0.40402450161322534,0.30361309872858994,-0.8391922300135163,0.703321158126546,-0.16729886113002523,0.10200651468057709,-0.046742865949216394,0.06289256576109459,-0.11317444555354328,0.2359114347882929,-0.02322266237112347,-0.01448334774971305,0.08676194384730329,0.03730868332773807,0.012685830818728316,-0.0125825902579213,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.716666666666667,0.0,1.0,1.0,1.0,-0.04741954801017585,-0.03000343030565787,0.6017217130399873,0.9917995701056315,-0.0828895742477915,-0.05398556592409253,-0.08092274045951763,-0.008741854938028598,-0.007769443633351143,0.002769091407237033,-0.03829310785726109,-0.022172740411342377,-0.04187558198270658,0.25357844669179425,0.7918418600666498,-1.3551572949345576,0.45300705429131816,0.3597139692051595,-0.27672585925175747,-0.16263941659198206,0.38275938924579606,0.404770683072247,0.3039253115082882,-0.8390874581220735,0.7032043902642577,-0.16331654238204485,0.08343556888774195,-0.013625761384954416,0.06290772375570075,-0.11513396048096869,0.23606503784076027,-0.022272438339389078,-0.01914217137043761,0.09235790776419228,0.03762760808740273,0.012460220084726803,-0.015466257290515095,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.725,0.0,1.0,1.0,1.0,-0.04750827141844653,-0.03005129695137735,0.6017454509818682,0.9917672838693683,-0.0830458865857037,-0.054078288776587005,-0.08109607934082619,-0.009725139531253174,-0.007911681299017759,0.002821604795614686,-0.03829733770160895,-0.02197992081734261,-0.041535088039363004,0.2522346411192665,0.7924595131669674,-1.355132701883901,0.45353136006399797,0.35874628793078805,-0.2747579864720324,-0.16282101285483394,0.38258033030745914,0.4055638000759619,0.30424022553004665,-0.8389845596787708,0.7030633871717041,-0.15906248256772892,0.06474091672907578,0.019557788219204397,0.06292854640372991,-0.11712581053636262,0.23622983524321128,-0.021298988941974017,-0.02386338258948295,0.09802647603667891,0.03795703958979324,0.012236299013528296,-0.01839989335165715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7333333333333334,0.0,1.0,1.0,1.0,-0.0476053598414787,-0.030098962800374343,0.6017688107940806,0.99173509204498,-0.0832022274488069,-0.0541700867264233,-0.0812680644130547,-0.010723215046157284,-0.008057916568914,0.0028752855123355707,-0.03830381769314557,-0.021784927444500352,-0.041189821935979296,0.25092740531566543,0.7929208753454677,-1.3548313317975709,0.454055863398047,0.3577618723628868,-0.2727886953310373,-0.16299439974101496,0.382361666202638,0.4064044576728583,0.3045579288347848,-0.8388835198051814,0.7028977253750635,-0.1545432237685107,0.04592906759695037,0.05279367898085141,0.06295524050690116,-0.11915035430300147,0.2364050601769807,-0.020302083890977873,-0.028647752411289362,0.10376753056130283,0.03829708499193285,0.012014267110984633,-0.021385154354960356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7416666666666667,0.0,1.0,1.0,1.0,-0.04771094148135372,-0.030146434452243704,0.601791788969175,0.9917029969269883,-0.08335860659734305,-0.05426094760935739,-0.08143867750197537,-0.011736341750261817,-0.008208179946673574,0.002930095632479485,-0.03831261170301221,-0.021587480158694453,-0.04083979544365233,0.24965892072312468,0.7932249976269166,-1.3542528072342201,0.4545806140724463,0.3567604486924047,-0.2708179021357494,-0.16315938091968357,0.382102867767271,0.40729325891865026,0.3048785102799122,-0.8387843218935878,0.7027069679324548,-0.14976591681703288,0.027006794930994893,0.08606782759463805,0.06298800615665123,-0.12120787950190559,0.23658993726027644,-0.019281538544525523,-0.033495862303540846,0.10958069604950049,0.03864783202277233,0.011794340261312986,-0.02442360873053051,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.75,0.0,1.0,1.0,1.0,-0.04782514653045686,-0.030193718407316262,0.6018143814559858,0.99167100084811,-0.08351503395032005,-0.05435085808761937,-0.0816079006223157,-0.012764739862611995,-0.008362492835294954,0.0029859925404439984,-0.03832378024673545,-0.02138730263579615,-0.0404850311838071,0.24843130670204822,0.7933709885943176,-1.353396868004327,0.45510566350065784,0.35574174103785505,-0.26884552971003267,-0.16331575871675705,0.3818034018309123,0.40823080260701666,0.30520205936849765,-0.8386869474674928,0.7024906652295546,-0.14473829821800732,0.007981141334090225,0.11936618263631349,0.06302703436015356,-0.12329858868933341,0.23678367288289426,-0.018237216306539183,-0.03840808106856941,0.11546531060451781,0.039009346886700325,0.011576751412114561,-0.02751672171591224,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7583333333333333,0.0,1.0,1.0,1.0,-0.04794810680423114,-0.03024082105052409,0.6018365836505133,0.9916391061759817,-0.08367151956903672,-0.05443980367052526,-0.08177571601906886,-0.013808584390338576,-0.008520866294772209,0.0030429282771956847,-0.038337380066714985,-0.02118412234843482,-0.04012556165234269,0.24724661575282456,0.7933580166491514,-1.3522633708569483,0.45563106464511555,0.35470547221424914,-0.2668715075877012,-0.16346333452479256,0.3814627330827948,0.4092176807620589,0.3055286660613572,-0.8385913760367192,0.7022483559038563,-0.13946866419090542,-0.011140578316080063,0.15267473604669846,0.06307250471884851,-0.1254225851812507,0.2369854451525899,-0.017169030782848704,-0.043384543015838606,0.12142039809053928,0.039381672269908075,0.011361751178511348,-0.030665840234105346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7666666666666666,0.0,1.0,1.0,1.0,-0.04807995533037988,-0.030287748633440355,0.6018583903855824,0.9916073153103185,-0.0838280736391654,-0.054527768734760944,-0.08194210620454481,-0.014868000205185347,-0.008683299844945829,0.0031008489146634663,-0.03835346374833892,-0.020977670509216576,-0.03976142819072164,0.24610682896553313,0.7931853122890496,-1.3508522890702153,0.45615687191263865,0.35365136461816754,-0.26489577229082284,-0.16360190922980453,0.3810803261139817,0.41025447590852565,0.3058584205729961,-0.838497584947851,0.7019795678923195,-0.13396584199692418,-0.03035077581400536,0.18597953469848605,0.06312458318413872,-0.127579859301431,0.23719439352544724,-0.01607694768273049,-0.04842512761680795,0.12744464255653343,0.03976482546704463,0.011149608351586071,-0.03387217844349033,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.775,0.0,1.0,1.0,1.0,-0.048220825896705094,-0.030334507254604175,0.6018797959193636,0.991575630680527,-0.08398470645154191,-0.054614736544136566,-0.08210705399099588,-0.015943057392843737,-0.008849780323852002,0.0031596939625050313,-0.038372079374883857,-0.02076768197394033,-0.0393926799174608,0.24501385171954249,0.7928521703855846,-1.3491637119453068,0.45668314103151786,0.35257914122589196,-0.2629182676956104,-0.16373128365283807,0.3806556476225147,0.4113417581380011,0.3061914131524746,-0.8384055492308594,0.7016838195964648,-0.1282391587357029,-0.049641590661333446,0.21926669194813453,0.0631834199131509,-0.12977027504307848,0.23740960819154888,-0.014960986457178693,-0.05352944080924127,0.13353636496112098,0.040158796645451966,0.010940610298448838,-0.037136804039619165,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.783333333333333,0.0,1.0,1.0,1.0,-0.04837085256005358,-0.030381102838265693,0.6019007939228536,0.9915440547437888,-0.08414142838182913,-0.054700689268624494,-0.08227054251870264,-0.017033766905676203,-0.009020280811099827,0.0032193958118527143,-0.038393270225767835,-0.020553895108650327,-0.03901937263331911,0.2439695096532714,0.7923579524446941,-1.347197844204413,0.45720992891119117,0.3514885267007829,-0.26093894548763036,-0.16385125900409084,0.380188168767161,0.412480081991211,0.3065277338504203,-0.8383152414428768,0.7013606211583259,-0.12229840781835033,-0.0690048931941889,0.2525223990739578,0.06324914724541442,-0.13199355723168327,0.2376301192910124,-0.013821221667790207,-0.058696798100892345,0.1396935024204815,0.040563547262584265,0.010735063237463649,-0.04046062537537143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7916666666666665,0.0,1.0,1.0,1.0,-0.048530169119093365,-0.03042754111170815,0.6019213774664283,0.9915125899836181,-0.08429824986923791,-0.05478560800251614,-0.08243255527946362,-0.018140076545877442,-0.009194759625170662,0.0032798792208371236,-0.03841707452233522,-0.02033605162534791,-0.03864156771341216,0.24297554492256998,0.7917020888323482,-1.3449550052940742,0.4577372934856081,0.3503792486053639,-0.25895776570742685,-0.16396163734730124,0.3796773676541665,0.41366998317834247,0.3068674722735177,-0.838226631510235,0.7010094758402086,-0.1161538133435075,-0.08843228978226758,0.2857329364993344,0.06332187782082,-0.1342492792684724,0.2378548860332974,-0.012657784081875345,-0.06392620960567474,0.14591359017806282,0.04097900865023374,0.010533292376584402,-0.04384437945860853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8,0.0,1.0,1.0,1.0,-0.04869890855386884,-0.030473827581325524,0.6019415390056011,0.9914812389088945,-0.08445518139450299,-0.05486947278155652,-0.08259307613548303,-0.019261867303033295,-0.009373159402478883,0.0033410608456685793,-0.03844352522429646,-0.02011389639130881,-0.03825933099886872,0.24203361276421295,0.790884080948323,-1.3424356285960908,0.45826529354153817,0.349251038712975,-0.2569746973870754,-0.1640622220721221,0.37912273194039975,0.4149119751608454,0.3072107173279242,-0.8381396865699338,0.7006298815006824,-0.10981599261979003,-0.10791513005171893,0.3188846846994231,0.0634017028555689,-0.13653685152807737,0.23808278579394382,-0.011470861492831608,-0.06921636712463597,0.15219374646777917,0.04140508077712379,0.010335641900851567,-0.04728862087488794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.808333333333333,0.0,1.0,1.0,1.0,-0.04887720243527872,-0.030519967507648797,0.6019612703661215,0.9914500040533608,-0.08461223345732047,-0.05495226259893894,-0.08275208933370257,-0.020398950066214335,-0.009555406265108916,0.0034028488207685113,-0.0384726498797244,-0.019887177217766682,-0.037872731700173135,0.2411452783789068,0.7899035033314862,-1.3396402605490838,0.4587939885332009,0.3481036344132293,-0.2549897192775278,-0.16415281837218176,0.37852376153542255,0.4162065456194721,0.3075575569531364,-0.8380543708118875,0.7002213321589604,-0.10329591709191732,-0.12744451605854135,0.35196413468985277,0.06348869059099038,-0.13885551047577604,0.23831260325881898,-0.010260699265863815,-0.0745656333624134,0.15853066041139563,0.04184163120001805,0.010142474795333811,-0.050793711669596675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8166666666666664,0.0,1.0,1.0,1.0,-0.0490651803077812,-0.030565965879530654,0.6019805627285696,0.991418887975574,-0.08476941655346663,-0.05503395542007222,-0.08290957951566963,-0.021551062726858097,-0.009741409083161581,0.0034651423913805574,-0.038504470530460785,-0.019655644633696553,-0.03748184132334928,0.24031201414601433,0.7887600056806806,-1.3365695596845932,0.45932343838472134,0.3469367802050454,-0.2530028206660951,-0.16423323372655316,0.3778799713843595,0.41755415283436864,0.3079080778479245,-0.8379706453233449,0.6997833196395224,-0.09660487194017464,-0.14701131331466222,0.38495789799708025,0.06358288492780084,-0.14120430855991128,0.23854301968353253,-0.009027600612382947,-0.07997203334791703,0.16492058305927482,0.04228849421099912,0.009954172492110391,-0.05435981221499686,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8249999999999997,0.0,1.0,1.0,1.0,-0.04926296904876034,-0.030611827387706743,0.6019994066126091,0.9913878932592876,-0.0849267411518187,-0.05511452819605681,-0.0830655317230775,-0.022717867684804778,-0.009931058836314552,0.003527831600784578,-0.03853900367414879,-0.01941905165087681,-0.037086732629371316,0.2395351971799039,0.7874533147762418,-1.3332242955824658,0.4598537032819976,0.3457502292705641,-0.25101400228280224,-0.16430327838238815,0.37719089431295727,0.41895522200379337,0.3082623651899864,-0.837888467937019,0.6993153352887105,-0.08975441463073441,-0.16660616354474023,0.41785271601193497,0.06368430425504057,-0.143582104926675,0.238772602331227,-0.007771926598046375,-0.08543324810351027,0.171359321650022,0.04274547018614294,0.0097711343298168,-0.05798687307421391,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8333333333333335,0.0,1.0,1.0,1.0,-0.049470692208078315,-0.03065755639796048,0.6020177918610631,0.991357022514238,-0.08508421767150576,-0.055193956875839056,-0.0832199313991517,-0.023898949765509186,-0.010124228078180496,0.0035907970341700086,-0.03857626028354286,-0.01917715352647257,-0.036687478636051235,0.2388161072355021,0.7859832362882683,-1.329605347751061,0.4603848434556387,0.3445437451229342,-0.24902327729390797,-0.1643627658365206,0.3764560839159677,0.4204101415285357,0.3086205023510269,-0.8378077930845146,0.6988168717549522,-0.08275633270014349,-0.1862194990289523,0.4506354686291081,0.06379294048110551,-0.1459875569927893,0.23899979414517547,-0.006494095891422247,-0.09094661058449138,0.17784223713072533,0.043212325139335706,0.00959377681462259,-0.06167462786134115,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.841666666666667,0.0,1.0,1.0,1.0,-0.04968846933139423,-0.03070315692412149,0.6020357076239902,0.9913262783773048,-0.08524185645941601,-0.05527221641703765,-0.0833727643860909,-0.02509381455245328,-0.010320770505759459,0.003653909620482033,-0.03861624588272474,-0.01892970752901197,-0.03628415167049562,0.23815592496823484,0.7843496564590926,-1.3257137044386473,0.4609169189566827,0.34331710332068427,-0.24703067238038265,-0.16441151331391185,0.3756751174698824,0.42191925928930546,0.3089825706089753,-0.8377285716567753,0.6982874248243548,-0.07562260105997087,-0.2058415583673101,0.48329318207844807,0.06390875827050113,-0.1484191129031165,0.239222903709842,-0.005194584262195878,-0.09650910388513845,0.1843642449428473,0.0436887904817862,0.009422532673368789,-0.06542258708702953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.85,0.0,1.0,1.0,1.0,-0.04991641527085036,-0.03074863260112863,0.602053142342934,0.9912956635140088,-0.08539966776828534,-0.055349280795465805,-0.08352401691879932,-0.026301887134503703,-0.010520520635122599,0.0037170304930138256,-0.0386589606794866,-0.018676472714003724,-0.03587682247904623,0.23755573055116924,0.7825525436488131,-1.3215504613830868,0.4614499894268137,0.34207009324121557,-0.24503622889874394,-0.16444934224089053,0.3748475988512154,0.4234828789442498,0.30934864885905666,-0.8376507508732918,0.6977264953035017,-0.0683653391066047,-0.22546240348251256,0.5158130358590007,0.0640316944877839,-0.15087500488810246,0.23944009554433932,-0.003873923839731175,-0.10211736168393659,0.19091981904461375,0.04417456298656419,0.009257849691803877,-0.06923003296889219,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8583333333333334,0.0,1.0,1.0,1.0,-0.05015463948670858,-0.030793986658385883,0.6020700837355268,0.9912651806203049,-0.0855576617355879,-0.05542512301340008,-0.08367367561517107,-0.0275225112640695,-0.010723293583250453,0.003780010908709863,-0.03870439975241232,-0.018417209714987857,-0.035465559400508315,0.23701650264979143,0.7805919497343841,-1.317116820507664,0.4619841138648124,0.34080251990588256,-0.24304000412131033,-0.1644760787112407,0.3739731614418168,0.42510125627338236,0.30971881332541806,-0.8375742741619119,0.6971335909415399,-0.060996767917663175,-0.24507193766269975,0.548182368687864,0.0641616578480908,-0.1533532435251539,0.23964938076525777,-0.0025327021440690878,-0.10776767087682826,0.19750299910388014,0.04466930495453436,0.009100189329118713,-0.07309601517094588,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8666666666666667,0.0,1.0,1.0,1.0,-0.0504032453434717,-0.03083922189363373,0.6020865187806188,0.9912348324246298,-0.08571584836344263,-0.05549971510667244,-0.08382172746320672,-0.02875494891767405,-0.01092888495471745,0.0038426922257316304,-0.03875255329038408,-0.018151680554949447,-0.035050427606911266,0.23653911775254152,0.7784680113544348,-1.3124140885716225,0.46251935039094855,0.33951420584912967,-0.2410420725526563,-0.16449155394329168,0.37305147100326824,0.42677459559598113,0.31009313727496557,-0.8374990810511398,0.696508228383986,-0.053529167810162925,-0.2646599244331038,0.5803886833828154,0.0642985287696407,-0.1558516128995291,0.23984860815110975,-0.0011715609028073448,-0.11345597632600124,0.20410740076454936,0.045172644576506604,0.008950025104570436,-0.07701934743161498,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.875,0.0,1.0,1.0,1.0,-0.05066232940393268,-0.0308843406475491,0.6021024337041074,0.9912046216901573,-0.08587423749973866,-0.055573028150681936,-0.08396815980525309,-0.029998380247078106,-0.01113707083097074,0.0039049059382702395,-0.038803406882065024,-0.017879648483499398,-0.03463148841517045,0.23612434985295538,0.7761809509938323,-1.307443675784617,0.4630557560109731,0.33820499302422374,-0.23904252731879183,-0.1644956047262875,0.3720822285030501,0.42850304628612484,0.3104716907350265,-0.8374251070768357,0.695849935151013,-0.04597483652609036,-0.2842160070339217,0.6124196506015478,0.06444215942300491,-0.15836766664792612,0.24003545562951423,0.00020880533098899257,-0.11917788762863757,0.21072622885444314,0.045684176484781513,0.008807840752791396,-0.08099860502885248,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8833333333333333,0.0,1.0,1.0,1.0,-0.050931980724485966,-0.0309293447792777,0.6021178139656316,0.9911745512172115,-0.08603283882067539,-0.055645032265451144,-0.08411296031966906,-0.03125190390553927,-0.011347607858782211,0.003966473766815713,-0.038856941852202606,-0.017600877843938816,-0.03420879867176273,0.23577287047710668,0.7737310779038694,-1.30220709439493,0.46359338638133196,0.3368747447383309,-0.23704148162549774,-0.16448807385444186,0.3710651728761243,0.43028669941022185,0.3108545402163786,-0.8373522837052599,0.6951582516335051,-0.038346048298988356,-0.30372972827627187,0.6442631113646247,0.06459237396868378,-0.16089872485966494,0.24020742220254077,0.0016076507442269738,-0.12492868779035549,0.21735229337190076,0.046203462484618596,0.00867412814324009,-0.0850321230204143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8916666666666666,0.0,1.0,1.0,1.0,-0.05121228015488093,-0.030974235643086736,0.602132644246289,0.9911446238457924,-0.08619166181489565,-0.0557156966198619,-0.08425611700022108,-0.03251453773033525,-0.0115602334334684,0.004027207801859267,-0.0389131356411255,-0.017315133973900925,-0.03378241021119309,0.23548524904797224,0.7711187888558945,-1.2967059572618733,0.4641322955771178,0.335523347609896,-0.23503907028208282,-0.16446881054721704,0.3700000837065442,0.43212558450898986,0.3112417484431035,-0.8372805382744484,0.6944327331006728,-0.03065501404136972,-0.3231905505428756,0.675907078295408,0.06474896897290083,-0.16344187180138747,0.2403618203183866,0.0030241799958602433,-0.1307033436709637,0.22397802806179645,0.046730032455422066,0.00854938496477331,-0.08911799519513153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9,0.0,1.0,1.0,1.0,-0.05150329964542872,-0.0310190140663119,0.602146908437525,0.99111484245816,-0.08635071576937958,-0.05578498943522923,-0.08439761813351351,-0.033785219760023986,-0.011774665971741868,0.004086910698333035,-0.038971962223700314,-0.017022183142861972,-0.033352369388377545,0.2352619535764172,0.7683445687281548,-1.2909419764233399,0.46467253586421364,0.3341507135416411,-0.23303545128685796,-0.16443767085451086,0.36888678381494155,0.4340196665445851,0.31163337409063563,-0.837209793955847,0.6936729517135862,-0.022913842876145507,-0.34258787569879656,0.7073397355150357,0.06491171398999018,-0.16599395442249643,0.24049576868893197,0.004457550097977658,-0.13649651805232144,0.23059551136434542,0.04726338540960384,0.008434112175585984,-0.09325407366128635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.908333333333333,0.0,1.0,1.0,1.0,-0.051805101564472676,-0.031063680328755047,0.6021605896313316,0.9910852099814336,-0.08651000975724919,-0.055852877988377896,-0.08453745227475351,-0.035062809562076185,-0.011990605268128094,0.004145375917684017,-0.039033392563482025,-0.016721792528630118,-0.03291871668378306,0.23510335166670315,0.7654089909275812,-1.284916961669956,0.465214157476951,0.3327567817028544,-0.23103080747060062,-0.16439451804558408,0.3677251417390055,0.43596884303172895,0.31202947153326355,-0.8371399697381886,0.6928784985396513,-0.015134505217397343,-0.36191106467870604,0.7385494371352941,0.0650803522982546,-0.16855158159193917,0.24060618554778312,0.005906872428045329,-0.1423025831656377,0.23719648949954153,0.04780299069578109,0.008328811220377208,-0.09743796899539969,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9166666666666665,0.0,1.0,1.0,1.0,-0.05211773802871434,-0.03110823414366991,0.6021736701118784,0.9910557293901511,-0.08666955262761762,-0.05591932861440077,-0.08467560822214257,-0.03634608984453905,-0.012207732928308127,0.004202388014087583,-0.03909739509779449,-0.016413730234805753,-0.03248148637966698,0.2350097118227939,0.7623127176501764,-1.2786328191377516,0.4657572084025179,0.3313415205151088,-0.2290253481943949,-0.1643392229807101,0.36651507409551426,0.4379729413695775,0.312430090602232,-0.8370709804355074,0.6920489855636629,-0.007328797585920421,-0.3811494565219964,0.7695247042972664,0.0652546017753719,-0.17111112400922224,0.2406897823348092,0.007371214854128283,-0.14811563550188755,0.24377240142872014,0.04834828933253932,0.008233981018632708,-0.10166705086934957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.925,0.0,1.0,1.0,1.0,-0.05244125024875078,-0.031152674640454448,0.6021861313486896,0.9910264037087461,-0.08682935299759974,-0.05598430670928155,-0.08481207499017658,-0.03763376832335968,-0.01242571287219118,0.004257722961209004,-0.03916393624896642,-0.016097765349715284,-0.03204070630475674,0.23498120504027115,0.7590564999855479,-1.2720915499316683,0.4663017341732072,0.329904929636034,-0.2270193110983538,-0.16427166446468194,0.36525654781397404,0.4400317163888743,0.31283527635547254,-0.8370027367212114,0.6911840476918288,0.0004916906751384342,-0.4002923866324015,0.80025422070793,0.06543415589738588,-0.17366871472955792,0.24074305779123228,0.00884960395418355,-0.15392951172196523,0.25031440542115035,0.04889869545687375,0.008150114729759128,-0.10593844907325956,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.933333333333333,0.0,1.0,1.0,1.0,-0.05277566789192587,-0.031197000349147328,0.6021979539914616,0.9909972360138958,-0.08698941924658056,-0.056047776732567264,-0.08494684178212197,-0.038924479815525874,-0.012644191898988352,0.004311148515218413,-0.03923298095722427,-0.01577366804724287,-0.031596397644317396,0.23501790666737954,0.7556411778729697,-1.2652952487926195,0.4668477776674743,0.3284470419362828,-0.22501296389787437,-0.1641917295814737,0.3639495822334815,0.44214484812659666,0.31324506885984654,-0.8369351451900114,0.6902833447457752,0.008315608641691896,-0.4193292040483554,0.8307268266308565,0.06561868484619371,-0.17622025023713905,0.2407622924422409,0.010341027310784567,-0.15973780547369532,0.2568134069405714,0.04945359787211112,0.008077696301325155,-0.11024905484941838,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9416666666666664,0.0,1.0,1.0,1.0,-0.0531210084643351,-0.031241209186806337,0.6022091178666003,0.9909682294366975,-0.08714975951282228,-0.056109702210277966,-0.08507989796192125,-0.04021704760991737,-0.012862834485956107,0.004362344770154965,-0.03930453324651814,-0.015441304954439912,-0.031148530023537013,0.23511979851763268,0.7520676799180753,-1.258246102821154,0.46739537892064376,0.32696792546541503,-0.22300660622431645,-0.1640993140095022,0.3625942510560791,0.4443119398378838,0.3136595029866744,-0.8368681084495226,0.6893465634443385,0.016131898997224225,-0.438249968325477,0.8609323164524252,0.065807894053872,-0.17876356994641185,0.24074725801606522,0.01184455666945139,-0.16553385135208987,0.2632593714653364,0.05001247432196321,0.008017581652799421,-0.11459667394102313,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9499999999999997,0.0,1.0,1.0,1.0,-0.053477280915281165,-0.031285298555237755,0.6022196002222036,0.9909393870942541,-0.08731038210898895,-0.05617004646197216,-0.08521123260290502,-0.041509592818432174,-0.013081233029574542,0.004411273074463552,-0.039378522332454854,-0.015100315452952075,-0.030697200480612308,0.2352867716506666,0.7483370117342117,-1.2509463768517457,0.4679445759017055,0.3254676491038426,-0.22100050959760661,-0.16399432030364952,0.3611906847109467,0.4465325043176856,0.31407861009854593,-0.8368015188291315,0.6883734001800915,0.023929827693058847,-0.45704327434003433,0.8908587372224464,0.06600134940359492,-0.1812906847595963,0.2406877707337518,0.013359021347549849,-0.1713112642610437,0.26964459707395805,0.050574541754536684,0.007969688776681139,-0.1189761345690421,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9583333333333335,0.0,1.0,1.0,1.0,-0.05384447080916944,-0.0313292651130284,0.6022293833663876,0.9909107123117923,-0.08747129427426588,-0.056228770148361466,-0.08534083612974513,-0.04280038222635127,-0.013298925953240785,0.004457599184156819,-0.039454845983725895,-0.014750386948114305,-0.030242403884270498,0.23551862897918366,0.7444502920124081,-1.24339845720078,0.46849540141070367,0.3239464140527551,-0.21899514337875392,-0.1638766636537097,0.35973906331839506,0.4488060164557831,0.31450241201591667,-0.8367352803032446,0.6873636278681878,0.031698779954779654,-0.4756979436734765,0.9204946078184673,0.06619859360210256,-0.18379549725388244,0.24057735435998095,0.014883102319209751,-0.17706262494834424,0.27595904929225146,0.05113899414108114,0.007934099081496893,-0.12338270527408435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.966666666666667,0.0,1.0,1.0,1.0,-0.05422255689541315,-0.03137310467662873,0.6022384417783925,0.9908822084181411,-0.08763250323994698,-0.056285834064487415,-0.08546869777850369,-0.044088160971689785,-0.013515526385378557,0.004500873037035173,-0.03953351406407774,-0.01439144527021086,-0.02978404716061668,0.23581508464991294,0.7404087126729871,-1.2356048000547712,0.4690478857950739,0.3224043908162779,-0.21699088702494027,-0.16374626859832936,0.3582396409618076,0.4511318218058898,0.31493092666756395,-0.8366692838444398,0.6863170217588568,0.03942858407654071,-0.4942044059998385,0.9498305059005796,0.06639927814117264,-0.1862766045089037,0.2404177953215808,0.01641576734965844,-0.18278022546580508,0.2821910009714712,0.05170527296907701,0.00791184275831247,-0.1278140483369583,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.975,0.0,1.0,1.0,1.0,-0.054611502378849444,-0.031416812647930434,0.6022467523227586,0.990853878761923,-0.08779401629337379,-0.05634119816989845,-0.08559480728590634,-0.04537114414114586,-0.013730635809093911,0.0045409935428746785,-0.03961452397502973,-0.01402326828822792,-0.029322169648853248,0.236175772047126,0.7362135519124108,-1.2275679487691036,0.4696020560463899,0.3208418039776067,-0.21498818012339424,-0.1636030675312154,0.3566927262272983,0.45350919980530763,0.3153641665654013,-0.8366034162572727,0.6852333937292385,0.04710959957946348,-0.5125522915642056,0.9788558888171517,0.0666029877745411,-0.18872794316450947,0.24020271491783873,0.017955939422912848,-0.18845713542663844,0.28833160421206094,0.052272690192364246,0.007903292809616769,-0.1322656924395016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9833333333333334,0.0,1.0,1.0,1.0,-0.0550112555254514,-0.031460383772063394,0.6022542908273323,0.9908257267617894,-0.08795584045114224,-0.0563948214462644,-0.08571915440290503,-0.04664758233859973,-0.013943808195560133,0.004577670886660076,-0.03969783502796057,-0.01364562411900157,-0.02885675000438099,0.236600244642904,0.7318661744802504,-1.219290535241152,0.47015793559131625,0.31925892509686943,-0.2129875084429763,-0.1634470029412808,0.35509868870469696,0.45593734854275747,0.31580213817077,-0.8365375622976129,0.6841125935515318,0.05473242763023134,-0.5307312764443939,1.007560216317911,0.06680928227349114,-0.19114385572446158,0.2399266266486655,0.019502402285774822,-0.1940859328933564,0.29437098856138544,0.05284051178242155,0.00790871700091289,-0.13673303118031388,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9916666666666667,0.0,1.0,1.0,1.0,-0.055421749190511245,-0.0315038121258736,0.602261032241485,0.9907977559031335,-0.08811798248981256,-0.05644666194075336,-0.0858417288676454,-0.04515238703293395,-0.014137393276978293,0.006104245078441208,-0.03680259574246253,-0.01881981033851243,-0.03239790164914991,0.23708797917429653,0.7273680306383375,-1.2107752784971384,0.4707155440842814,0.3176560730488657,-0.21098940301258315,-0.16327802749311915,0.3534579606790757,0.4584153829479974,0.316244841761775,-0.8364716043072575,0.6829545098762333,0.07509987446225719,-0.3318798219683705,0.5816610550196,0.06379754474141852,-0.20608385197812495,0.28321499084715374,0.010145256218802023,-0.17963537137828722,0.2821301060228709,0.048923711114552404,0.01172521373765445,-0.13010992222733275,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0,0.0,1.0,1.0,1.0,-0.0558001741293845,-0.031549601115974504,0.6022971000887485,0.9907666696914539,-0.08825793400695968,-0.056547680403607144,-0.08599013475376373,0.1401535705225972,0.025203964475844724,-0.04661880657216133,0.12387652021754829,-0.1793428225773769,0.23662988734434587,0.23785190921727495,0.7263348441141109,-1.2095961843241587,0.4712212280036732,0.31582419423056735,-0.20826725859552372,-0.1632779153376341,0.3521047658483922,0.460639516976472,0.31661753335601256,-0.836342142068652,0.6819440948477429,-0.15507511683424902,-2.400170444688039,1.713726155230324,-0.29255148765887085,0.5025747141046943,-0.22322035949470853,0.19020645834642136,0.14275815752886167,0.35947111431199885,-0.03985466967891149,-0.21265291645744977,1.0790201475740635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.008333333333333,0.0,1.0,1.0,1.0,-0.052984302691268456,-0.0316146439293787,0.6017289421722183,0.990970064478171,-0.0873353170987279,-0.057841709925247134,-0.08369713429274227,0.37047680034022,0.07515851296402046,-0.11773218484415154,0.32345454855170075,-0.4100558821171616,0.6304125867312037,0.2345033938937257,0.6873651898935369,-1.1822131759099663,0.46583968595663355,0.3260323182839439,-0.21470974233749496,-0.16010791985401213,0.35583726330455673,0.4644065681865307,0.31558059726712645,-0.8400158195815484,0.7009381790024677,-0.6095825659790932,-4.6064105009935234,3.401555679725492,-0.7718449184295761,1.4107600358216266,-0.8514249125441931,0.512030129357739,0.37701495025676435,0.8038240559178178,-0.12140072705879579,-0.5039593415958343,2.6641107459608415,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.016666666666667,0.0,1.0,0.0,1.0,-0.04933668037031474,-0.031654139277092964,0.6009713841682112,0.9912399137624403,-0.08617641637430923,-0.059700950480248156,-0.08032966536273095,0.4530725286311131,0.0936988285516417,-0.14681149605626825,0.3842386564145225,-0.5182892552501627,0.8090828188421666,0.22769219978429006,0.6495613357642188,-1.1529035896620672,0.45835714602984695,0.3393368614942611,-0.2224576738045936,-0.15474407984833846,0.3583883483526716,0.4740365845751023,0.31459418790503263,-0.8447414644285826,0.7263459406137569,-0.9311849063900435,-4.454088800841416,3.592142534392053,-0.9540335982874304,1.7145523875408697,-0.9790597817674984,0.7124585902089536,0.21538601678277147,1.4184424501916915,-0.1130209802472737,-0.57668224532609,3.237032763134975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.025,0.0,1.0,0.0,1.0,-0.04506388825445818,-0.031662688939550876,0.6000823279169277,0.9915272838366413,-0.08491078663942077,-0.06179921256679214,-0.07645038290458989,0.5154048625748883,0.10724851241846065,-0.16924165916000844,0.41980581181604437,-0.5664624973816493,0.8982747196496038,0.21898364545389165,0.61313037654618,-1.1223441336700988,0.4499391259851764,0.3546081914096251,-0.23102740536695326,-0.14823361001719623,0.35942703025093625,0.48804727568972556,0.3136969142630052,-0.8496271903369832,0.7548887250547173,-1.1247943478653795,-4.307224607918996,3.7427918916436065,-1.044177586772872,1.9166690387947571,-1.0638593636843814,0.8173189924611307,0.02355119822573304,1.901962192217549,-0.10780552248248476,-0.5747484990340501,3.5252591434295932,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.033333333333333,0.0,1.0,0.0,1.0,-0.04031381645200485,-0.031627092744796186,0.5990930680129102,0.9918160003056405,-0.08353117922040207,-0.06401312540164666,-0.07229027190673229,0.5629409077894239,0.11782019790739376,-0.18755505582120915,0.45275588893635227,-0.5887715898237803,0.9497991940439925,0.20894562731986707,0.5777742589655689,-1.0905237248013404,0.4409541862502991,0.37128134547417374,-0.2401886631993333,-0.14112209664065295,0.35878086832310047,0.5057359544453948,0.3127974291969912,-0.8543206060791501,0.7851002596709168,-1.2680045458114926,-4.19363806893426,3.8947555694713865,-1.1023437708835981,2.062107496177399,-1.1240068796068037,0.8770027133756292,-0.18618259162590856,2.3195507710391574,-0.10993070815095596,-0.5397691900019463,3.674069209748121,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.041666666666667,0.0,1.0,0.0,1.0,-0.03519473620235858,-0.03153889231546915,0.598023120446128,0.9920995093145977,-0.08203016035878526,-0.0662767524380083,-0.0679485724337352,0.5995969329726372,0.1260121342713473,-0.2029674812442399,0.48475698145203994,-0.5961925744511645,0.985046328070378,0.19785023635703344,0.543236408730609,-1.0574315408455757,0.4315667298037831,0.3889766496792484,-0.2497608533604,-0.1336168981276024,0.3563239870571711,0.5267064552070448,0.3118647357938226,-0.8586233435036823,0.8161232118838526,-1.3852868561180265,-4.108211401171136,4.047027580598446,-1.1451432338015999,2.1683367252659647,-1.1658621871532637,0.9208891405043584,-0.4075652063315627,2.692871429873418,-0.11375728450572775,-0.4848217605403682,3.7362477293873053,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.05,0.0,1.0,0.0,1.0,-0.029787464569521003,-0.03139428189815178,0.5968881799446141,0.9923750860798024,-0.08040532453597847,-0.06854286916439727,-0.06347083898464963,0.6282294641444128,0.13214295777822327,-0.2159900408374838,0.5157785618143591,-0.5925187993992905,1.0128651745727943,0.1858575130512333,0.50930406894605,-1.0230732651246996,0.4218684656869391,0.40742029089527315,-0.2596196996518877,-0.12577394429891364,0.3519881148842411,0.5506171449432851,0.3109014744552291,-0.8624009687548229,0.8473710551607052,-1.4863510818173342,-4.045979698247009,4.197695131720516,-1.1788072721479326,2.2460844997348985,-1.1960729740595033,0.9615977341016116,-0.6341027747783912,3.024117195705074,-0.11656303350448649,-0.4158363179990743,3.736861418883992,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.058333333333334,0.0,1.0,0.0,1.0,-0.024152291833269442,-0.031192127909871283,0.5957026346768316,0.9926417758781422,-0.07865709945312817,-0.07077047424843799,-0.058880433611089196,0.6510414145649944,0.13650276463278704,-0.22688197263750068,0.545716718503229,-0.5790783253732705,1.0369486419332974,0.17307771832674454,0.4758034137598255,-0.9874699553169004,0.41191994193465087,0.4264113913414967,-0.2696954029280584,-0.11759026922590889,0.34575560747753126,0.5771084084687961,0.30992201856874785,-0.8655539488036669,0.8784042355319192,-1.5757140649107755,-4.002482374971229,4.344833735431122,-1.2061375680346043,2.3029937514309275,-1.2206218899973176,1.0037026333590573,-0.8605239823757871,3.3106730288589326,-0.1175425368994365,-0.33626625295421375,3.690357771173327,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.066666666666666,0.0,1.0,0.0,1.0,-0.018333178729740465,-0.030932742587905886,0.5944802012939387,0.992899577777381,-0.07678737322369379,-0.07292064844197911,-0.05419139040803846,0.6698107185206488,0.13935232697502364,-0.235824917926464,0.5745094293540438,-0.5563485908275698,1.0588548315504582,0.15959561196938704,0.44259602936319614,-0.950659369534181,0.40176617288636235,0.4458035200857886,-0.27996339781850965,-0.10904556707626269,0.3376460485113113,0.6057950287576006,0.3089424321735718,-0.8680054063040598,0.908877018013594,-1.6558087588061483,-3.973658310314716,4.486292718341199,-1.2285908045060923,2.3448262715478507,-1.2442448387628902,1.048189657623788,-1.0831472688249821,3.550136575120688,-0.1167138618835728,-0.24840995490785334,3.6063277572966324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.075,0.0,1.0,0.0,1.0,-0.012360688337293922,-0.030617333015916806,0.5932340220571143,0.9931490909874986,-0.07479890743861199,-0.07495524624817584,-0.04941373875152751,0.68597498024172,0.14089818393614614,-0.24297146451457813,0.6021160614777483,-0.5245324236478001,1.0792501483158803,0.1454809056799754,0.4095757752545802,-0.9126984100112138,0.391443428526216,0.46549182920062754,-0.2904328169074399,-0.10012044159884576,0.3277031529971149,0.6362773513874742,0.30797678753735497,-0.8696941147187978,0.9385096981535297,-1.7281480819112627,-3.9558896568571247,4.619683243026946,-1.2470146157506223,2.3758995011917063,-1.270271735565236,1.0944804573897569,-1.2998105969222085,3.741710351332357,-0.11436715689434829,-0.15386644469817856,3.4915781264747614,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.083333333333333,0.0,1.0,0.0,1.0,-0.006254769968280228,-0.030247778002707,0.5919766804714178,0.9933913362517071,-0.07269512010492406,-0.07683659226103812,-0.04455570293074552,0.7006670390284,0.14128133214591118,-0.24845107477911726,0.6284930676403155,-0.48376079845448766,1.0984220557519275,0.13079314393753266,0.37666453508224407,-0.8736646488170652,0.3809825959571853,0.4854018451056504,-0.3011345934112636,-0.09080422611976674,0.31598253856260783,0.6681568679464732,0.30703631289199934,-0.8705698470490294,0.9670699867881734,-1.7937895764367684,-3.946049782059117,4.742455026666564,-1.2619266186806566,2.399309351672271,-1.300711992389083,1.141326411537615,-1.5096133622492214,3.8862598495887113,-0.11082379401800901,-0.053755527717676,3.3509841101249216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.091666666666667,0.0,1.0,0.0,1.0,-2.710210020171853e-05,-0.02982658419618829,0.5907202173067102,0.9936276373133791,-0.07048007992260893,-0.07852746505733417,-0.03962466320121481,0.7147632898332185,0.14058001141472615,-0.2523673585132935,0.6535796031603145,-0.434159694959123,1.1164845816645144,0.1155844127393626,0.3438082788869283,-0.8336574929001044,0.3704113182148717,0.5054803183951654,-0.3121113501139246,-0.08109833473988551,0.3025429302929612,0.7010483488806194,0.3061297243037215,-0.870590040180759,0.9943594333222784,-1.8535300279184483,-3.941439096909225,4.851934831857343,-1.2736281335121502,2.4171468421642053,-1.3364575853262228,1.1871828479080395,-1.7125044117151778,3.985823819191905,-0.1063510648966115,0.051148249943369084,3.187982030102199,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1,0.0,1.0,0.0,1.0,0.006316944449689439,-0.02935690046487186,0.5894762035477042,0.9938595219438332,-0.06815854729129266,-0.07999119207167066,-0.034627622855608775,0.7288762924800086,0.13881750039374816,-0.25478262203219937,0.6772997975997759,-0.3758766408159593,1.1334747691076228,0.09990097680555853,0.3109738834670903,-0.7927990682861095,0.3597554603986495,0.5256876258083871,-0.32340888650003397,-0.07101784532129941,0.28744079836735487,0.734587264933005,0.3052637951437225,-0.8697173762166399,1.02020302062321,-1.9080182321117118,-3.9398238349685135,4.94544503603825,-1.2822798831026594,2.430595284657253,-1.3774904286284761,1.23039521262683,-1.9090949391738654,4.043287982399535,-0.1011496152551905,0.16026626194459492,3.00481706559679,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.108333333333333,0.0,1.0,0.0,1.0,0.012775848838531194,-0.02884250661703874,0.5882558675205044,0.9940886306604644,-0.06573600965861173,-0.08119178711053897,-0.029571356621219725,0.7433853598515237,0.13597445479330755,-0.25571058247844825,0.699561812914586,-0.30908478767675523,1.1493865633935718,0.08378410887083407,0.2781445483041197,-0.7512334089661336,0.3490399868298274,0.5459902398061196,-0.3350695239243992,-0.060591747862771675,0.2707246813067301,0.7684364819206116,0.30444389738280164,-0.8679189358150158,1.0444397177488915,-1.9578044270661275,-3.9393727959541742,5.020354361044002,-1.2879386284154504,2.4400939838225355,-1.4231163946120218,1.269279912000517,-2.100380710909823,4.061951626608367,-0.09536817987507051,0.27311300541150496,2.8027891345464395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.116666666666666,0.0,1.0,0.0,1.0,0.01935050575250232,-0.028287853101627177,0.5870702473625928,0.9943166184978244,-0.06321874461119119,-0.08209405422441121,-0.0244625994237465,0.758488033906989,0.13200382045439635,-0.25511464322231786,0.7202619438301685,-0.23398286175687874,1.16417860391952,0.06727090302112307,0.24531767020118742,-0.7091264956020428,0.3382898165917253,0.566355858872096,-0.347127493076901,-0.0498631801212908,0.2524344531855245,0.8022864587098111,0.303674325479138,-0.8651654927931148,1.0669161728656507,-2.00337048133587,-3.9385178292920955,5.074059816957308,-1.2905865772326175,2.4455260410874735,-1.4721752723446457,1.3021539910625137,-2.287440140731156,4.045101054117968,-0.08913794249897022,0.38923235706655124,2.5824959501916034,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.125,0.0,1.0,0.0,1.0,0.0260426509934175,-0.02769804057239991,0.585930383318721,0.9945450570545445,-0.06061381931542394,-0.08266371899712273,-0.0193081319279947,0.7742073172153707,0.1268447259192832,-0.25290082214001564,0.739295090262665,-0.15079858174527896,1.1777863348642745,0.050394600848569567,0.2125025844825848,-0.6666657453501784,0.3275302105426171,0.5867490071575775,-0.35960577846347663,-0.03888918134506311,0.23260067896121084,0.8358548328225778,0.3029582650078188,-0.8614317298639066,1.0874813169187516,-2.045167109777133,-3.9359318567157344,5.104037103055039,-1.2901710334375904,2.4463141327733773,-1.5232145937746921,1.3273824489957877,-2.471353727327783,3.995868549564636,-0.08261067048487725,0.5081177832455275,2.34396730771806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.133333333333333,0.0,1.0,0.0,1.0,0.03285356205623613,-0.02707878679375612,0.58484753348091,0.9947753323839919,-0.05792907013849947,-0.0828675540598402,-0.01411486442979364,0.7904169682669765,0.12043539261059412,-0.2489166937735295,0.7565611574644933,-0.05978897133407346,1.1901237657213934,0.03318478452483752,0.17971880592259185,-0.6240592105511255,0.3167869660344321,0.6071277610849857,-0.37251440297314586,-0.027740139304694336,0.2112452243967281,0.8688842678692217,0.3022974809710567,-0.856696863072356,1.1059822946609517,-2.0836323266599064,-3.9304861905681054,5.107885980598111,-1.286630783915249,2.4415385676777257,-1.5746477060823982,1.343417819524134,-2.653091831130862,3.917077608539956,-0.07599337511323911,0.6291677702141718,2.0868039716993314,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.141666666666667,0.0,1.0,0.0,1.0,0.03978292434262657,-0.0264363661021443,0.583833412957223,0.9950085403340457,-0.05517304530509866,-0.08267351010354722,-0.008889907856497917,0.8068564781495392,0.11272547146054704,-0.2429510194488797,0.7719733959858671,0.038758495322901,1.2010873701840667,0.015667395404237797,0.1469944813064497,-0.5815343123402099,0.3060863641440296,0.6274413166188729,-0.38584990689818327,-0.016498884352994212,0.18838248177569647,0.901139459631577,0.3016917087559315,-0.8509456003603371,1.1222613831137405,-2.119211983205476,-3.9212491194800094,5.0834100945409055,-1.2799253258302878,2.4300295143164563,-1.6248926471648795,1.3488468986463282,-2.8334648283876485,3.811172469892534,-0.06958109622692277,0.7516510095335049,1.8102813997952394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.15,0.0,1.0,0.0,1.0,0.04682780115278316,-0.025777521414551138,0.5829004511617978,0.9952453804807517,-0.05235491421584522,-0.08205084671659733,-0.003640623943090976,0.823139853656496,0.1036874389905088,-0.2347353523385317,0.7854658308554816,0.1445268130421152,1.210562410325924,-0.002135415195253745,0.11436465393125836,-0.5393357089754437,0.295454877270594,0.64762825299026,-0.3995959470925605,-0.005259357660588866,0.1640208105902673,0.9324038090340973,0.3011377960339413,-0.8441693462467976,1.1361536513242056,-2.1523802435791004,-3.9075312544235667,5.028747189549945,-1.2700628315601648,2.4104467529293716,-1.6725073699958526,1.3424442978830415,-3.013111981878931,3.680193164790717,-0.06378266360782314,0.8746828520635841,1.5134277111309125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.158333333333333,0.0,1.0,0.0,1.0,0.05398167050940929,-0.02510935214081793,0.5820620592865858,0.9954860501297168,-0.04948434959948731,-0.08097024985618874,0.0016253554962917032,0.8387613609698615,0.09332701896160613,-0.2239487178254413,0.796999139966727,0.2571745080607139,1.218432110116432,-0.02020560865541388,0.08186896039939026,-0.49772185918104417,0.28491865028469354,0.6676154291676958,-0.4137250297314475,0.005875187278389812,0.13816394874438095,0.962476012378089,0.30062866436246777,-0.836367552825944,1.1474851782992557,-2.1836613220032572,-3.8889725648093987,4.942548973498488,-1.2571257889430532,2.381356760496316,-1.7163307317823917,1.3232283723202278,-3.192510705356486,3.5257678229110168,-0.05913667864186789,0.9972158568660516,1.1950822250376536,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.166666666666667,0.0,1.0,0.0,1.0,0.06123352350781045,-0.024439184088385413,0.5813328945694768,0.9957301400878595,-0.04657139201054863,-0.07940391358041925,0.006900150384730592,0.8531143486807266,0.08155707401078069,-0.20852468882454525,0.8068076423098061,0.3841555847832847,1.2251802307131,-0.0385297705619747,0.049548444517768374,-0.4569598927504689,0.2745027807882098,0.6873175323318652,-0.4282014592889337,0.016794448544748264,0.11081229883432586,0.9911666060826142,0.3001521847232435,-0.8275490819656968,1.1560716884081665,-2.2145813217182426,-3.8693884497184308,4.8143788652625386,-1.2415908058270875,2.339718629562413,-1.7662918464962651,1.2911934904095255,-3.3775652044649176,3.332864432286071,-0.058595260392684256,1.122568278410958,0.8321809283114012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.175,0.0,1.0,0.0,1.0,0.06856276761661453,-0.023774070353704057,0.5807572326683863,0.9959815917285828,-0.04362546293641111,-0.07726050811807314,0.012177922939888994,0.8651384082959611,0.06834255525591106,-0.18680793417120095,0.8148726559329829,0.5306760979965199,1.231387513586838,-0.05711529735071792,0.01737915290408308,-0.4174822114266685,0.2642254701875754,0.7066107396604027,-0.4431632271730519,0.027395078785215236,0.08187119533663233,1.0180237529161902,0.29965207668925636,-0.8176580815190947,1.161354860437779,-2.2469885768063054,-3.8523631783229013,4.6365896502263615,-1.2239165228590088,2.2830505568743553,-1.8308031706405237,1.24613222315923,-3.5734972166029992,3.0921616027629972,-0.06443150348167892,1.251365916383409,0.40791126690794766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.183333333333334,0.0,1.0,0.0,1.0,0.07593859945619504,-0.023122543227658377,0.5803710837566135,0.9962412720807723,-0.040658124731691246,-0.07446881021993247,0.01745396806011005,0.8735328003699377,0.05401249484205206,-0.1611308554405157,0.8206771116070266,0.6836770799967399,1.236233387590511,-0.07597958017541312,-0.014657608454279986,-0.37968339858002953,0.25410417207389296,0.7253683749464378,-0.4587148454662758,0.03756331893073543,0.051254011890942544,1.0427026327953308,0.2990783263318822,-0.8066929833593066,1.162870209523299,-2.2807664389907574,-3.8340345915030563,4.426553002857129,-1.2039870669662252,2.212624851760343,-1.8941287103064575,1.186562067297349,-3.772261070817379,2.831668631576667,-0.07366665276352102,1.3734938623510828,-0.04391650647849854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.191666666666666,0.0,1.0,0.0,1.0,0.08332772877459892,-0.022493488978205533,0.5801746675708365,0.9965020174071029,-0.03768211436379142,-0.0710462188509009,0.02272052702141703,0.8776585174968845,0.03904639150571522,-0.13392860668187717,0.8240645846079717,0.829765236835021,1.2384374261274473,-0.09512807133389721,-0.046521423620967846,-0.3437063280457164,0.24415901907147167,0.743487820523075,-0.47473203901149286,0.04717111324017105,0.01900017748967602,1.0652182301091346,0.2984242991431977,-0.7947665171465766,1.1606229186631374,-2.314982561079812,-3.8109036632751483,4.206170456038017,-1.1819178821874965,2.129870838217476,-1.9386046014159786,1.1118884435201222,-3.962808014184198,2.5762012136595835,-0.08361064368267335,1.4813769404086763,-0.48889978532018485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2,0.0,1.0,0.0,1.0,0.0906973706933092,-0.021894027288008128,0.5801629983869797,0.9967545892763217,-0.03470839724691011,-0.06703323945121603,0.027967136544566895,0.8774931387854652,0.023829923470582735,-0.10564487129631965,0.8252754551328085,0.9653929671870117,1.2373584087136416,-0.11456262286007665,-0.0781726695088658,-0.30958055764606257,0.23440554070410136,0.7608662222500624,-0.4910249221565421,0.05609479298940413,-0.014792788345460765,1.0856393196896572,0.29768481560383764,-0.7820033676858287,1.1547218797679626,-2.3493155589300367,-3.7833321601996768,3.9855012415750135,-1.158213888579059,2.03532577851959,-1.9602696638175532,1.0234073891013415,-4.139473521635536,2.3283803856679475,-0.09443785999310284,1.574913447742139,-0.9194945321161363,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.208333333333333,0.0,1.0,0.0,1.0,0.09801671836363687,-0.02132969825300981,0.5803309670548191,0.9969893517170041,-0.03174627141377717,-0.06247706489096791,0.03318166930730392,0.8731726083877165,0.008682350867367308,-0.07646741577139007,0.8245532980989296,1.089538215038174,1.2327424990344271,-0.13428333064939782,-0.1095769596242958,-0.2772813073527995,0.2248554542618207,0.7774099168317349,-0.5074032000751187,0.06422790305852674,-0.04999104787091625,1.104024569870267,0.2968503348099793,-0.7685179596842077,1.145298009794535,-2.383657448123836,-3.751800234144653,3.7694065398544936,-1.1333090779138144,1.930491337715221,-1.960571141888997,0.9235836112632728,-4.298683979727699,2.0865731545123944,-0.10659617265067811,1.655526229096329,-1.3340964622141094,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.216666666666667,0.0,1.0,0.0,1.0,0.10525704446591881,-0.02080472389343101,0.5806736071818497,0.9971969028907398,-0.028803643875432626,-0.057426904822177945,0.03835150022436587,0.8648728296141871,-0.006117524442128895,-0.046618249324060716,0.8221311742403052,1.2018799287374886,1.2245956530576367,-0.15429024699547392,-0.14070267341127668,-0.24675711531515435,0.21551705607220445,0.7930410778786494,-0.523701107854692,0.07148785317712535,-0.08643752134092242,1.1204155389315305,0.29590821272632634,-0.7544112638675565,1.1324869387310608,-2.4180569147507693,-3.716470189144364,3.5603776565284324,-1.107617391978929,1.8173920030674462,-1.942737122339493,0.8153707364620083,-4.438040355333245,1.8489043162104046,-0.12034978546631492,1.7248903319273867,-1.7322841765265196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.225,0.0,1.0,0.0,1.0,0.11239195441409111,-0.020322173060731426,0.5811857948494515,0.9973683910626671,-0.025887098534346654,-0.051932757494194834,0.04346423060610574,0.852813728913676,-0.02032320909531156,-0.01637917666123606,0.818247180098289,1.3022724301226494,1.213071553864675,-0.1745842792285773,-0.17151812944336853,-0.21794167974399228,0.2063951643955052,0.8076997835495257,-0.5397821521141103,0.07781741533289355,-0.12395838712647032,1.1348396418071072,0.2948445050522074,-0.7397697874854179,1.1164266068524265,-2.4526352345568574,-3.6771472095215043,3.359741847917949,-1.0815627995094519,1.6981715742884762,-1.9101541420370571,0.7017324746744378,-4.555795469533051,1.6139768560713286,-0.13576077634872008,1.7847623535159984,-2.113728660544356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.233333333333333,0.0,1.0,0.0,1.0,0.11939758528463149,-0.019884045693666495,0.581861907988342,0.9974957234886582,-0.023001908726819172,-0.04604513595211383,0.048508136232495266,0.837255058963583,-0.03371627950099672,0.01391887588491747,0.8131468263648516,1.3905991632511632,1.1984097129887303,-0.19516750090475488,-0.20198846023663508,-0.1907614178498552,0.1974910094137136,0.821343937450124,-0.5555370102219763,0.08318339442169931,-0.16236744583313995,1.147315153199386,0.29364553312051433,-0.7246652246422899,1.0972581277219882,-2.4875272676206923,-3.6332511889682584,3.167988464162424,-1.0555823711732844,1.5749096263150775,-1.8658224608826468,0.5853724978862868,-4.650678755478303,1.3810026467851788,-0.15273017214978646,1.836910555411908,-2.4779603013395146,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.241666666666666,0.0,1.0,0.0,1.0,0.12625272813687166,-0.019491305118025663,0.5826955366718409,0.9975717300367756,-0.020152006835301474,-0.039815065511303586,0.053472428655392576,0.8184886534496546,-0.0461034735184239,0.04391137353825529,0.8070855353066411,1.466733020921228,1.1808977413680408,-0.2160430670222555,-0.23207231592617283,-0.16514187200795188,0.18880212487595047,0.8339482773214436,-0.5708791931288211,0.08757362363099833,-0.20146969971777537,1.1578563525868601,0.2922990021830443,-0.7091546115618861,1.0751272684967679,-2.5228418755595756,-3.5838041498864914,2.9848474731942587,-1.030126127762584,1.449543651700318,-1.8121965603895585,0.46858298696969364,-4.721842901237699,1.1497981860368256,-0.17105168122030112,1.8830464432157057,-2.8243292426689237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.25,0.0,1.0,0.0,1.0,0.13293883200249434,-0.019143875966118204,0.5836792507359111,0.997590300734649,-0.01733992850903627,-0.033294139131027106,0.0583473999950194,0.7968258239302052,-0.05731367175619627,0.07321478321849462,0.8003293234642666,1.5305314135295172,1.1608501315002835,-0.23721486549741447,-0.26171852940140994,-0.14101395996328422,0.18032224061767052,0.845502998311796,-0.585740286228469,0.0909931108711942,-0.24106482752043493,1.1664784562999997,0.29079467176684265,-0.6932811172553615,1.050185973677506,-2.558636343323496,-3.5274356540428156,2.8092936979232745,-1.005657229721157,1.3238380301259145,-1.7511840562795111,0.35317873551774404,-4.768872131947607,0.9207520703996019,-0.19046159512220107,1.9247425424067033,-3.152003752597805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.258333333333333,0.0,1.0,0.0,1.0,0.13943986265091782,-0.018840622751938776,0.5848044199923882,0.9975465023813153,-0.014566749888275981,-0.02653454949435557,0.06312450483560679,0.7725817908776828,-0.06719469339634515,0.10143892963938898,0.793152938766748,1.5818458607051689,1.1385989461602104,-0.2586870060776471,-0.29086291016021976,-0.11832031037589731,0.17204117104726452,0.8560122444902089,-0.6000655940668129,0.0934599358896274,-0.28095090191690214,1.1732022204268535,0.2891246422643409,-0.677075569188441,1.0225938726201378,-2.5949023075134554,-3.462405548150387,2.639533166110618,-0.9826521463390359,1.1993775295010223,-1.6842203893663843,0.24049212518993696,-4.791818919413008,0.6947767235992552,-0.21067935276036343,1.9633426313954927,-3.459967903944965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.266666666666667,0.0,1.0,0.0,1.0,0.14574201101875175,-0.018579323535521195,0.5860610802342848,0.9974366733369426,-0.011832035863152367,-0.01958905640466718,0.06779641983846334,0.7460595820301091,-0.07561024814290881,0.12819644438775818,0.7858352298023995,1.6205399721735603,1.1144930003078286,-0.2804632372893054,-0.3194252885372497,-0.09702174052810726,0.16394470484535326,0.8654926238034797,-0.613810626051242,0.09500131295769315,-0.3209284761773184,1.1780580683599873,0.2872833492208366,-0.6605587400654366,0.99251984194509,-2.631562436552858,-3.386636099928597,2.472981193970785,-0.9615994389689164,1.0775770171776333,-1.6123843238658142,0.13140872113140023,-4.791245372005716,0.4732390521052787,-0.23143649935641775,1.9998728425258028,-3.747009105740229,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.275,0.0,1.0,0.0,1.0,0.15183326745994405,-0.018356652367382337,0.5874378367410753,0.9972584922917325,-0.009133816099461236,-0.012510862475939213,0.07235710997673848,0.7175357119274322,-0.08243753312205346,0.15310903976761345,0.7786518364180137,1.6465133774042102,1.088902469503131,-0.30254638002019474,-0.3473068451590297,-0.07710395714305089,0.1560145137311159,0.8739718614431694,-0.6269386661312432,0.0956500812418174,-0.36080499145033074,1.1810895379619415,0.2852673672750673,-0.6437443551463443,0.9601437208578006,-2.668477624977874,-3.2977428507844686,2.306226340403488,-0.9429957106174353,0.9597032954675844,-1.5365344343568266,0.02642711177783169,-4.768250264923187,0.25786476575094586,-0.2524934820875324,2.034960690989809,-4.011694107334733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.283333333333333,0.0,1.0,0.0,1.0,0.15770289620109945,-0.01816818288219912,0.5889217961160077,0.9970110149260792,-0.0064686035233038576,-0.005353378576641481,0.07680191884078655,0.6872496831523025,-0.08756600358640071,0.1758108210053588,0.7718655423991362,1.6597296907271382,1.0622259246288213,-0.32493786437226996,-0.37438766938365753,-0.058584634854715795,0.148228109668396,0.8814876787279394,-0.6394195332905225,0.09544176482065701,-0.40039931392603817,1.1823558144558364,0.2830751245193777,-0.6266427285489398,0.9256582734895111,-2.705464010340876,-3.1930550901017654,2.1349745862384393,-0.9273374932055284,0.8469054089491279,-1.4574505807949945,-0.07426957291373826,-4.724466583500482,0.05061540333180847,-0.2736450027342263,2.0687673380875826,-4.25233435911941,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.291666666666667,0.0,1.0,0.0,1.0,0.1633408598339422,-0.018008423427159498,0.5904985180583068,0.9966946717705564,-0.003831466985881947,0.0018301301865749008,0.08112768879658658,0.6553991904790714,-0.09089781625655727,0.1959494624063722,0.765714983949153,1.6602457803855146,1.034896667457236,-0.34763744685920933,-0.40052442999405913,-0.04152104737241024,0.1405588888443571,0.8880869515923215,-0.6512295091444931,0.09441225502658843,-0.43954610117533877,1.1819331280174716,0.28070661722949686,-0.6092648995115513,0.8892714815391438,-2.7423175307842773,-3.069623496737275,1.9539819300501768,-0.9151082737509841,0.7402484908258611,-1.375962755621587,-0.1707397943139341,-4.6620180128357696,-0.14645798894310058,-0.29471584154105446,2.1009373464673264,-4.466941732926948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3,0.0,1.0,0.0,1.0,0.16873725852322746,-0.017870891130732824,0.5921519827475621,0.9963112215688985,-0.0012161648158306286,0.008987012731222334,0.08533290387612556,0.6221430371252067,-0.0923503331524908,0.21318690433513712,0.7604030892542102,1.6482375778835998,1.0073847589029201,-0.3706431565520079,-0.42554806099594544,-0.026018269353879513,0.1329763051058796,0.8938251535750371,-0.6623522458842156,0.09259610158209144,-0.47809961413996765,1.1799148479734514,0.2781631938270268,-0.5916271061078177,0.8512092446073953,-2.7788402877156795,-2.9242269870100626,1.7570166101949678,-0.9067606515075777,0.6407434077277863,-1.2930428152147844,-0.26321475640066705,-4.583425239325701,-0.33137593350149874,-0.31555056454054653,2.1305705994372848,-4.653174349876477,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.308333333333334,1.0,1.0,0.0,1.0,0.17388186624310936,-0.01774822743010665,0.5938645796287975,0.9958636577279903,0.0013846635119094694,0.016065784400191463,0.08941783196186512,0.5876142183131803,-0.09186083277711637,0.2272023943867169,0.7560878516999995,1.6240140842423505,0.9801901280386696,-0.39395145165447065,-0.44926154644422683,-0.012237437202494112,0.1254462113192308,0.8987660083877846,-0.6727802227314061,0.09002534241991064,-0.5159365218307671,1.1764101957924467,0.2754474411538211,-0.5737553895209299,0.8117185757078692,-2.814856579267896,-2.7534167577885196,1.5369520904797398,-0.9026950018774635,0.5493597136092854,-1.2098213482722486,-0.35204170923659656,-4.491453606201316,-0.5023930233543394,-0.33600271978673213,2.156223194190292,-4.8082694293205845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.316666666666666,1.0,1.0,0.0,1.0,0.17876386973722205,-0.017632349256784505,0.5956171428927048,0.9953560720750501,0.003979267688095606,0.023016691399246485,0.09338462032309121,0.5519460205677317,-0.08939312825363994,0.23770205595161098,0.7528797006346495,1.588006493721079,0.9538209694236011,-0.4175574328731395,-0.47143834029242077,-0.00040240117921718226,0.11793138840792187,0.9029811488018585,-0.6825159350220864,0.0867287397614815,-0.5529571742433229,1.1715416309175457,0.27256314849724794,-0.5556900528713128,0.7710714207853856,-2.850196908641555,-2.5536712510459028,1.286173103916398,-0.9032380178140337,0.46700345302756574,-1.1274751204162725,-0.43764753435345,-4.388894144237561,-0.6581426425175518,-0.35593183157343056,2.1759466415645434,-4.928955312670067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.325,1.0,1.0,0.0,1.0,0.18337194240685234,-0.017514617090079194,0.5973890882083551,0.9947934910419177,0.0065765655972135975,0.02979215417695404,0.09723727009902125,0.5153130165862927,-0.08494510970918788,0.24443966958308885,0.7508506202498091,1.5407168652066265,0.9287520884986742,-0.44145473346516323,-0.49182273396165854,0.00919878119611252,0.11039224435566358,0.9065493992715774,-0.691571474738344,0.08273121684735314,-0.5890847575680598,1.1654411517504875,0.2695152439609306,-0.5374896121615208,0.7295693204967014,-2.8846197206014748,-2.3217595363539925,0.9975244164141085,-0.9086262040009655,0.39443923818208937,-1.0469267848567632,-0.5205300874131602,-4.278277401852131,-0.7977371582622972,-0.37521761633079076,2.1873725675397715,-5.011329411382399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.333333333333333,1.0,1.0,0.0,1.0,0.1876947953500847,-0.01738598564191236,0.5991587319268764,0.9941817131429669,0.009186005049096928,0.03634689732457332,0.10098139327964163,0.34757752408756454,-0.0402904777198647,0.2610238252892896,0.7775674004205452,1.4246665610442912,0.9678048767029986,-0.4656344282164974,-0.5101343325649873,0.01622300576101796,0.10278761834123912,0.9095551361048934,-0.6999647147696991,0.0780532383045955,-0.6242617976075251,1.158246011613174,0.26630952155840143,-0.5192338434123166,0.6875492639290123,-2.8919580359428387,-1.2859637003036628,-0.1156852287198483,-1.0558088246157937,0.23029857593384495,-1.0997770816051888,-0.6595400393382215,-4.483802532528811,-0.7908574866167184,-0.4482252208134929,1.9653500654041944,-4.958398606244838,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.341666666666667,1.0,1.0,0.0,1.0,0.18948831060495047,-0.017052818874760657,0.6013021472603356,0.9934903557129426,0.012118222269498909,0.04217565476622991,0.10512504974476533,0.18596966922328817,0.0008649598627146482,0.2580450802819908,0.7812937177171342,1.3317640100535626,0.9967787657424579,-0.48965403406421054,-0.5132554623000529,0.007270694050781715,0.09279543061206702,0.9103877088704748,-0.7099010927650972,0.07173888285838279,-0.6638147997768733,1.1522601936402088,0.262044823614039,-0.5047337777381176,0.6469293437259541,-2.8586978384876307,-0.2596616137344898,-1.321445588252827,-1.179868933234128,0.21807236224094861,-1.5008736430301206,-0.7715307185057457,-4.685632855820033,-0.7951294125568964,-0.4907997579358925,1.708679451528592,-4.856065865168464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.35,1.0,0.0,0.0,1.0,0.1910831301048882,-0.016786717105550696,0.6031915474171493,0.9927630035452217,0.014837223897860675,0.04795603057721756,0.10909488914974937,0.17399398732601762,-0.003956792181667855,0.233714250594697,0.7428790529109476,1.3072875749386017,0.955469076675959,-0.5132793921912913,-0.5144620261272288,-0.0058010873765291585,0.08312313612067032,0.9131896754755758,-0.7249792754868678,0.0651943929961664,-0.702355678537859,1.1449938547372258,0.2581295255928032,-0.49075585255350673,0.6066148328428712,-2.8011383763123434,-0.0834265264802192,-1.6271318147245948,-1.1536741712546001,0.42868568677020935,-2.002190977299474,-0.8056376682299763,-4.505170707835571,-0.9658888912625629,-0.45766678179732234,1.6842052898615245,-4.809592734787196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.358333333333333,1.0,0.0,0.0,1.0,0.19270354224850858,-0.016558885055915153,0.6049083860003575,0.9920093965694987,0.01745719681314135,0.053548156096889774,0.11289463443377486,0.17899292695156607,-0.009613189239206912,0.21682861175140955,0.7183044940057118,1.2511896812667045,0.9170406081715815,-0.5363396736694163,-0.5146459044080566,-0.019848169527961534,0.07356752775782369,0.917532470316645,-0.7432709423867551,0.05831158838788318,-0.7389009782407995,1.1361620454524994,0.254417043917417,-0.4766636895737588,0.5667694648128342,-2.7227181312633952,0.027003267930403307,-1.6757955307159729,-1.1444413099774686,0.596825570264059,-2.323948436947063,-0.8446830126164322,-4.251566824424349,-1.1385302480610804,-0.43315281854975685,1.7017390536476762,-4.723360909938008,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.366666666666666,1.0,0.0,0.0,1.0,0.19440695887801226,-0.016350454695641944,0.6064697643617039,0.991239844542989,0.020007650507277853,0.05884183548714449,0.11653713140248892,0.18934049537326117,-0.014776907666574593,0.20123050263449474,0.6962729506462952,1.1717531542559183,0.8818221400814992,-0.5586580277123478,-0.5140119716617221,-0.03373101288846204,0.06404911428771251,0.9231367683133102,-0.7637117494359855,0.051116342785892534,-0.7732151256115981,1.1260183506028745,0.2509103119503073,-0.46239353499271213,0.5278921510105711,-2.6243137700210895,0.12466594806577858,-1.6286654752930256,-1.1426097190531754,0.7390669827116425,-2.5429487745894064,-0.8800263721420957,-3.9816948415031828,-1.2756659466620013,-0.407159815522381,1.7153948174674272,-4.570312546840152,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.375,1.0,0.0,0.0,1.0,0.19621484507660228,-0.016148819500912844,0.6078697694356509,0.9904650024515378,0.022503741076355298,0.06375662691086516,0.1200323004423457,0.2026093399959335,-0.019500199815134962,0.1849570829664538,0.6750852308512056,1.0744007470791,0.8492403772569537,-0.5800782365031011,-0.5125681386069603,-0.04699259411617863,0.054524032440270764,0.929850253361839,-0.7856534219632452,0.04364448218551492,-0.8052625589325192,1.114900946341466,0.24763104699204397,-0.4480737759493017,0.490597589032165,-2.507529635444379,0.22661872627371737,-1.543306522022334,-1.1453064534783193,0.8660243556059699,-2.6933346815086168,-0.9111696964163797,-3.7113361883844553,-1.371886894400829,-0.3784054535266762,1.7086811989597883,-4.338936424612264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.383333333333333,1.0,0.0,0.0,1.0,0.19814134875571804,-0.01594338425825348,0.6090964954431334,0.9896956764719732,0.024957161699075213,0.06822611442482059,0.12338883828937804,0.21842084256975738,-0.023920641739636865,0.16750863963695795,0.6543448190245977,0.9616558359412968,0.8191130520976034,-0.6004501883030875,-0.5102349928904935,-0.05945278825550094,0.04496067339640719,0.9375705075734097,-0.8086006607944625,0.03593018117895287,-0.835070728751339,1.1031535690295273,0.24460355439152934,-0.433915515010049,0.4555765439337,-2.3727733654912386,0.3406369048178348,-1.4437724903957097,-1.151389882254253,0.9822100835317493,-2.7883631715474277,-0.9382942150425942,-3.445799644473664,-1.4270408159941672,-0.3466373112879134,1.6733165007042572,-4.019887668566149,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.391666666666667,1.0,0.0,0.0,1.0,0.20020068606767366,-0.015724274672686975,0.6101365099822986,0.9889426422028964,0.0273784951597568,0.07219066013077756,0.12661507438790645,0.2368704051410862,-0.028179379985196054,0.14875472618945504,0.6338978405370156,0.834806968517191,0.7914068517679601,-0.6196244592612884,-0.5068908568599964,-0.07105546895610712,0.03533420106936655,0.9462204214207015,-0.8321261414890356,0.02800624526813835,-0.8626925530070803,1.0911169327415633,0.24185375847057874,-0.42018516760423075,0.4235994612227292,-2.2202020617125706,0.47034861987977905,-1.3409789639775611,-1.160153396965189,1.0902422157395453,-2.8347796231400935,-0.9615325262122814,-3.187552236113733,-1.4413289391705497,-0.3116425063095801,1.603158208308424,-3.603535236146297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4,1.0,0.0,0.0,1.0,0.20240840893216885,-0.015481946676129652,0.6109758435099002,0.9882164186783942,0.02977790321120632,0.07559456932667186,0.1297191098033043,0.2580889490238074,-0.0323956897557144,0.12860466070284024,0.6136667224264013,0.6945831500923326,0.7660900639568796,-0.637453555998297,-0.5023958492258305,-0.08180243765512696,0.025624783446987376,0.9557412111690687,-0.8558469878467974,0.01990463907541485,-0.8881965993532346,1.0791314200433515,0.239409512619703,-0.4071962115382419,0.3955176233312617,-2.0502255458462537,0.6170813108632445,-1.2397627212864377,-1.1710471641361506,1.1921958874861138,-2.837486156619775,-0.9809850406451058,-2.9383697415469356,-1.4143707353493706,-0.27316611866930185,1.4930389634914187,-3.08064300474047,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.408333333333333,1.0,0.0,0.0,1.0,0.20478104149587686,-0.015207001508150885,0.6115998135626666,0.9875270747564816,0.03216547870948133,0.07838430478138955,0.13270855052404523,0.282224063209452,-0.03657119745562746,0.10673433828975101,0.5935471747605844,0.5404016566023581,0.7426875577956591,-0.6537948850253926,-0.49660616834560894,-0.09171818097754775,0.01581674833376404,0.9660903528788034,-0.8794175774326985,0.011656494590719919,-0.9116653820328625,1.0675440871524071,0.23730098982609038,-0.39530118487937377,0.37225541114372135,-1.8625008782706542,0.7816507075213097,-1.141341990285649,-1.1835439451325136,1.2901965029518014,-2.7996441193689736,-0.9970678299730843,-2.70048446340311,-1.3420736680394008,-0.23100029089081597,1.3376821940927786,-2.439147478257464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.416666666666667,1.0,0.0,0.0,1.0,0.20733593351396237,-0.014888139753490478,0.6119897625719709,0.9868851203151727,0.03455171130072983,0.0804994906257444,0.13558676397422775,0.3072845328240499,-0.03999286666910042,0.08743490749823768,0.5766925152529835,0.3946991601247729,0.7182458885665814,-0.6684952373028079,-0.48936833743380864,-0.10082480415988777,0.005899051028112151,0.9772444862182654,-0.9025077231696136,0.0032868419091967786,-0.9332046737432864,1.0567635255760282,0.23555950777152274,-0.3849015083033623,0.354865165360304,-1.6758457260804493,0.9446200453306686,-1.0623856584932325,-1.2009296515147623,1.3760601115594984,-2.752746433334805,-1.0187964493981592,-2.470275007574121,-1.2855455838745566,-0.19517419304496852,1.1746336393951107,-1.796004551935807,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.425,1.0,0.0,0.0,1.0,0.21006763758192223,-0.014515953886276963,0.6122089465012805,0.9862861579334289,0.03694542025414003,0.08207554522701875,0.13834108381955357,0.3292684730384399,-0.04207652645822518,0.07720518821772702,0.5660781731838552,0.2924800905379735,0.6901125900287186,-0.6817256471267334,-0.48086250092343114,-0.10942460861910162,-0.004198745858148665,0.9890246880714617,-0.9252966846549453,-0.005323446232582735,-0.9528366321590979,1.0461183274211645,0.23404808660867424,-0.3757239575561219,0.34232200194479123,-1.5206338281281617,1.0741174971827183,-1.0261598533163931,-1.2264227395200795,1.4355664736780405,-2.744261153727001,-1.0542242589954582,-2.2370361131936822,-1.3409418993583078,-0.17792793486296254,1.0713208183575584,-1.353367727543563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.433333333333334,1.0,0.0,0.0,1.0,0.21294834634054943,-0.014094375776912199,0.612356255770332,0.9857160580600616,0.03933982886828075,0.08334391572134699,0.14096106718853682,0.3472605776996065,-0.04378605027048742,0.0742743893010664,0.5577560858550322,0.22799008605067533,0.6604985720122869,-0.6938391344382773,-0.47146637914743,-0.11792746838182766,-0.014541327963889173,1.0011705941128994,-0.9482454090650636,-0.014283562407394193,-0.9704886089631811,1.0344144939200564,0.23259404219047336,-0.3670461613307363,0.3323090365679113,-1.394326341914205,1.1710834511434198,-1.0234330671091865,-1.2551590117628662,1.4709366157970782,-2.7703124748510355,-1.0929729100818684,-1.997281883289983,-1.4904693872117347,-0.17163533869033076,1.0297918028006559,-1.1069476512718823,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.441666666666666,1.0,0.0,0.0,1.0,0.2159600458675358,-0.013635062121351106,0.61246531396077,0.9851697545562546,0.041718368446503826,0.08438728907936997,0.14345353911915065,0.36319103421336196,-0.04601043373868707,0.07382169065875452,0.548166053401808,0.17741767120432925,0.632032144305055,-0.7049644194919702,-0.46134444340437414,-0.12648182640425473,-0.025118062720863102,1.0135402983347463,-0.9714685592357959,-0.023539661400613872,-0.9861246635472642,1.0212771709676356,0.23118749763050206,-0.35856076084277766,0.3238728744235932,-1.279125223759987,1.2537236895208481,-1.0322581112911067,-1.2828820264044034,1.4917614758373743,-2.8010592516758304,-1.1251909585568818,-1.755863951043859,-1.66765620223837,-0.16524642172407955,1.0144914125795834,-0.9406005122299455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.45,1.0,0.0,0.0,1.0,0.2190968328305922,-0.013144765770639973,0.6125491909504428,0.9846457291839779,0.044072880420999334,0.08523631616835094,0.145825716588474,0.37847454284428217,-0.04865707430846347,0.07433267568267599,0.5377240405715732,0.13184259706288937,0.6048656514979952,-0.7151578881676104,-0.45057098432208254,-0.13513177023667944,-0.03592269507062923,1.0260332853768557,-0.9949297299263274,-0.03303674505000889,-0.9997530081472454,1.0066202238827502,0.2298399351617387,-0.3501379711210766,0.31663236136407885,-1.1689313619211905,1.329870306320251,-1.0439558568716922,-1.3102435417009408,1.5016052269686764,-2.823863214432736,-1.1513703038411984,-1.5165843164672843,-1.8480385355928663,-0.15747875854905946,1.0103753887667333,-0.8056328262173695,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.458333333333333,1.0,0.0,0.0,1.0,0.22235868816182347,-0.012626244450442392,0.6126130998827138,0.9841440758347378,0.046400377788335403,0.08590065398069698,0.1480828166497548,0.39379230303915014,-0.05157071761481228,0.07521793429575194,0.5268562478952692,0.08757576714597545,0.5787307553092865,-0.7244466088573234,-0.4391799382990366,-0.1438810906854496,-0.04695545508254545,1.0385670521175576,-1.0185329461430082,-0.042729166464633844,-1.011401068821719,0.9904765287077545,0.2285628516546844,-0.34172117102999877,0.3104456606533037,-1.0612236766567396,1.402986779222356,-1.0550803237853053,-1.3377733036017012,1.502082016293631,-2.833929715568939,-1.172434119112276,-1.2812865861226186,-2.0213994857138196,-0.1484473597047009,1.0112507688734251,-0.6816601560507429,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.466666666666667,1.0,0.0,0.0,1.0,0.22574819463431756,-0.0120801863210224,0.6126590630894241,0.9836656011449961,0.04870029956219531,0.08638115274095196,0.1502283674880669,0.4094408803066853,-0.05466394997298557,0.07622467982426581,0.5157728539792631,0.04304815819466132,0.5533766068191602,-0.7328449494452227,-0.42718787133504327,-0.15271644229976786,-0.05821891679732425,1.0510679856484162,-1.0421618918524764,-0.05257731370188016,-1.0211077845826224,0.9729302324541865,0.22736581249999369,-0.33328379163985283,0.30527135876323314,-0.9549251059174058,1.4744920806573458,-1.0640082267024853,-1.3655942733819604,1.4940224732235174,-2.8298079298038203,-1.1889259047205594,-1.051179736475154,-2.1832872220400645,-0.13834021814393527,1.0146169623764256,-0.5602062879287906,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.475,1.0,0.0,0.0,1.0,0.22926893132714476,-0.011506366661200862,0.612687767641508,0.9832113931812057,0.0509730949425665,0.0866748735341355,0.15226478978630315,0.42552939047252925,-0.057895252286694024,0.07723163252046125,0.5045508780863192,-0.002420333478853731,0.5286297897077642,-0.7403620272892801,-0.41460507028808086,-0.16161456113049102,-0.06971535963891146,1.063467426671283,-1.0656964116397385,-0.0625445982099765,-1.0289207310963049,0.9540884083404201,0.22625718135228548,-0.324810888323725,0.30110888918782386,-0.8496186464274857,1.5448115592358236,-1.0696495724450035,-1.3935934199423736,1.4779063419997218,-2.8114388937066215,-1.2011143968563083,-0.8272179232109389,-2.3316760762379896,-0.12726082917960568,1.0195699599529051,-0.43794547925342764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.483333333333333,1.0,0.0,0.0,1.0,0.23292469081099887,-0.010904216887716684,0.6126993472187454,0.9827826119288249,0.05321957040636275,0.08677720524533158,0.15419381202242713,0.4420763359721634,-0.061243858247920016,0.07817107338520912,0.49320251703290147,-0.049130131091731005,0.5043772838632486,-0.7470052602190141,-0.4014410120144462,-0.17054393517385125,-0.08144547379636381,1.0756997580150782,-1.0890192067475868,-0.07259588698281863,-1.0348947499694714,0.9340689645168867,0.2252447986803336,-0.3162909589739711,0.2979722674423427,-0.7452050752627692,1.613878739467477,-1.0710161545935633,-1.421542547611484,1.4540353996847433,-2.7793153459078734,-1.2091360936697946,-0.6102240730346864,-2.4655731399432934,-0.11524932991364756,1.0259238788234781,-0.31384359082061053,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.491666666666666,1.0,0.0,0.0,1.0,0.23671908695467375,-0.010273085374217825,0.6126937288087219,0.9823803849758963,0.055440602124412784,0.08668277161723194,0.15601671691035665,0.45905531977969993,-0.06469614264256845,0.07899752975612967,0.4817112680551624,-0.09721715605396458,0.48054390977711625,-0.752782111876993,-0.38770709129695624,-0.17946483037371708,-0.09340773543243619,1.087701349999362,-1.1120183340715364,-0.08269686643780641,-1.0390911323135497,0.9129955226746985,0.22433635918705802,-0.3077121570100004,0.295878162674147,-0.6417431739521473,1.6813808947634146,-1.0671037036090343,-1.449155424965414,1.4226086908025648,-2.7341234060666375,-1.2130800597699973,-0.40093821711775224,-2.5844153670288272,-0.10231247056252168,1.0338302341722105,-0.18791906270006709,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5,1.0,0.0,0.0,1.0,0.24065534715624687,-0.009612353321384971,0.6126707951706467,0.9820057524249156,0.05763701301725987,0.08638582648984176,0.1577344791620298,0.4782904907476679,-0.06881587689397665,0.080621191600033,0.46781969813177043,-0.1596087336260141,0.4583551670722093,-0.7577009797848833,-0.37341799710172263,-0.18832899690066848,-0.10559806421245405,1.0994099028617876,-1.1345879301820307,-0.09281388797898525,-1.0415770535881006,0.8909953750664062,0.2235395908376249,-0.2990604550711009,0.2948402830640082,-0.5233708054140762,1.7481274087119147,-1.023307254644776,-1.4719960034945196,1.3801063596808971,-2.646018040877114,-1.2093816508261248,-0.1999231930810863,-2.6636891472279767,-0.0832299799912517,1.0421694946990046,-0.027090751245848477,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.508333333333333,1.0,0.0,0.0,1.0,0.24477125002685457,-0.008921918765108445,0.612639820090326,0.9816682482002617,0.059809295093436805,0.08577159893459414,0.15935347976144243,0.5021925194673251,-0.07402181941049896,0.08371741796474884,0.44993055918809793,-0.2521400057862823,0.43906656171201097,-0.7615049586338942,-0.358571634485091,-0.19651995128446334,-0.11794100215734485,1.1107031226607103,-1.1561186347528216,-0.10285322728490849,-1.0424231855315678,0.8686007035542322,0.2229491928538705,-0.29034266543168363,0.2954266501533829,-0.37276418310966397,1.8148033411036224,-0.89723993841203,-1.4859183665252362,1.3242426954178699,-2.481426582730566,-1.1955723437760137,-0.010236356707871153,-2.669101521765833,-0.052873846918035095,1.0471340888601632,0.214581476539768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.516666666666667,1.0,0.0,0.0,1.0,0.24911187438942206,-0.00819575882096493,0.6126070503192851,0.9813785775660746,0.06196715465496763,0.08470200333486949,0.16087799684679407,0.5294884578540439,-0.07942542919496187,0.08678020460590435,0.43128441159292913,-0.3652484911048054,0.42123656135048887,-0.7639137161700443,-0.3431712747499956,-0.20328299587420232,-0.13036337032120798,1.1214806144520855,-1.1759450398942068,-0.11274009370858548,-1.0417476595332318,0.8465103497036424,0.22265836005565764,-0.28160822025676485,0.2984166410063377,-0.20576112778923905,1.879114859292973,-0.7125599013200673,-1.4953608038869393,1.2611502236828942,-2.269287922705141,-1.177351806676287,0.16279257891991694,-2.6105555090964616,-0.016905145989313808,1.0470581505580268,0.5185294678132091,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.525,1.0,0.0,0.0,1.0,0.2536860186885724,-0.007424283969939144,0.6125660472841195,0.9811382445680044,0.06412423711910376,0.0831454023712096,0.16230424924958106,0.5574122228353835,-0.0842920733120424,0.08841535426827253,0.414251341792446,-0.4818020840952398,0.4031568708616834,-0.7649343107637149,-0.3272530534968748,-0.2083959496397978,-0.14286368222212717,1.1317222930554252,-1.1939401001312406,-0.12247575739617994,-1.0397099758829025,0.8250914450692912,0.22266744042071526,-0.2728916962557165,0.3040688079502697,-0.04475352025426815,1.9373594365122238,-0.5111853724475324,-1.5044274688620385,1.1957425069075933,-2.0519397044637433,-1.1590887411104973,0.3169408344937974,-2.517707956579429,0.018658203494234527,1.0472534606042327,0.8337388544404911,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.533333333333333,1.0,0.0,0.0,1.0,0.25848771682236316,-0.006602844563739219,0.6125110976539471,0.9809451453943806,0.06628593928178239,0.08110775324187994,0.1636286293557593,0.58463762624277,-0.08872230259360704,0.08855846876754726,0.39830616705383237,-0.5951538991070277,0.38452260994689696,-0.7646596081742821,-0.3108819508081252,-0.2118027520816612,-0.15543716146890862,1.1414096562338787,-1.2101440349686026,-0.13205823939376043,-1.0364653122916685,0.8045485504273185,0.2229693301138949,-0.264153995913361,0.3123122885803459,0.10329611128755856,1.9864332824548026,-0.3058814746009725,-1.512411559005059,1.127518209347782,-1.8426973744400588,-1.140107481305049,0.4533787084352747,-2.405603136673067,0.05350543526704554,1.0555179075180687,1.1291616192050713,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.541666666666667,1.0,0.0,0.0,1.0,0.2635056799123783,-0.005730786266847948,0.6124389518341476,0.9807953612953085,0.06845240982595195,0.0786111825777309,0.1648484419837308,0.610604323431903,-0.09289433819724417,0.08739630123091195,0.38296968147610577,-0.702274522895574,0.36529143608955217,-0.7632127089089222,-0.29414583212262807,-0.21349397421648067,-0.16807054153887815,1.1505142632112215,-1.224651723038575,-0.1414775487512641,-1.032153664075648,0.7849980594580734,0.22355919767516602,-0.2552997311304154,0.3228881682703542,0.23595497628769557,2.0241949658987926,-0.1003341569785765,-1.5184162701407917,1.055350023811532,-1.645840218554211,-1.1196273917509314,0.5739531409529874,-2.282644719416649,0.08790085533316061,1.0772142609180508,1.3874411497300265,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.55,1.0,0.0,0.0,1.0,0.2687270411683885,-0.004809934397550712,0.6123484224543653,0.9806839892606335,0.07062082604329391,0.07568575168920184,0.16596167969812295,0.6350990034395437,-0.09694869869578081,0.08512502538462,0.36794566316972865,-0.8016053228221158,0.3454534127955033,-0.7607270252361539,-0.2771453680431453,-0.21347498803130413,-0.18074409930458848,1.1589988232974042,-1.2375747052778394,-0.15071869592294262,-1.0268994266091187,0.7665044717703744,0.22443434436944756,-0.24620042489806013,0.335436307742513,0.35253275347127966,2.049609244987234,0.10399681004528649,-1.5217669401469391,0.9783646662051515,-1.4625736524627575,-1.0971987759378938,0.6804087355001709,-2.1539316611775217,0.12204017530092925,1.115146839771501,1.5997051048733757,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.558333333333334,1.0,0.0,0.0,1.0,0.2741388639567354,-0.00384365407333118,0.6122396967754393,0.9806056260808269,0.07278658726352612,0.07236591197522729,0.16696674398629927,0.6584108718946573,-0.10057767692525944,0.08145688171442532,0.3527839194923139,-0.8952989239427764,0.3228742838994717,-0.7573371630177342,-0.2599856780395075,-0.21176069404905923,-0.19343332387466047,1.1668203409813074,-1.249027950579621,-0.15976419501689565,-1.0208135184839784,0.7490991984384481,0.22559320059684818,-0.23671395046755703,0.3495499200182438,0.45692802160486545,2.0650559165009987,0.30596697356079117,-1.5213253056804072,0.8965403372164049,-1.2905109189723074,-1.0739035684533156,0.7710659949463494,-2.01185065555195,0.15475145844027816,1.1658695123673875,1.777383611788509,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.566666666666666,1.0,0.0,0.0,1.0,0.2797307187880641,-0.0028270406171338035,0.6121069404239735,0.9805595599666977,0.0749448124578669,0.06866485398093487,0.16784326698332688,0.6807385762771356,-0.10365468514746119,0.07623978259379496,0.3375231105913215,-0.9842860840187336,0.29636972958688246,-0.7531115582094061,-0.24272776943479535,-0.2083755384719576,-0.2060995210659286,1.173941162251011,-1.2590832205940445,-0.16861708873049788,-1.0140483266933462,0.7329736275111752,0.2270135353434522,-0.22676926635860367,0.36505936793898813,0.5511156645169102,2.0720355646582833,0.5044415172595573,-1.5165129217203017,0.810027013798722,-1.128611855462811,-1.050565166708607,0.8453291565195009,-1.852907103786654,0.18506841927294682,1.227001145573674,1.9273805613475725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.575,1.0,0.0,0.0,1.0,0.28549222111901745,-0.0017606468823442444,0.6119480009143138,0.9805423588568858,0.0770916274099524,0.06461022016149455,0.1685796041093415,0.7015574862060625,-0.10690722942157059,0.07025795801226667,0.32263901657180916,-1.0632688804138994,0.26922549682045116,-0.7481519019424524,-0.22545175196186945,-0.2033533354280666,-0.2187085392366655,1.180320791211286,-1.2678381481706678,-0.1772736144620391,-1.0067246992086534,0.7182174133753372,0.2286776742513973,-0.21626393137466246,0.3816729293740367,0.6295725797538276,2.0670937409570525,0.6976503455192673,-1.5080111444912736,0.7181168231222568,-0.9809649931612041,-1.0252659112893865,0.9090804494074889,-1.6962610396227973,0.2147345865262007,1.304315813298947,2.026763185075633,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.583333333333333,1.0,0.0,0.0,1.0,0.2914112464330515,-0.0006558491997242617,0.611768410445173,0.980545493559145,0.0792204707202047,0.060257207207015585,0.16918546349985328,0.7205882852487419,-0.11067130803588104,0.06396650800593516,0.3077930335239564,-1.1296785665726043,0.24300453898586125,-0.7426186818801757,-0.20827620708551114,-0.19674803271330316,-0.23123304014078316,1.1859097759697153,-1.2754326371467313,-0.18570485391865432,-0.9988969858698881,0.7047026101841286,0.23059244511888888,-0.2050306694702879,0.39883875435691535,0.6910484568898778,2.0495314453132756,0.8829374066840973,-1.4956273530912763,0.6203703817273132,-0.8488049667661235,-0.996768177275375,0.9657574729125207,-1.5522107082998637,0.24493757146562434,1.399091536823775,2.066524088592433,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.591666666666667,1.0,0.0,0.0,1.0,0.29747622194765727,0.0004790558666303961,0.6115715518422115,0.9805628774158505,0.0813220093812441,0.05565313381980336,0.16966408848218845,0.7379842135279399,-0.11475484371836739,0.05721778998580393,0.29258080656732904,-1.1848690732214198,0.21662235182619652,-0.7366344276609544,-0.19129289453998152,-0.18863771198333165,-0.24363566178818677,1.190660297573408,-1.2819848976167698,-0.19388641741662868,-0.990628741326778,0.6923472349036728,0.2327599671091577,-0.1929457390942662,0.4161149975172439,0.738962979820017,2.0221657093782865,1.0574457746126897,-1.4786820642011855,0.5171618716743076,-0.7302634692223853,-0.9657212196774234,1.0146816699797911,-1.417004475187651,0.27504030595473516,1.5063640160520304,2.058180362721558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6,1.0,0.0,0.0,1.0,0.30367613708706614,0.0016367556710691175,0.6113593595078868,0.980589658055157,0.08338755325864414,0.05084232933570297,0.1700161640103839,0.7537893004064027,-0.11909339601927482,0.049946161343718834,0.27703972972950397,-1.2294721606410688,0.18963822603166114,-0.7303026322165087,-0.1745734452625397,-0.17912393646975833,-0.2558777412108029,1.1945291404976204,-1.2876036949671044,-0.2018002075799447,-0.9819856247035582,0.6810858689310011,0.23517645021813446,-0.17992460253608739,0.43314176040227464,0.7753321935440471,1.9872052113784278,1.2184161001728566,-1.4570524682293224,0.409007339735461,-0.6244258258100377,-0.932747243381542,1.0557249465727092,-1.289370231632403,0.3044536177893542,1.6218050213555812,2.01033083167138,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.608333333333333,1.0,0.0,0.0,1.0,0.30999974051555235,0.0028102606549076452,0.6111327256590591,0.9806219566610068,0.0854087105774897,0.04586738951443605,0.17024133708120195,0.7679776919137931,-0.12363771670606682,0.04212584352040215,0.2611922370646981,-1.263868308802993,0.16187355536148645,-0.7237122244352203,-0.1581728076836744,-0.1683307769804507,-0.2679198695920088,1.197477086568999,-1.2923919947136038,-0.20943220480632105,-0.9730333255505662,0.6708577310431327,0.2378341940723136,-0.16591565540500652,0.44962051137843356,0.8017213267959256,1.9466877385649846,1.363011063935361,-1.430724275455466,0.2963148550316008,-0.5305731985789963,-0.8983115397146618,1.0889571061614656,-1.1690547175920818,0.33271898924033316,1.7417675491001312,1.9295790842737504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.616666666666666,1.0,0.0,0.0,1.0,0.31643543200435076,0.003992876724746709,0.6108917059618449,0.9806567323293148,0.08737746070350018,0.040769792004053715,0.17033900539316718,0.780477320726002,-0.12833051622444253,0.03376329582537703,0.24505403792116587,-1.2883533922847712,0.13327082921411174,-0.7169406101032433,-0.14212864961978997,-0.15640708540416898,-0.27972314580172736,1.1994677214148137,-1.2964465816100876,-0.21677206657518908,-0.9638363396008671,0.6616016236377997,0.24072176670547335,-0.15089514338441853,0.46530141180683715,0.8194717748285063,1.9026015252215618,1.488352155459008,-1.3997688038562595,0.1793529234988256,-0.4479767445163185,-0.8628186173379532,1.114562058158799,-1.0563106876758033,0.3593948973023303,1.863055673167436,1.8213560057667455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.625,1.0,0.0,0.0,1.0,0.32297066195308405,0.005178058595275507,0.6106358024543519,0.9806917762092977,0.08928601420303926,0.035589878535690275,0.17030856786769696,0.7911682333749452,-0.13309631713729025,0.024893110439578058,0.22863939831655017,-1.303222055287126,0.10383279335799611,-0.7100543615214119,-0.12646278226331503,-0.14352490772280058,-0.2912493496562798,1.200466301960646,-1.2998582737888758,-0.22381251509528693,-0.9544572912479196,0.6532525529152027,0.24382410902735244,-0.1348647275188826,0.4799764448078793,0.8297917111500475,1.856854161183702,1.5916678097394972,-1.3643325309430876,0.058226689169136314,-0.37582597329219425,-0.8266508121576344,1.1327936359863178,-0.9516775898127205,0.3840101551216879,1.9827579056878242,1.6904030402336945,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.633333333333333,1.0,0.0,0.0,1.0,0.3295917104766272,0.006359533386931603,0.6103641189768627,0.9807256597954807,0.09112699916742907,0.030366827196184484,0.17014965779454447,0.799907101077482,-0.13783519414975387,0.015571963505609424,0.2119941037600851,-1.3087918407112813,0.07361340832718077,-0.7031107482507425,-0.11118108026672827,-0.12987928857517736,-0.3024620213174455,1.2004381662342993,-1.3027103478316242,-0.23054958011114965,-0.9449564456677618,0.6457403304742544,0.24712193595750148,-0.11784917828962146,0.49347479581073206,0.833728078878262,1.8113219854279272,1.6702882211518086,-1.3246778559085715,-0.0671465765797663,-0.3131213364577734,-0.7902141082842384,1.1439570276891708,-0.8558285479543848,0.4060247927405375,2.098205926240774,1.5410046614570072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.641666666666667,1.0,0.0,0.0,1.0,0.3362834034181738,0.007531404624036161,0.6100755359261988,0.980757686195162,0.09289360815284667,0.02513848394196196,0.16986228291951994,0.8065132528534992,-0.14242335187716926,0.005884014061117007,0.1951714875514977,-1.3054408847250976,0.0426980549153267,-0.6961588935401075,-0.09627408250618291,-0.11568677070360377,-0.31332731392142266,1.1993471923509833,-1.3050769627298386,-0.23698275023335758,-0.9353913407864334,0.6389887437826296,0.2505911889063614,-0.09989462874820303,0.5056598558321628,0.8322278779501513,1.767702184932912,1.721915903139285,-1.2811375974711492,-0.19704266562555084,-0.2586718780146757,-0.7539137281833763,1.1484039211496477,-0.7695319703763914,0.4248478007779577,2.206906958164469,1.3771697224282065,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.65,1.0,0.0,0.0,1.0,0.34302866501355334,0.00868817283007941,0.6097689654418725,0.9807878512929542,0.09457962323826881,0.019941002843245924,0.16944687081770726,0.8107792885854063,-0.14671156178511213,-0.00406121869776134,0.1782495111713115,-1.2935994118550789,0.011206246865151863,-0.68924028361824,-0.08171937718451307,-0.10118069018952261,-0.3238143146086313,1.1971541218072068,-1.3070215457985355,-0.24311480891420592,-0.9258163803152677,0.6329147976346479,0.2542027326371341,-0.08106739565354698,0.5164276245178688,0.8261039920918201,1.7274557433941387,1.7447212913007748,-1.2341346522744978,-0.3319543480042064,-0.21105008139749248,-0.7181708992847047,1.1465355808321243,-0.6936303627223972,0.43982573115333823,2.3065308634240913,1.2027017862272582,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.658333333333333,1.0,0.0,0.0,1.0,0.34980836814527416,0.009824929097833477,0.6094434979338857,0.9808167326684766,0.0961796780960999,0.014808765888750753,0.1689044312377556,0.8124822305105205,-0.1505286875132309,-0.014134717367027858,0.16133733397580696,-1.2737553724042354,-0.02072516167911677,-0.6823904936719105,-0.06748315344961393,-0.08660808251525752,-0.3338962247926643,1.1938146198842465,-1.3085944640864635,-0.248952265221436,-0.9162824144392313,0.6274282377372563,0.25792161775891703,-0.06145244769113484,0.5257048856026171,0.8160385539311243,1.6917826633991786,1.737386893947985,-1.1841694240368295,-0.47258086278122224,-0.16858257663506127,-0.683429149000106,1.1387778994960596,-0.6289494154663355,0.45023630576254137,2.394891706258248,1.0213145371320675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.666666666666667,1.0,0.0,0.0,1.0,0.35660105760476357,0.010937408434676152,0.6090985580911759,0.980845431160515,0.097689332858078,0.009773999346621397,0.16823645072956325,0.8113841795566835,-0.15368916025148363,-0.0241876853360342,0.14455618558903732,-1.246453012915601,-0.052956470128169814,-0.6756396410527212,-0.053522999461193425,-0.07222424195705619,-0.3435504716759118,1.1892777740941864,-1.3098312554091198,-0.25450529473087435,-0.906836748657,0.6224323073768756,0.2617066710665098,-0.04115253388257618,0.53344953347007,0.8026195558401295,1.6615408577320983,1.6992231242580829,-1.1317715253603278,-0.6197979901248241,-0.12938333453771822,-0.6501248291409156,1.1255759454653291,-0.5762820766324617,0.45531370485875633,2.469941145403455,0.8366632208647284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.675,1.0,0.0,0.0,1.0,0.36338284379013347,0.012022073390481091,0.6087340589020795,0.9808754626318148,0.09910516410467454,0.004866689158421157,0.16744494196976625,0.8072479524054524,-0.1560012157478673,-0.03405489084090325,0.12804186643719628,-1.2122485248796202,-0.0853371821042874,-0.669013501074575,-0.03979080582074563,-0.05828769711095614,-0.35275908354866975,1.1834846533821661,-1.3107508529954255,-0.25978767904045125,-0.8975228153481425,0.6178235364600486,0.26551017950656297,-0.020286761934410587,0.5396492726170292,0.7863152801207041,1.6372557540032298,1.6300980086448216,-1.0774944666124764,-0.7746256768796744,-0.09138074434270393,-0.6186743766794978,1.1074054493396068,-0.5364273067609493,0.45426619011984304,2.5298043383028275,0.6522463813964463,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.683333333333334,1.0,0.0,0.0,1.0,0.37012740787572024,0.013076146387863268,0.608350504041259,0.9809086581450704,0.10042479356382004,0.0001145594352962626,0.16653243554889732,0.7998480584781669,-0.15727915013963528,-0.04356232527375152,0.11193368535345327,-1.1716934864764512,-0.11772485240654662,-0.6625343863840428,-0.026235403561139597,-0.045055941812975835,-0.36150871278611973,1.1763673461461919,-1.3113542678148316,-0.2648165343421993,-0.8883799911680066,0.6134918522641931,0.26927777423517385,0.0010108717558042816,0.5443203064933441,0.7675036001175695,1.6191801090434463,1.5302963475127787,-1.0218736071965073,-0.9381662413578029,-0.052381254723212756,-0.5894514252049787,1.0847500921278308,-0.5101435394720455,0.44629716903924366,2.5727829284628747,0.47140620090622587,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.691666666666666,1.0,0.0,0.0,1.0,0.3768061300742726,0.014097596486451784,0.6079490173131461,0.9809470814886769,0.10164685811820313,-0.0044568744357434105,0.16550189069560015,0.7889830572273206,-0.15735557830640923,-0.0525360785305662,0.0963642186578777,-1.125309905104927,-0.1500014038942054,-0.6562217744059489,-0.012804470670021524,-0.03278275798574316,-0.3697903103352782,1.167848549359536,-1.311623873907479,-0.2696118694605342,-0.879443647146012,0.6093211441355145,0.27294846565721703,0.02259295353997065,0.547506042632133,0.7464953345425873,1.6074039607909765,1.4002858900506827,-0.9653907334494727,-1.111534429508545,-0.010146284720429222,-0.5627657857629731,1.058081192834539,-0.49811656705707197,0.4306257405095004,2.5973641826104537,0.29729376103118765,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7,1.0,0.0,0.0,1.0,0.3833883594611748,0.015085083863792712,0.6075313103453643,0.9809929608240103,0.10277091827620219,-0.008824120494310233,0.16435657598015666,0.7744889850244131,-0.15609348613864782,-0.06081102199584014,0.08145024578889637,-1.0735590948816474,-0.18208411378647588,-0.6500927974749997,0.0005546624520433451,-0.021717843645464457,-0.37759855834361095,1.1578417723210495,-1.311523372560172,-0.27419596410491553,-0.8707453046207643,0.6051899094799086,0.2764548699103322,0.044300274799311846,0.5492752025105305,0.7235520166649922,1.602002261192958,1.2404194357665872,-0.9084473600102494,-1.29578119274798,0.03752409895386499,-0.5388433222741007,1.027846320147816,-0.5009497559781484,0.4065089631495178,2.60224090852463,0.1327917537246881,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.708333333333333,1.0,0.0,0.0,1.0,0.38984183049469023,0.016037863991679144,0.6070995893452601,0.9810486393395106,0.10379731406395108,-0.012965401591874749,0.16309991785645458,0.7562541419306529,-0.15339766087316453,-0.06823952263775943,0.06728560394131328,-1.0168142258628114,-0.21393698892511273,-0.644162574128199,0.013895567016527773,-0.012109100722966714,-0.38493109966878236,1.1462521961470697,-1.310998472258248,-0.2785925914984359,-0.8623128751435484,0.6009719815358787,0.27972361504304233,0.06596363534871448,0.5497192385275445,0.6989056602163646,1.6031993067448846,1.0506257051903904,-0.8513431307307651,-1.4918129893742105,0.09270645705431235,-0.5178096445526648,0.9944617956670299,-0.5191510135014266,0.3732618796637266,2.5863401157550703,-0.01957811622111949,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.716666666666667,1.0,0.0,0.0,1.0,0.3961332447756269,0.016955660959075233,0.6066564095976764,0.9811165473484332,0.1047269841860502,-0.016860241055641156,0.16173531331764548,0.7342380321099328,-0.14922550170932855,-0.07469964335959327,0.05393692294128655,-0.9553385494497835,-0.2455832094404972,-0.638444369804727,0.027274650897791422,-0.004207415225624615,-0.39178761052245703,1.132978222498146,-1.3099782649426002,-0.28282612484745995,-0.8541709413596471,0.5965373925882181,0.28267590123806097,0.08740594339522968,0.5489489005735119,0.6727802478856537,1.6115211356737125,0.8301533031149498,-0.7942583349087406,-1.7003041787934992,0.15727172355793684,-0.4996782990169357,0.9583104842494916,-0.5531065016610159,0.3302745468859958,2.5488739666371654,-0.15777458440559888,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.725,1.0,0.0,0.0,1.0,0.4022290653180594,0.017838522288518364,0.6062044900120759,0.9811991965237624,0.10556126776900643,-0.02048896618979052,0.16026589703564884,0.7084982484833855,-0.14359823715177317,-0.08010295781518172,0.04144210595366643,-0.8892696727015629,-0.27711996579281245,-0.6329495699967714,0.04075425261108965,0.0017267876622824496,-0.39816873858392804,1.117913793167178,-1.3083772768656157,-0.28692056314871817,-0.8463410337393902,0.5917535398415285,0.2852281908244756,0.10844486812600057,0.5470896621207845,0.6454158750915728,1.6279119729225966,0.5774218719416904,-0.7372364520307473,-1.9215938423073098,0.2328000013374032,-0.48434171086170985,0.9197430004328644,-0.603025639508803,0.27702753036862093,2.489430523751447,-0.2804024798628668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.733333333333333,1.0,0.0,0.0,1.0,0.40809660506056966,0.01868666548026088,0.6057464968709544,0.981299196041735,0.10630170362630673,-0.023832149449415255,0.15869424786891914,0.6792280186057535,-0.13661412994199085,-0.08440306707470094,0.029809552429174657,-0.8186066722722096,-0.3087363989690343,-0.6276874385532007,0.05440651711316803,0.005416282640070223,-0.4040748847229695,1.1009516584596908,-1.3060982649203101,-0.2908984866951551,-0.8388418913524327,0.5864869652630714,0.28729302674420465,0.12889645212442047,0.5442755259091308,0.6170962999864438,1.6538081426249103,0.289992564668196,-0.6801615532701066,-2.155555400008473,0.3204733417689587,-0.4715605934096945,0.8790752640216049,-0.6688429984702893,0.21311024914843046,2.4081167356066926,-0.3869456194242016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.741666666666666,1.0,0.0,0.0,1.0,0.4137055066264969,0.019500317071666298,0.605284792256136,0.9814192903277074,0.10694982530948509,-0.026869986732203994,0.15702202155127987,0.646802757986192,-0.12846502551843408,-0.08760689585971511,0.019013650001657,-0.7431916322103507,-0.34073328094668737,-0.622664631663664,0.06831772165483815,0.00655999707341905,-0.40950476447176315,1.0819878698337035,-1.3030360545027997,-0.2947799063722131,-0.8316897793390301,0.5806061565336903,0.28878002831028277,0.14858014705277878,0.5406405684637144,0.5881790516088548,1.6911901816443864,-0.0354024021444032,-0.6227272422417851,-2.401432454673227,0.42091175440083894,-0.46094529107922555,0.8365689559511802,-0.750074619887926,0.13824970183176966,2.3057466307437187,-0.47807576912312966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.75,1.0,0.0,0.0,1.0,0.41902967555079573,0.02027952681230199,0.6048211165467902,0.9815624189173506,0.10750691854434166,-0.029581570805337267,0.15524951176434357,0.614373130798898,-0.12071718616616388,-0.08993675412617862,0.005363939770781284,-0.6758437659545757,-0.3734580501451141,-0.6178844543597198,0.08259302014057447,0.00482624260433017,-0.4144536720936659,1.060927784215137,-1.2990830690136295,-0.2985809082131422,-0.824899075419913,0.5739857215982727,0.2895971884414008,0.16732556263681578,0.5363075964237453,0.5690029207684644,1.7286711948472362,-0.34460065858254085,-0.5541943068629085,-2.6515025964251393,0.551049345043757,-0.44731749210329186,0.7824962950132797,-0.8007510857464828,0.06411801326239197,2.1976955254787223,-0.5413310489140355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.758333333333333,1.0,0.0,0.0,1.0,0.42409654190295476,0.02101759965313152,0.604353415638901,0.9817314367568042,0.10796091238766699,-0.03205641484916446,0.15336301296942675,0.586968027297654,-0.11544024957064179,-0.09206537085943327,-0.015444273276996046,-0.6351303993872134,-0.4069701344156545,-0.6131812496508563,0.09712890823562542,0.0008166527637100364,-0.4187413362528116,1.0377961598932846,-1.2938518987520704,-0.30223519790726794,-0.8186481744221421,0.5672603051045823,0.28984866186465597,0.18520840581075748,0.5316183843151472,0.5724135179368961,1.7457674532209186,-0.5498100956198996,-0.4615734519195991,-2.8894884385218633,0.7302108252513229,-0.42481183449452287,0.7011294524691536,-0.7497780066062298,0.007797603937076403,2.1089627132957567,-0.561420378459927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.766666666666667,1.0,0.0,0.0,1.0,0.4289706289248948,0.021709338034957813,0.6038763858421097,0.9819267783872265,0.10830151870747469,-0.03443094693753347,0.15134428573606187,0.5656221874162635,-0.11235128106887207,-0.0945262836011531,-0.04053907013237812,-0.6163486274197371,-0.4409022101349326,-0.6083442290607716,0.11168914436092311,-0.004337258989334823,-0.42214656295899256,1.012769643573106,-1.286912888592774,-0.3056611054547176,-0.8132135845454271,0.5614894214881688,0.28972714850701875,0.20247494119174506,0.5269505901160798,0.5921094948400363,1.7446733784127844,-0.660501990769259,-0.35179153735725,-3.1062949370671467,0.9447086674057203,-0.39682823759474406,0.5931985855763577,-0.601934199572074,-0.0340666713757265,2.0435328219098214,-0.5527428064831352,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.775,1.0,0.0,0.0,1.0,0.43369476630512804,0.02235786119285304,0.6033863866928175,0.9821471059293005,0.10853346112488733,-0.03675275183074814,0.1491870817601666,0.5484971629977267,-0.11033237880056362,-0.09725837913235247,-0.06612035569457414,-0.605699594470339,-0.4748687389509653,-0.603312758070189,0.1262067978758385,-0.010191713749110947,-0.4246045285420991,0.9860245776088321,-1.2781067542953084,-0.30884900186718034,-0.8087615313292028,0.5572280684450477,0.28928088400839386,0.21926728617592117,0.5224060042070949,0.6170427593587324,1.740411051279659,-0.7357599358690406,-0.23622400234913687,-3.3031664255992776,1.1731782448945482,-0.36802062513604517,0.4683018937462502,-0.4001926708344161,-0.07216720373714458,1.9925415501753125,-0.5381873882534816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.783333333333333,1.0,0.0,0.0,1.0,0.438298703152627,0.02296499252008233,0.6028821146409755,0.9823912236937307,0.10865919095788722,-0.03904076110939462,0.1468893556465919,0.534444995066873,-0.10913086170756472,-0.10008978442806961,-0.09195203962752484,-0.5983428899798398,-0.5087240727780278,-0.5980601830714594,0.1406959952155841,-0.016599924587152166,-0.4260836296648115,0.957716869813118,-1.2673599178445316,-0.31179478254031834,-0.8054085529829896,0.5548195436409286,0.28852436177806634,0.23568396702800026,0.5179808003118551,0.6445996915689189,1.7397468655098325,-0.8006909924414375,-0.11752753308559849,-3.4819376251494183,1.408013361995355,-0.3386712060091557,0.3306846949459641,-0.16275217998032998,-0.10915037586209042,1.9520443099186757,-0.5264261660985725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.791666666666667,1.0,0.0,0.0,1.0,0.4428057181269609,0.023530881025202323,0.6023628503911105,0.9826581552382387,0.10867896913455372,-0.041302770443613385,0.1444503816738403,0.5229082343805825,-0.10869833698442892,-0.10298713430569577,-0.11813841124830045,-0.5923306891896851,-0.5424627941390621,-0.5925694298773737,0.15520257896766904,-0.023536563623134905,-0.42656332076019243,0.9279922838563418,-1.2546398649287192,-0.31449352196733293,-0.8032501197467701,0.5545155321120422,0.287461711077359,0.2518013580078991,0.5136322347721187,0.674008079007995,1.7453133650231363,-0.8654924818263672,0.003271408969212075,-3.6434509099601486,1.6453455426000119,-0.3087072003132396,0.18233139320326552,0.10220318741570145,-0.1458625159992033,1.9201676512591537,-0.5208675916312733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8,1.0,0.0,0.0,1.0,0.4472364159576618,0.024054753799184488,0.6018278038487028,0.9829470296273883,0.10859185142817877,-0.04354188662119234,0.14186983773857156,0.5136870913165577,-0.1090352353314687,-0.1059873919630798,-0.14477307999767647,-0.5868158021588831,-0.5761028671651677,-0.5868267150879928,0.16978455129930303,-0.031024799284258286,-0.4260291061819913,0.8969926879804488,-1.2399374921345314,-0.316939902545539,-0.8023696964296019,0.5565229300978569,0.2860933198447463,0.2676867612156528,0.5092996737846672,0.7049904873593071,1.7581407639113151,-0.9341840059985761,0.12554581881724647,-3.787979966355699,1.8827873311167487,-0.27811325068760717,0.02456342487591856,0.3903590931591516,-0.1825975028789939,1.8963048716578368,-0.523365203731585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.808333333333334,1.0,0.0,1.0,1.0,0.45161087066637906,0.02453540078310733,0.601275899851375,0.9832569982801758,0.10839623939957363,-0.04575904180188018,0.13914755014310215,0.5067843380950119,-0.11016161645535255,-0.10915955201701233,-0.1719213564388718,-0.5813841440057097,-0.6096517088997604,-0.5808195884213853,0.18450492503285762,-0.03910629705644451,-0.42447089044657166,0.8648592844170802,-1.2232600760767733,-0.3191287428121264,-0.8028407293321714,0.561021516998028,0.2844184193627091,0.2834064392021964,0.5049094813765923,0.7374283978018714,1.7786770379278283,-1.0082291635721428,0.24881673505174895,-3.9155160126349564,2.1185200758124223,-0.24691844657696804,-0.14138240293499527,0.698798906462621,-0.21941840959521008,1.880620179211172,-0.5354905709768687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.816666666666666,1.0,0.0,1.0,1.0,0.4559498181763463,0.024971398847385765,0.6007057105733754,0.9835871898019382,0.10809012398774086,-0.047953990087202164,0.13628345456747482,0.5023111633698102,-0.11210632130816425,-0.11258809416305887,-0.1996337354950345,-0.5757916785892438,-0.6430997364031132,-0.5745362417912949,0.19942916859810017,-0.04782861867712733,-0.4218821605977955,0.8317340877698662,-1.2046288242043244,-0.32105520998848847,-0.8047260698118518,0.5681695785389006,0.2824363463514928,0.29903043086917236,0.5003748309350528,0.771257622820265,1.8071398999605304,-1.087975520817549,0.3726826903242608,-4.025941050028139,2.3509055966276815,-0.21517161319673295,-0.31414749547922227,1.0249707072357728,-0.25627471184888395,1.8737271746895734,-0.5589031781565623,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.825,1.0,0.0,1.0,1.0,0.460275251820954,0.02536120088770868,0.6001154397780751,0.9839366879600194,0.1076711826042636,-0.050125693123922524,0.13327762532364598,0.5004258250923053,-0.11489693801550377,-0.11636473808958078,-0.2279540122853531,-0.5698580109165057,-0.6764208177344309,-0.5679652947077142,0.21462392336553313,-0.05723922240340366,-0.41825951227450064,0.7977602669166112,-1.1840783161329786,-0.32271493636540527,-0.8080765209234918,0.5781043621186243,0.2801471741652277,0.3146352254470226,0.49559442840731627,0.8064251486884189,1.843588090867719,-1.1731776046311144,0.4967848351511839,-4.119147374885322,2.5783370165552855,-0.18293909383987117,-0.49218844324498745,1.3662438146816402,-0.2930651119180183,1.876466738582716,-0.5953945679242345,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.833333333333333,1.0,0.0,1.0,1.0,0.46461059013864014,0.02570316803843449,0.5995029337652323,0.9843045211883045,0.1071368203369612,-0.05227245566862154,0.13013032573091854,0.4842535441858185,-0.11362285626653876,-0.11512838610482398,-0.25500047401817416,-0.5496660312163111,-0.7056245473686097,-0.5610958226464879,0.23015563677922882,-0.06738157875431257,-0.41360241334527575,0.7630816315217775,-1.1616565405950696,-0.32410419488581965,-0.8129292105326016,0.5909403087835946,0.2775519278195258,0.3303048765122176,0.4904515881363155,0.8327855882266655,1.827534691269301,-1.226594866889337,0.6059003057048373,-4.253115049432279,2.821761942600509,-0.021753143393581365,-0.645993393499269,2.5090055802031497,-0.353493341538752,1.6709233106467214,-0.38002924756168066,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.841666666666667,1.0,0.0,1.0,1.0,0.4686789791362194,0.02598306446332298,0.5989330993185362,0.9846900068977356,0.1064836096695227,-0.05428055057480636,0.12688756052862088,0.49117624851399355,-0.11910182429848362,-0.11920458992194784,-0.2876611129555129,-0.5442244097824489,-0.7367572714155911,-0.5540855349039364,0.24508283488668814,-0.0776824701848926,-0.4081611738460867,0.7268750160927399,-1.1370489504229702,-0.3230774887552983,-0.818843077481813,0.6199211217886768,0.2742556184729152,0.3424839472911346,0.4892606076146216,0.8746933190083284,1.8812916029514366,-1.3107347420214657,0.7341092083434309,-4.305388323882822,3.041096545161297,0.140951250543756,-0.7131420307837355,3.580285077069949,-0.38993311267615405,1.3348348196188464,0.1282226125127428,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.85,1.0,0.0,1.0,0.0,0.473162695096707,0.026222106481375036,0.5982803432599373,0.9850918148931983,0.10568500161239601,-0.05638820900104594,0.12347131873593699,0.5333792953976111,-0.134271924995402,-0.13311478767778923,-0.32473343680842126,-0.560984049272902,-0.7727783585157743,-0.5465176006630158,0.2615104968284194,-0.08922715778800366,-0.40136725987288524,0.6913251594570639,-1.1109715981757147,-0.32175500737675705,-0.8248149110456638,0.6506117267347604,0.2710530426082566,0.35255212350586507,0.49258863167819456,0.9354684224979337,2.045920342163651,-1.4506803344232262,0.8876169259162947,-4.232501396741153,3.2081600784760145,0.17160288959987113,-0.6985192321506717,3.7267237727172486,-0.3868530018800409,1.0745041800327981,0.6576407233833537,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.858333333333333,1.0,0.0,1.0,0.0,0.4780006848806139,0.02641282034716178,0.5975629845502141,0.9855068030486658,0.10475829162928654,-0.0585388936314954,0.11989678649662147,0.5690845337164478,-0.14726012448610615,-0.14513884650173398,-0.35840486147691314,-0.5665234303814717,-0.8071772866036988,-0.5384943945289709,0.2791815072560823,-0.10186047575861304,-0.39336755841414844,0.656333326147054,-1.0835796157817033,-0.32021744059530044,-0.8304850646843241,0.6820331846672976,0.26780806844158117,0.36039235029168126,0.5002212863376775,0.9870333860450464,2.181585413991646,-1.571804112672324,1.0268937411495715,-4.171834701802804,3.359701223843481,0.19551960707982818,-0.6528779200749457,3.7841568914565493,-0.39768689459428685,0.8038795842682755,1.159882960857881,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.866666666666666,1.0,0.0,1.0,0.0,0.4831381866319532,0.026550718715865406,0.5967913341739589,0.9859341542531024,0.10370161617829671,-0.06069387867231472,0.11617259302880432,0.5992770797166199,-0.1583003547217146,-0.15592951881011285,-0.3914824445874744,-0.5636993687719603,-0.8405664139954433,-0.5300670442289317,0.2978702537282802,-0.11542389299920906,-0.38425236418705905,0.6217945810936838,-1.0549765777783233,-0.3184963472587599,-0.8356962097135796,0.7136810082590362,0.2644249276983518,0.365950116577003,0.5119200143591592,1.0332006453093934,2.29252463778413,-1.6747069332975595,1.1562243411816242,-4.1224168056264725,3.4999358473840614,0.21591098411913978,-0.5916812167162777,3.790055227879705,-0.4192057847376107,0.5302034737858552,1.631137709831758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.875,1.0,0.0,1.0,0.0,0.4885314592150292,0.026632793805898048,0.5959729209283814,0.9863731417961386,0.10251303506507245,-0.06282251767321693,0.11230509364357874,0.6251089474216808,-0.16767792084386535,-0.16571151634509246,-0.4241230207163697,-0.5538971554736984,-0.8731090986776083,-0.5212743837738143,0.31739025121915115,-0.12977225798023903,-0.37409715272778804,0.5876263793866128,-1.0252473516586356,-0.3166189241933148,-0.8403464182962621,0.745200771798626,0.260821305362621,0.36922907485477885,0.5274069148348735,1.0750790673797184,2.382831456600664,-1.7612194536434542,1.2769386260534243,-4.081936340516985,3.6306082126495376,0.23325481817089821,-0.5199376633289243,3.7583361207639676,-0.45011565562793177,0.2595846166292515,2.066128869190371,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.883333333333333,1.0,0.0,1.0,0.0,0.4941454644339151,0.02665684267636445,0.595114676530001,0.9868230319958665,0.1011913348238514,-0.0648974373867694,0.10830023037803574,0.647518822051214,-0.17561933493611043,-0.17452646606782735,-0.4562779466170509,-0.537689118209269,-0.9047634173700551,-0.512149059772603,0.33758411133829125,-0.1447775505599333,-0.3629700537528353,0.553762308751734,-0.994466440900831,-0.3146087669559116,-0.8443618374357283,0.7763199436051024,0.25692300010455293,0.3702765268541572,0.5463554955123321,1.1132865297874006,2.4556990230007494,-1.8335160474794965,1.3897675094298112,-4.048649843658785,3.752620157658073,0.24798639072616813,-0.44035109270655903,3.6970321201403,-0.48953370427597287,-0.0036120028764830003,2.459664074131027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.891666666666667,1.0,0.0,1.0,0.0,0.4999522688072545,0.02662122828643272,0.5942236217622916,0.9872831121737697,0.09973593658736288,-0.06689264521464282,0.10416416555710753,0.6672934923508478,-0.18230469652065912,-0.18236206563935256,-0.4878715240994439,-0.5153187450412895,-0.935427466148291,-0.5027196082773576,0.35831856826916364,-0.16033085877156397,-0.35093436090395785,0.5201488819922997,-0.9627036823643343,-0.312485817681212,-0.8476856031747048,0.8068179738009643,0.2526624102913548,0.36916887480683747,0.5684013160703906,1.148251448423866,2.513819289193321,-1.8938752214998573,1.495223617332373,-4.021091051723461,3.8662418619661088,0.26052631894828204,-0.3546189794404242,3.6114287739095596,-0.5366945385010108,-0.2566799590030511,2.808190635829493,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9,1.0,0.0,1.0,0.0,0.5059299313565256,0.026524801683642935,0.59330700871194,0.9877527191499665,0.09814683870473379,-0.0687827540828563,0.09990343640631599,0.6851014119451871,-0.18787507995221914,-0.18919783662405454,-0.518820194141566,-0.4868973440845239,-0.9649969870766234,-0.4930115356322053,0.37948109949151326,-0.17634213758493092,-0.3380496601306291,0.486744124556343,-0.9300290765347292,-0.3102666616401069,-0.8502721537597354,0.8365104231702617,0.2479780911295361,0.36599852753743967,0.593158672776157,1.1802930285385738,2.5594888622405967,-1.944440386356426,1.5937162185617593,-3.9979340726439316,3.9712172121864198,0.2712464560027128,-0.26389679222443174,3.5052628246268758,-0.5908576260722442,-0.4983628363864312,3.110151413145592,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.908333333333333,1.0,0.0,1.0,0.0,0.5120615521727296,0.026366892846414185,0.592372281167656,0.988231255288473,0.09642460788095931,-0.07054267318201352,0.09552493039882823,0.7014917530315145,-0.19243251326814548,-0.19501562202758083,-0.5490354940045369,-0.4524891274058597,-0.993386193433319,-0.4830480578017147,0.4009767159731736,-0.19273819854417107,-0.32437242392792853,0.45351664744823417,-0.896516728827894,-0.3079650434145001,-0.852083883045112,0.8652390208780789,0.2428147831901507,0.3608628275337303,0.6202371729561504,1.209649637695721,2.594586702498898,-1.9870358728703004,1.6855971155458827,-3.9779934849109133,4.066894400312844,0.28044790848380186,-0.16901692718985117,3.381224907904221,-0.6512690335237886,-0.7286317590913971,3.3658595282980786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.916666666666667,1.0,0.0,1.0,0.0,0.5183341776719227,0.026147326693787568,0.591427003238167,0.9887181906392889,0.09457039695473947,-0.07214751727073854,0.0910357911611334,0.7169250544518203,-0.19604494240753786,-0.19980361421660287,-0.5784163314426998,-0.41214221258318695,-1.0205260350701872,-0.4728507083372766,0.4227242111998282,-0.20945940213276926,-0.30995637487153105,0.42044423314116114,-0.8622475031961818,-0.30559252983204355,-0.8530891025462329,0.892864171635332,0.23712360723747294,0.3538546648859164,0.649256331581125,1.236481745920056,2.6206310840706095,-2.0231199957941866,1.771172266029396,-3.960156128169836,4.1522804362115755,0.2883545764650941,-0.07058961383123119,3.24127647342914,-0.7171145077821439,-0.9482872642792295,3.5769612534177564,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.925,1.0,0.0,1.0,0.0,0.5247383898047773,0.02586649838676585,0.5904787796840744,0.9892130449655572,0.0925860305428474,-0.07357254861281269,0.08644338442646657,0.7317214171432261,-0.19874035687818042,-0.2035402028890535,-0.6068573464103493,-0.36591671212399135,-1.0463709697632333,-0.4624400287030471,0.44465390070768374,-0.22645686514074084,-0.29485288616077193,0.38751404531207023,-0.8273120548910344,-0.3031591338067485,-0.8532603766089658,0.9192602954352312,0.23086287472711498,0.3450580397957431,0.6798531938464464,1.2608911918022858,2.6386637575590224,-2.053694883158738,1.8507271540352577,-3.9435252617899987,4.226238802663265,0.2951104435895313,0.030886489541077644,3.0867073580671933,-0.7875220383319192,-1.1588799448625908,3.7462349435148434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.933333333333334,1.0,0.0,1.0,0.0,0.5312663397876811,0.025525345542298204,0.589535286146149,0.9897153724745856,0.0904739807088803,-0.07479332000456618,0.08175511963879499,0.7460676510346581,-0.20051016583532663,-0.20618768873489557,-0.6342408868447738,-0.3138883964191275,-1.070893897275719,-0.45183585514057184,0.4667019404924786,-0.24368765018541488,-0.27911092230427675,0.35471881211132783,-0.7918101898184607,-0.3006740224388847,-0.8525743277205483,0.9443092942697853,0.22399823993194096,0.33453999913820653,0.7116935806397057,1.2829173766370905,2.6492925401382683,-2.0793642156962617,1.9245240751020631,-3.9274336689120215,4.287592094852209,0.30077903119948624,0.13496328814573522,2.918254157986062,-0.8615458602968151,-1.3624519783964995,3.877150303533259,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.941666666666666,1.0,0.0,1.0,0.0,0.5379114684714748,0.02512546348809961,0.5886042615162531,0.9902247182696249,0.08823751866941298,-0.0757856480273605,0.0769784592082755,0.7600778866626003,-0.20132239168439006,-0.20769525612769546,-0.6604310189205337,-0.2561440059818714,-1.0940735864306141,-0.4410580724257623,0.4888087763766549,-0.2611129354023452,-0.2627774849090709,0.3220568174968699,-0.7558521866434976,-0.29814614995342376,-0.8510109884732036,0.967897864734999,0.2165037770555014,0.32235050682246813,0.7444723655720007,1.30253931573183,2.6528628902074147,-2.1004720913268593,1.9928045093866664,-3.911287516070041,4.335081530791753,0.3053657007383115,0.24122635772387824,2.736302985662551,-0.9381069296013517,-1.5611229953965888,3.9732571480255285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.95,1.0,0.0,1.0,0.0,0.5446675882776556,0.024669119164994438,0.5876935845109068,0.9907405802179574,0.08588072518098118,-0.0765257243458349,0.07212085181728296,0.7737618411709785,-0.20112448567879146,-0.20798656324115256,-0.6852883667463752,-0.19279430113801976,-1.1159002409448842,-0.43012686654504134,0.5109163219959355,-0.27869551837419587,-0.24589751381449898,0.2895306868434938,-0.7195588309719315,-0.29558459409324617,-0.8485538884251503,0.9899143440308278,0.2083631244385851,0.3085212825482634,0.7779145331067978,1.3197041612433724,2.6494220515557054,-2.1171267454391076,2.055819363917785,-3.8946390115431906,4.367474035347687,0.30883781882134254,0.34923170916675517,2.540903623650026,-1.0159882946160292,-1.7570829399755472,4.038119515263261,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.958333333333333,1.0,0.0,1.0,0.0,0.551528083669278,0.024159271660931243,0.5868113583654194,0.9912623630661727,0.0834085305067851,-0.07699020611580253,0.06718967756056884,0.7870438703820927,-0.199851306117095,-0.20696015208798668,-0.7086675147692483,-0.12397085747007869,-1.1363721331551806,-0.4190630030717061,0.53296581056925,-0.29639838115966366,-0.22851382884377447,0.25714616730448336,-0.6830609527210362,-0.29299885297306805,-0.845190459987091,1.0102462584624994,0.1995706388119009,0.293065791156209,0.811774357493055,1.3343307277908767,2.6388065055072274,-2.129315409656831,2.1138301535231525,-3.8771556600293655,4.3835909668284305,0.31113821038414646,0.458479147351325,2.3318610989378508,-1.0938242972081136,-1.9524460498823781,4.075095730144782,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.966666666666667,1.0,0.0,1.0,0.0,0.558485338002444,0.02359958542535533,0.5859660053233511,0.9917893283291265,0.08082673810601652,-0.07715630313652233,0.06219221419729798,0.7997913133182852,-0.19743481933247303,-0.20449180196692776,-0.7304220782346219,-0.049826388631552795,-1.1554884645520753,-0.40788802108186006,0.554896430421056,-0.31418410853514306,-0.21066701125577977,0.2249114258430044,-0.646498981524791,-0.2903989572535104,-0.8409125693026283,1.028778695679792,0.19013271948511654,0.27598051505022375,0.8458327952758775,1.3463214904260923,2.6207284851905754,-2.136977892512001,2.1671163554456663,-3.85854863261273,4.382298131876817,0.31221072163371777,0.568410527658878,2.108831260096684,-1.1700776933769264,-2.1490986257458333,4.087143908328397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.975,1.0,0.0,1.0,0.0,0.5655304380473876,0.022994427866396425,0.585166373671897,0.9923205402801717,0.07814201461565994,-0.07700188059462529,0.057135639274398034,0.8118263678624218,-0.19381214512336367,-0.20043614597965903,-0.7504120447827798,0.02946304531540743,-1.1732456482537512,-0.39662431156460454,0.5766446186557596,-0.332014679368197,-0.19239522291968003,0.19283702342760453,-0.6100226505230892,-0.2877953409458394,-0.8357169511927763,1.0453934461307774,0.18006934392228546,0.2572474807271118,0.8798934226318617,1.3555778695754517,2.5948262048252357,-2.140061265149601,2.2159854995031125,-3.8385437663883604,4.362515205868087,0.31202424179890387,0.6784056095400803,1.8713783966775255,-1.243040153582294,-2.3486335856284617,4.076753459474349,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.983333333333333,1.0,0.0,1.0,0.0,0.5726528284435851,0.022348828599327675,0.584421840065792,0.9928548122803155,0.07536184788547293,-0.07650557190090529,0.05202702262812551,0.8229285488687577,-0.18893217124992984,-0.19462850732545067,-0.7685103731253857,0.11369750648693468,-1.18963504610719,-0.38529505658893587,0.5981435338348099,-0.3498517962876364,-0.17373391959739456,0.16093569640319838,-0.5737903947603229,-0.28519855322352866,-0.8296058091436269,1.0599683356244174,0.1694153835920783,0.23683662195641605,0.9137786862671167,1.3620139137425646,2.5606965717133545,-2.138573976726539,2.260780492029399,-3.816890258618717,4.323251967793487,0.3105930892669173,0.7877787029014205,1.6190061842540038,-1.3108584356147546,-2.5523366396078435,4.045945477813442,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.991666666666666,1.0,0.0,1.0,0.0,0.5798400844284051,0.021668418531534284,0.5837424112193146,0.9933906524320237,0.07249447716680991,-0.07564689010982553,0.04687334485541823,0.8328426494256544,-0.18276206741491505,-0.18688840571198156,-0.7846091884300372,0.2026547885553594,-1.204637923786904,-0.3739240796688951,0.6193228948509821,-0.367657578980306,-0.15471554805252338,0.12922218578395925,-0.5379684510598645,-0.28261878945805746,-0.8225873061444193,1.0723768825350108,0.15822170332870622,0.21470853673364773,0.9473258472620857,1.365568394530362,2.5179312583626734,-2.132629776470485,2.3018831098203743,-3.7933678546013576,4.2636508931105,0.3079982253408464,0.8957919964040673,1.3511851893676452,-1.37157214677699,-2.7611589538561914,3.9962597343828943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0,1.0,0.0,1.0,0.0,0.5870777256971899,0.0209593394765734,0.5831388204829132,0.9939262111557365,0.06954879202914434,-0.07440633203042624,0.041681531388445596,0.8414528459942514,-0.17519910311384607,-0.17473141914071075,-0.7988994472465245,0.30686926344820076,-1.2186824044978708,-0.36253558334676317,0.6401090548075211,-0.3853956258954778,-0.13536920110038833,0.09771289882650909,-0.5027295465418146,-0.2800652494678479,-0.8146759425368925,1.0824880887805448,0.1465558478124618,0.19081730605881286,0.9803830151734982,1.3665080447221645,2.464623700688877,-2.137994112077698,2.3394777526883277,-3.77219402958802,4.169392577867955,0.3074612081999739,1.0088780870928327,1.0365439661004228,-1.428302796233113,-2.9846341181384144,3.9072838897036344,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.008333333333333,1.0,0.0,1.0,0.0,0.5943462998241114,0.0202243631040413,0.5826606695250529,0.994466053718601,0.06652893958938357,-0.07267599565545814,0.036460497174275325,0.8481685603092528,-0.16606178724923856,-0.15568802466559328,-0.8112723399997741,0.4366189339659665,-1.232708841185846,-0.3511489455901924,0.6603999565291301,-0.40329081418160095,-0.11572425217438459,0.06635228529082558,-0.4684785747620652,-0.2774944359880579,-0.8057726713595388,1.0896526153033512,0.134416656724821,0.16496463476467416,1.012447245423813,1.3650481400394876,2.3989400325456267,-2.1715151397787213,2.374439921077557,-3.7580036944977953,4.024804186969423,0.3116726551352311,1.1316014252607287,0.6446600465172514,-1.4837924117877266,-3.2339192404330466,3.76152999170682,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.016666666666667,1.0,0.0,1.0,0.0,0.6016169096991795,0.019469020173195285,0.5823547672933342,0.9950132968864731,0.06344250933357323,-0.07035068961137847,0.031214860243855794,0.8516487836520529,-0.15533116032716704,-0.1322274812988622,-0.8210198835015173,0.5789018165228218,-1.2468150692962487,-0.3397847810127717,0.6800913886832816,-0.42158754489178984,-0.09579520241576238,0.035079503918212504,-0.43564947675899085,-0.27487070521559404,-0.795815918782547,1.0932324228891657,0.12182597428266637,0.13691865205159542,1.0430751817019452,1.3607979081416588,2.3219638698466816,-2.217040536109478,2.4086184928844405,-3.7471672793207236,3.8446085919596373,0.31654322551600833,1.25229976849772,0.21121801323943146,-1.5294636225678007,-3.5013790838551055,3.588210421395752,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.025,1.0,0.0,1.0,0.0,0.6088560120181343,0.018704322488258283,0.5822243497716311,0.9955618524347694,0.06030458226411897,-0.06742997557435698,0.02594520627981051,0.8511427894590248,-0.14325668884313225,-0.10737674235875443,-0.8278982846535632,0.7175086617203763,-1.2599939594772356,-0.32846898045449807,0.6990993543599081,-0.4402414897834256,-0.07558061062631058,0.0038994973021468566,-0.40440176489607127,-0.2722187155627911,-0.7849010085512435,1.0931729155240084,0.10892559634869099,0.1066083167004224,1.0722507524470755,1.3536464196019338,2.2346110552126763,-2.251006480307426,2.4432082870592655,-3.7351628995641337,3.65287789319147,0.3183222466112634,1.3601608644213137,-0.22009945879011283,-1.55486711517286,-3.7723828426245825,3.416884772083155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.033333333333333,1.0,0.0,1.0,0.0,0.6160319630216956,0.017940604246848013,0.5822650940898204,0.996102794799387,0.05712969724857649,-0.063943578873855,0.02065523193172203,0.8467710891992822,-0.13019987578679343,-0.08175633318277221,-0.8321674327415045,0.8477506017056864,-1.2711500765291164,-0.3172240073527395,0.7173349062701595,-0.4591043195635803,-0.055075064298107955,-0.02717321107452306,-0.374768178539133,-0.26956533443873965,-0.7731465710421918,1.0895640985759971,0.0959115223631187,0.07404560467451905,1.1000232612366645,1.3439409845933203,2.1370763129925097,-2.2660837912680276,2.478407443164629,-3.721000282689452,3.4603898545264733,0.3173776789979943,1.454234632690743,-0.6384493599183916,-1.5556866737790807,-4.038637907488697,3.250566886099624,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.041666666666667,1.0,0.0,1.0,0.0,0.6231169260083618,0.017186649822957745,0.5824716630085355,0.9966263367395108,0.05393097216506223,-0.059930838691050356,0.015352189826944024,0.838831136767422,-0.11651692081174217,-0.055602658388841965,-0.8340919246619255,0.9681634092556796,-1.2794995329646548,-0.3060699640446094,0.7347172929097833,-0.47800955297122605,-0.0342738199069001,-0.05811717407601067,-0.3467286006539634,-0.2669290875794912,-0.7606637646730644,1.0825320928587019,0.08299748511903965,0.039297684908944114,1.1264268672154025,1.331956994938468,2.0308191153388466,-2.2621862881863675,2.514139835930922,-3.703747449190245,3.2713989223417363,0.31474437925225973,1.5357231866727572,-1.0411276283686322,-1.5311066164900962,-4.294526002651975,3.0868120127271714,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.05,1.0,0.0,1.0,0.0,0.6300866102904371,0.016449633681621723,0.5828384742709176,0.9971226576339808,0.05072001863506729,-0.05543434724803746,0.010045819432746076,0.8276440856203054,-0.10253654076887694,-0.0291210201826151,-0.8339495792145593,1.0782329725777033,-1.2845513139077775,-0.295024724103765,0.7511818915258069,-0.4968074243666864,-0.013172733699259254,-0.08890233522769381,-0.32024486316677075,-0.2643195947845353,-0.7475511845976458,1.07221197143652,0.07039307875495043,0.0024701712969861394,1.1514701281154507,1.3179876533139778,1.9178357752981778,-2.241639829359341,2.5503529644590226,-3.6822867519876397,3.087347844692443,0.31143412962820527,1.606274901561744,-1.427434757965611,-1.4823695729760127,-4.535832828168829,2.9226279136348055,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.058333333333334,1.0,0.0,1.0,0.0,0.636920439742029,0.01573525817260812,0.583359826476646,0.9975823210026583,0.047506844768862806,-0.05049824937240586,0.004747560865224608,0.8135231872747836,-0.08855295144855257,-0.002534378279426694,-0.83202497296527,1.1777178100203967,-1.2860346099066462,-0.2841035031560431,0.7666812224980862,-0.5153702167938817,0.008232062834083606,-0.11948861994247133,-0.29527280324242267,-0.26173851875235443,-0.733892516313702,1.058741513559275,0.05829132556943944,-0.03629952889386969,1.1751373324426493,1.3023647664534221,1.8001407154333138,-2.2071721974023375,2.5870425622399833,-3.65537208949166,2.9084338799740284,0.3082798263011399,1.6676372937327688,-1.7971370395933084,-1.411992936528508,-4.7592091469469375,2.755536413349189,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.066666666666666,1.0,0.0,1.0,0.0,0.6436008652265478,0.01504787878440688,0.5840296469826493,0.9979965544417082,0.04429999009032008,-0.04516754333311299,-0.0005303130458465732,0.796733735300017,-0.07482504076533213,0.023909628339760014,-0.8285885865644436,1.2664681603634051,-1.28387239980853,-0.27331864466287464,0.7811842367830288,-0.5335936276567254,0.029944642338073795,-0.14982520338588814,-0.2717709651672036,-0.2591815976795163,-0.7197572297020997,1.042259687443298,0.04685986314614197,-0.07684998115212949,1.1973957350046038,1.2854439176394294,1.6796012360310364,-2.16142569171063,2.6242462603475207,-3.6216925518245717,2.734069854965922,0.30587763038174454,1.7214720391608695,-2.1500777978801677,-1.323295809337815,-4.962104746194483,2.5838765691107524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.075,1.0,0.0,1.0,0.0,0.6501128731456193,0.014390657132587014,0.5848413232970607,0.9983574498528892,0.041106613634360224,-0.039487895070519266,-0.005775360340882474,0.7775097084869702,-0.0615765352280461,0.04994590837822795,-0.8238988198429356,1.3443482506883955,-1.2781352163130755,-0.2626794378620526,0.7946745764319368,-0.5513939783223922,0.05196950050654228,-0.17985016247288085,-0.24970497232632397,-0.256640558245992,-0.7052013156610208,1.0229068835946056,0.036236395413809186,-0.11900127466377775,1.2182019419278285,1.2675979015073946,1.5578721747862478,-2.106660284356612,2.662016747407279,-3.5798739791220924,2.563186792023788,0.30460497740635417,1.769327304367001,-2.486025486069061,-1.219949521475095,-5.14258274520903,2.4067141272483905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.083333333333333,1.0,0.0,1.0,0.0,0.6564435514631791,0.013765692241582812,0.5857875401877972,0.9986581156713854,0.03793257669656164,-0.03350561160066247,-0.010975501448683898,0.7560629366236358,-0.04900008403811396,0.07529519191377226,-0.8182014972115331,1.4112129109901401,-1.2690077427607287,-0.25219201297108473,0.8071487730294663,-0.5687046323960022,0.07431158812819512,-0.20948976970458968,-0.2290511853001405,-0.2541048480560771,-0.690268441295983,1.000825929342147,0.02652737112155705,-0.16255969357227998,1.2375076371254103,1.2492107097779632,1.4364056212041465,-2.04470733447937,2.7004006785526298,-3.5284329495151816,2.394282145377536,0.30465188335592863,1.8125911917337012,-2.804596260969323,-1.1056302072084248,-5.299224723041293,2.223751375764822,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.091666666666667,1.0,0.0,1.0,0.0,0.6625817411504146,0.013174116830464913,0.5868601262727899,0.9988927954055917,0.03478249530426371,-0.02726766636946008,-0.016119420028709964,0.7325932912404255,-0.03726235122412411,0.09966748142542872,-0.8117332292738729,1.4669027091882225,-1.2567577071387122,-0.24185925936575323,0.8186146701186726,-0.5854724338970484,0.09697617848241945,-0.23865737829813388,-0.20980026990336503,-0.25156302685672655,-0.6749914624654592,0.9761636125784502,0.017809225293668775,-0.20732168671446596,1.2552644648572422,1.2306765019035888,1.3164803659203028,-1.9769896499997053,2.739418822863338,-3.4657304951042627,2.225414932799919,0.30606556158813636,1.8524500041468617,-3.1051999696881327,-0.9837553395588212,-5.431057949993084,2.0352273939818666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1,1.0,0.0,1.0,0.0,0.668517764026083,0.01261615313175848,0.5880499162125032,0.9990569600414201,0.03165975818271475,-0.020821725689599946,-0.02119684148412702,0.7072969875237133,-0.02650909235286485,0.12276630738467119,-0.8047254603156875,1.5112484595562923,-1.2417086383684004,-0.23168073793935826,0.8290901124614714,-0.6016544598959973,0.11996856850925075,-0.26725194462299406,-0.19196093642014184,-0.24900375536294148,-0.6593942745602019,0.9490725965140115,0.010131448795576698,-0.2530773260721647,1.2714280936917748,1.2124007369032725,1.1992318869279006,-1.9045666658247673,2.779046166882448,-3.389937626980024,2.0541846074698826,0.308797886879178,1.889848153552962,-3.3869972659684255,-0.8573079968263165,-5.537505031527463,1.8418229127357177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.108333333333333,1.0,0.0,1.0,0.0,0.6742432068068911,0.012091131879194786,0.5893466360524514,0.9991473781027923,0.028566516584073137,-0.014216144402572198,-0.026198707550914087,0.6803723344975845,-0.01686939345385048,0.14429387989111714,-0.7974074672697963,1.5440815231207698,-1.2242182197227078,-0.22165258041736535,0.8386018682341376,-0.6172152116607945,0.14329361459712692,-0.29515633874780095,-0.175563859778867,-0.24641639540874025,-0.6434939932395765,0.9197136581456431,0.003520758679896832,-0.2996134372399237,1.2859615134028375,1.1948011085036176,1.0856769235307229,-1.828189223535206,2.8191926708910025,-3.299022645992015,1.8777195434993683,0.31274813504832244,1.9254493598932365,-3.6488625774569328,-0.7287429261069357,-5.61835234592233,1.6445694188906312,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.116666666666666,1.0,0.0,1.0,0.0,0.6797507441387938,0.011597484784077574,0.5907388190796791,0.9991621641585328,0.02550365827198309,-0.007499910168020215,-0.031117271803344167,0.6520235798560116,-0.008458554277400172,0.16395696397859646,-0.7900073681584544,1.565247493552105,-1.2046627702054977,-0.21176738613096463,0.8471847278536501,-0.6321242802882507,0.1669551130241008,-0.32223565538952764,-0.16066561069515237,-0.24379128644546944,-0.6273034518953147,0.8882582202230627,-0.0020142666395388956,-0.34671653183753687,1.2988375840066186,1.1783064396284226,0.9767311795610967,-1.7483543828361703,2.8596855260756886,-3.190765802719097,1.6926949653906087,0.3177964515344289,1.9596002870054807,-3.8893483846899746,-0.599960214883396,-5.673728475863617,1.4447579873119976,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.125,1.0,0.0,1.0,0.0,0.6850339952134702,0.011132724140276124,0.5922137584231734,0.9991008043096319,0.02247077989720533,-0.0007225260640477438,-0.03594614070588423,0.6224653937765487,-0.0013795392208467774,0.18147266733496964,-0.7827509638424414,1.574619470067729,-1.1834254748025164,-0.20201413975689164,0.8548807212268226,-0.6463544513747307,0.19095504003172173,-0.3483357687931192,-0.14735227702235684,-0.24111978788316643,-0.6108339884561518,0.8548911850674769,-0.006478578234826434,-0.3941755785043173,1.3100408131913708,1.1633520210241706,0.8732223711795672,-1.6653493835701183,2.9002510742998795,-3.062795967313853,1.4953886786798116,0.3238273254101909,1.992298150901315,-4.106638897748014,-0.47232527679697794,-5.704075881464203,1.2438461692054137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.133333333333333,1.0,0.0,1.0,0.0,0.6900874429230656,0.010693419518444694,0.5937574908730935,0.9989641564433943,0.01946616970695017,0.0060661552136721435,-0.040680267196784185,0.5919237052621991,0.0042780521791217704,0.19657757881176519,-0.7758584400777749,1.5721169040955305,-1.1608937513538669,-0.1923781857805618,0.8617384340399762,-0.6598801033477527,0.21529263092909878,-0.3732822548447585,-0.13574246605048884,-0.2383941643552996,-0.5940984827136261,0.8198142385939291,-0.009886354586155194,-0.4417844631952736,1.3195683534933755,1.1503721224448515,0.7758867427659699,-1.5792874018094505,2.9405047979365158,-2.9126925487066346,1.281835242562549,0.33073960085522824,2.023166441114721,-4.29852813263683,-0.34673313230991987,-5.710127471871712,1.0433485383468222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.141666666666667,1.0,1.0,1.0,0.0,0.694906342887165,0.010275203873558078,0.5953548744898662,0.9987544207691677,0.016486815029666972,0.012816204769417801,-0.045315966496709055,0.5606453808809072,0.008439620402777417,0.20903291453309325,-0.7695390467842137,1.5577120308102588,-1.1374484853029456,-0.18284127104947745,0.8678121669395887,-0.6726759080715549,0.23996345333066366,-0.39688064460489647,-0.12598835631298103,-0.23560746120224596,-0.5771145477709064,0.7832490495235297,-0.012257463773325098,-0.48934436970217915,1.3274299554971511,1.1397849403031868,0.6853750939166781,-1.4901120659279732,2.979927216973439,-2.738072121007761,1.0480014524308559,0.338452162813494,2.0514331501838945,-4.462339643364522,-0.2236697229891858,-5.692833303331954,0.8447428434993798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.15,1.0,1.0,1.0,0.0,0.6994868613229801,0.009872776534052052,0.5969896278279447,0.9984750828735423,0.013528439113523182,0.01947783202091602,-0.04985082020980726,0.5289107933243108,0.011048999626018227,0.21863202225890854,-0.7639859333025747,1.5314335132642196,-1.1134532501994068,-0.173381770108842,0.8731613522719208,-0.6847153044465523,0.26495808454532277,-0.41891679019488787,-0.11827577517664124,-0.2327532949750747,-0.5599079302105612,0.7454419112045204,-0.013614183302641624,-0.5366650182508061,1.3336474008850319,1.1319745767078422,0.6022473530014949,-1.3975703419882368,3.017837185149286,-2.5367053446202115,0.7900342292616456,0.34690410432377194,2.0759194864258834,-4.594844174853215,-0.10328279523112188,-5.653262926426591,0.6493754485252845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.158333333333333,1.0,1.0,1.0,0.0,0.7038262678143038,0.009479951605783568,0.5986444926749894,0.9981308273873088,0.010585564916696858,0.02600168004958099,-0.05428360589644851,0.4970434549964189,0.012074261510358675,0.22521181069702786,-0.7593696228279532,1.4933731813803477,-1.0892489902625477,-0.16397502810434675,0.877849622822947,-0.6959687471046921,0.2902607397498184,-0.43915906701523333,-0.11282111915862027,-0.2298257261301831,-0.5425158896638084,0.7066683132759761,-0.013978843693843796,-0.5835654184759557,1.3382528796392392,1.1272689151590398,0.5269503809167997,-1.3011716624670444,3.053367612803112,-2.306691846634954,0.5046033446119217,0.3560450082732858,2.095035957468332,-4.692202429327617,0.014529866427421996,-5.592510019761748,0.4583709960157911,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.166666666666667,1.0,1.0,1.0,0.0,0.7079233313398908,0.009089733563635682,0.6003014117597775,0.9977274258349281,0.0076516247735733435,0.03233908632286405,-0.058614161010255426,0.35593317957294285,-0.008619191118039701,0.2447282303430261,-0.7774960162973661,1.3792640941984828,-1.1019594474418204,-0.15459395485619135,0.8819438586205341,-0.706401498821003,0.31584754475870797,-0.45736165430547043,-0.10986571943310922,-0.22681921150385326,-0.5249906642527556,0.6672385373823935,-0.01337201886218459,-0.6298735185801686,1.341286917485295,1.2190755463576437,0.3391434967753715,-1.3639022794542743,3.058691496000716,-1.2118454640172693,-0.6450218471540923,0.39990434599428637,1.9437065246133667,-4.685206349536808,0.16486888308163564,-5.792396761387932,0.4111460999318606,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.175,1.0,1.0,1.0,0.0,0.709947996117229,0.008568654299604133,0.6023245044805621,0.9972736052176877,0.00449341024120335,0.03791980577085172,-0.06314470627711385,0.2230038764690376,-0.02743369703736062,0.2465187656070209,-0.775991506673365,1.288240113900578,-1.1047982532494691,-0.14365710233171936,0.8835020144358698,-0.7187004517622634,0.34123893134983035,-0.45935649141552115,-0.12357148327785514,-0.223160653696945,-0.5101207809202523,0.628581540783696,-0.011231028975816536,-0.6801053644990879,1.3451053146381036,1.279502848972482,0.2953774343896498,-1.7603161979014947,3.023075698508272,-0.1577298131052718,-1.8161611936487838,0.42061053230491086,1.7639988196722667,-4.636623548294428,0.29367129277011855,-5.9751344433026325,0.33856815803315676,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.183333333333334,0.0,1.0,1.0,0.0,0.7118504104247958,0.008112833643751222,0.6041129518945567,0.996769373830869,0.0015324152651052798,0.043494425580069086,-0.06750334835943181,0.2164458608815949,-0.021468797954928807,0.22485942924037178,-0.7414405372041096,1.2721015564988762,-1.0633439128472113,-0.13326890737331665,0.8868668158603616,-0.7357401021193613,0.36623213973384583,-0.45999048452389163,-0.14013507266058894,-0.21980903596543808,-0.49559068392488453,0.589961478244153,-0.008477497316015948,-0.7294590926352125,1.346929720119181,1.2291434240727046,0.48747399355072885,-2.2271281477967286,2.972072341584792,-0.037939185057120905,-1.9980289983673205,0.39459136292201935,1.7509620072132237,-4.61697265101275,0.37528841415291947,-5.814348006883357,0.08330204468187663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.191666666666666,0.0,1.0,1.0,0.0,0.7137848793578695,0.007695675302690735,0.6057454338419351,0.9962256426562888,-0.0013347882388146835,0.0489171200765607,-0.07169241673872916,0.22127081083655675,-0.016242059030456273,0.20988071170871034,-0.7198534790024167,1.224404434049272,-1.0232281618123562,-0.12317137859717428,0.8916265809950487,-0.7558192542255422,0.39077347037624355,-0.45998881116647317,-0.15687196658397715,-0.216584130981578,-0.48093808080003186,0.5516319966001502,-0.004976222073267878,-0.7770111646138105,1.3464936820494682,1.199508470237884,0.6387177765443242,-2.5344056310462793,2.909163839515454,0.033228989847656765,-1.9671824744895068,0.37990381253116157,1.7664350188748779,-4.551567313582936,0.4635198510793734,-5.579957553203374,-0.1770209423917679,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2,0.0,1.0,1.0,0.0,0.7157856690431744,0.007302417242038317,0.6072380991293768,0.9956531972725764,-0.0041295020312959755,0.05407814196413132,-0.07571798026610943,0.2294552733871368,-0.011777215612980466,0.19596061260905345,-0.700332310776257,1.1536185167003017,-0.9845378594602098,-0.11327709953601858,0.8975121121361004,-0.7779801959701326,0.41471820372577006,-0.4594366680264307,-0.17292144723541406,-0.21347730575658538,-0.4661501002769699,0.5141020230177707,-0.0007521664646930588,-0.822458385188602,1.3439793710793182,1.1779382552931486,0.764775667223887,-2.747815906385578,2.8286696225071353,0.10333998885290963,-1.8661040439411454,0.36484046097305045,1.7747025245408954,-4.419700995780799,0.5477244620372083,-5.318703079150686,-0.41211486991524104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.208333333333333,0.0,1.0,1.0,0.0,0.7178671541965391,0.0069234356044288025,0.608586023948412,0.9950629653818439,-0.006861825956054649,0.058897077163464824,-0.07958482626507954,0.2398764714272893,-0.007813883275008843,0.18138561029012842,-0.6814691346146357,1.0649508562890189,-0.9471411460730649,-0.10353907434228847,0.9043728421154468,-0.8016161859986352,0.4379179640846958,-0.4582664780189247,-0.1879737006496629,-0.21050345663202716,-0.45135970539101694,0.47797031333713685,0.004152518960685594,-0.8656562159329886,1.3396251008842142,1.1612532166408216,0.8757151118461959,-2.896219667122193,2.730184491488772,0.1854769353871033,-1.7407938874971796,0.34773809562715086,1.763071218735831,-4.2119138840880375,0.6268675887381833,-5.043302005201951,-0.6185990392768081,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.216666666666667,0.0,1.0,1.0,0.0,0.7200423548903991,0.00655034981204539,0.6097786912836772,0.9944660516224346,-0.009539785874882845,0.0633070075723245,-0.08329758368755659,0.2526586569852009,-0.004194405277420238,0.16572320859252973,-0.6629840757162656,0.9608510290441548,-0.91109149905516,-0.09392287925867156,0.9121073640002036,-0.8262505237555025,0.46022127858391626,-0.45634538576997896,-0.20193467869370038,-0.2076816708294662,-0.43676557996470605,0.4439034582829701,0.009695626680943328,-0.9065134186086345,1.3336693870913714,1.1482972688101678,0.9761272272453114,-2.991200438161805,2.6132732450914986,0.28540727842287894,-1.6100601776832624,0.3282382929439509,1.724675444585383,-3.9196663416393074,0.7010654879706599,-4.758571739080861,-0.7966765222498529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.225,0.0,1.0,1.0,0.0,0.7223266146821671,0.0061750558311061115,0.610803973167762,0.9938736076373328,-0.01217088661948575,0.06724797333822195,-0.08686099033945739,0.26809771760519885,-0.0007941958323767553,0.14885180590194952,-0.6447687072680609,0.8426494990218406,-0.8764534908179651,-0.08440078652878567,0.920641629236202,-0.8514695266346652,0.4814725181695541,-0.45350969004521,-0.21480803694438394,-0.20503281841629464,-0.4226151146479272,0.41264254097648173,0.015836943760196592,-0.9449657449176696,1.3263471588467166,1.1383524351164287,1.068888298598527,-3.0392163985435894,2.477551570715615,0.40566286702776955,-1.4825015867738423,0.3061402534881963,1.653890796304578,-3.5337916243498158,0.7705686522502659,-4.467423378032474,-0.946529442816324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.233333333333333,0.0,1.0,1.0,0.0,0.724737414847432,0.005789553097453058,0.6116490179295813,0.9932966352020686,-0.01476247419742794,0.07066425453592147,-0.09027971523383199,0.28640168900090895,0.0024893249791164834,0.13068278522456495,-0.6267595461474955,0.7111431762310949,-0.8432404674375797,-0.07495033867339775,0.9299221689768458,-0.8769041303978956,0.5015138047625098,-0.4495843379861828,-0.22664303847326442,-0.2025793332713296,-0.40920073335962975,0.3850069312104732,0.022538437551781094,-0.9809704749091758,1.317893896377766,1.1308282546169992,1.156297626610523,-3.045225856363769,2.3229646901342895,0.5468654434346032,-1.3618164586799493,0.2812514358783069,1.5456493250318526,-3.0452430905277716,0.8356409119217183,-4.1724231193696815,-1.0677284517534202,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.241666666666666,0.0,1.0,1.0,0.0,0.7272934119615453,0.0053858790168749004,0.6123002058094197,0.9927457867285545,-0.017321934276463558,0.07350263046317637,-0.09355809339987202,0.3076579780033391,0.005728293952519295,0.11106233221133868,-0.6089360928764689,0.566703427193898,-0.8114121569023065,-0.06555364895183569,0.9399132563463773,-0.9022232909073947,0.5201885963384589,-0.44439526598796664,-0.2375049779223831,-0.20034529448498953,-0.396854292564063,0.36188848946768554,0.02976429229222523,-1.0145061302404976,1.3085516846508263,1.1252361600487302,1.2403960591770846,-3.0134949036049385,2.149930288132631,0.7084419301630296,-1.2486870069806484,0.2533722239227332,1.3959955967090643,-2.446440501388296,0.8965733087078416,-3.876194551862946,-1.1589893031486076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.25,0.0,1.0,1.0,0.0,0.7300135064750524,0.00495593959472054,0.6127426473116278,0.9922311943832198,-0.019857017266354356,0.07571056489807403,-0.09669987782278752,0.32967936047066076,0.008583600208223553,0.09368649188388826,-0.5938322005118252,0.43110212512761126,-0.7797102851571918,-0.05619640267258558,0.9505954366297972,-0.9271290454579779,0.537345976231387,-0.43777697248346564,-0.24745448858960856,-0.19835646287261738,-0.38593414008114535,0.3442329228540016,0.03748132603024512,-1.0455737174402249,1.2985774079919559,1.1239324145472265,1.3141717990925939,-2.9762827202931885,1.9758103864897425,0.8681989018510639,-1.156494449188677,0.22954052255199364,1.2399870404821511,-1.8489869569075101,0.9533752917577664,-3.555985815703564,-1.2703409179895786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.258333333333333,0.0,1.0,1.0,0.0,0.7328899342263601,0.004493886196474018,0.613030341285132,0.9917487439687628,-0.022377918014701775,0.07741715970661758,-0.09970075803628693,0.3491575659632184,0.010799898109458465,0.0841230647352577,-0.5837786151080998,0.33619882716799343,-0.746830977612711,-0.046821442042715246,0.9618161196645872,-0.9518280029122812,0.5531187694466213,-0.4299252842904489,-0.25677988540886104,-0.19651961910912297,-0.3761878418893605,0.3310720401858937,0.045653880488188005,-1.0737725605022237,1.2873793360176666,1.1290933897324271,1.3651191978234145,-2.976605209702472,1.8265411494930017,0.9950724745620554,-1.1062719037578606,0.21844410072988485,1.1400558276600992,-1.4376819201879754,1.0044069047213933,-3.18785988092412,-1.4689268211403395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.266666666666667,0.0,1.0,1.0,0.0,0.7359038767272852,0.0040018034351149735,0.6132480950281634,0.9912858803991795,-0.024884814004543333,0.07883524478356246,-0.10255756244609465,0.3664351545377759,0.013101401235574343,0.08117551409013639,-0.5756098165886261,0.27578609598053316,-0.7139973185764664,-0.03737817951037846,0.9733474232601874,-0.9767391322863525,0.567788328722937,-0.4211924312407647,-0.26589235365223957,-0.19471572786045263,-0.3669332096201437,0.32027155751753533,0.05422144110893501,-1.0987047154556269,1.2740952943062835,1.136809479679955,1.3946015668582135,-3.004982484709484,1.6994734627587849,1.0947373587745013,-1.092979001631439,0.2145259479385475,1.1007060289730142,-1.20821190439646,1.0467717876790668,-2.7971293809405795,-1.7286992608645013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.275,0.0,1.0,1.0,0.0,0.739054705298536,0.0034865134817595295,0.6134271009072859,0.9908387291838958,-0.02736665979843709,0.08003955216395169,-0.10527748483287996,0.3833531907068375,0.016021170785619182,0.0807774231488354,-0.5663923138073408,0.22756808389921765,-0.6825239166670486,-0.027874617381382662,0.9850594791122241,-1.001911044324106,0.5814433271592677,-0.4116796616442072,-0.27499620210271836,-0.1929441866434805,-0.3578427414064769,0.31093517511261937,0.06310007694950578,-1.1203913835179,1.258567681669925,1.143795320199959,1.4108168943376387,-3.032176651167633,1.5796045384884883,1.1861171391840952,-1.0967262481445017,0.20983673060014196,1.0893588056451187,-1.0533346157014012,1.079620185077865,-2.4121845115438445,-1.9931833818601774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.283333333333333,0.0,1.0,1.0,0.0,0.7423454393807859,0.0029518796745830567,0.6135795435620283,0.9904067888671075,-0.02981746411433164,0.08105580762843982,-0.10786689700740482,0.4005038525383726,0.01936848656689248,0.08141488386506655,-0.5564066807317272,0.1832753623634517,-0.6522515562989246,-0.018314924173712475,0.9968610381658147,-1.027275409805813,0.5941150710310785,-0.40142381225436313,-0.2841711244546479,-0.19121844901711693,-0.3487772295260584,0.30271598058917865,0.07221511086023276,-1.1389077906480243,1.2408755712752806,1.1506306350599653,1.4171766367283944,-3.048803240834057,1.4622468582684789,1.274536891123802,-1.1067977893667968,0.20366018402532993,1.0899770022383415,-0.9264721175899304,1.104292645794266,-2.0378883957055427,-2.2429276691515954,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.291666666666667,0.0,1.0,1.0,0.0,0.7457807283683274,0.002399163256184048,0.6137102757798377,0.9899909616828849,-0.03223508017712086,0.08189054000125424,-0.11033011764485329,0.4181894138783762,0.022944669782362884,0.08238486951282559,-0.5459462669968678,0.13901854483482848,-0.622744427746475,-0.00869744013038324,1.008679089724364,-1.0527244316713402,0.605814108130409,-0.3904373801254772,-0.2934428319254983,-0.18954985024305834,-0.3396764580358379,0.2954939731527872,0.08150495437941022,-1.1543561901129924,1.2211855538507317,1.1576974745879751,1.4155186669660136,-3.051194019044594,1.345065440045674,1.3624530429501247,-1.1180608668806058,0.19621642885419677,1.0947903451364327,-0.8052189634741336,1.1221230981205232,-1.6772859992338773,-2.469302720174036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3,0.0,1.0,1.0,0.0,0.7493660191683139,0.0018276447733759345,0.6138195144386791,0.9895932422889915,-0.034619005861022775,0.08253762687354456,-0.1126688927912638,0.43651704869729707,0.02662387022971853,0.08334516901615993,-0.5351884775928792,0.0930133359219294,-0.5936310948645463,0.0009800337360871094,1.0204530159485816,-1.0781286434565562,0.6165328283651731,-0.3787162615385277,-0.30280547223599136,-0.18794817520288032,-0.3305307237737845,0.2892956645312764,0.09091716249557481,-1.1668625573019222,1.1997205259390467,1.1650849579567126,1.4068619129619009,-3.038379469083421,1.2270122781464243,1.450729989025178,-1.1277601183337316,0.18779553803322357,1.100103903259988,-0.679111265956307,1.1340111706473497,-1.3325011602295955,-2.6688221386767896,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.308333333333334,0.0,1.0,1.0,0.0,0.7531063450565101,0.001235994413649245,0.6139067330422336,0.9892157145877903,-0.03696993588252143,0.08298907632624099,-0.11488388514132396,0.4553438869139394,0.030388809991430635,0.0843507301864447,-0.5243938351835026,0.04591096885307924,-0.5649628653901401,0.010720642502228638,1.032126788273729,-1.1033640894893972,0.6262643127661828,-0.36625854697505755,-0.31223883389772716,-0.18641992460917128,-0.32134139298150477,0.2841754520535154,0.10040514055686604,-1.1765645427834857,1.1767051848727852,1.1729393696241077,1.3913028232946267,-3.0123098710045104,1.109321422818379,1.538039127550197,-1.1348111614463408,0.1787347362828151,1.1068632525961375,-0.5514950850159461,1.1403475124986509,-1.0041168477834983,-2.844267125901525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.316666666666666,0.0,1.0,1.0,0.0,0.7570049988710638,0.0006239054305912106,0.6139738799048848,0.9888594884818278,-0.039288979022676876,0.08324432409035655,-0.11697722288516645,0.4744972401233565,0.03424229121292237,0.08542792597077778,-0.5135322507918358,-0.0018424183750148926,-0.53684091699248,0.020529023229822238,1.0436413963368254,-1.128333807973298,0.6350215187454794,-0.35308227607935777,-0.32171899159343037,-0.18496926293150007,-0.3120830028971822,0.28010407978101065,0.10992295437055233,-1.1835978380983139,1.152316073840688,1.181093309036186,1.3688297392720994,-2.974494268262311,0.9928619063828892,1.6231897810646578,-1.1380365049097896,0.16901918545174366,1.1161549326527076,-0.4256602710208113,1.1412163808768148,-0.6925856540133957,-2.997936204817586,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.325,0.0,1.0,1.0,0.0,0.7610643920044935,-9.074012313233188e-06,0.614021663124807,0.9885259138524911,-0.0415762998820324,0.08329896778348847,-0.11895045563813925,0.49389635315708297,0.038149880081203374,0.08643276942382817,-0.5024287491550348,-0.050862500008679035,-0.5091559246746644,0.03040553098616507,1.0549406172615974,-1.1529389939604358,0.6428120112058976,-0.33920538395731326,-0.331206108979557,-0.18360293818497556,-0.3027388107706263,0.27708111420316855,0.11942541357147962,-1.1881076370170423,1.1267395814591588,1.1891838367771548,1.3396987996345366,-2.925036420024907,0.8773302150347861,1.7059700996194571,-1.135708212477341,0.1585061402710941,1.1272104051313336,-0.2992034669557142,1.1368469431613615,-0.39874607474376766,-3.129317414440407,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.333333333333333,0.0,1.0,1.0,0.0,0.765286041668999,-0.0006634440601068757,0.614050375957029,0.9882163326634613,-0.04383210717083646,0.0831471982835486,-0.12080467563702885,0.5147080715819307,0.04234798289908598,0.08823970150332511,-0.4890277321191129,-0.11503220365317879,-0.4831300810128427,0.040348753842774816,1.0659697096640677,-1.1770844149737132,0.6496436889960592,-0.32464944108570015,-0.34064746180138605,-0.18232749392698183,-0.29329616281166,0.27511735533174875,0.1288704034232417,-1.19024360601071,1.1001607836000145,1.1944781208813708,1.3000586341386278,-2.833115609685586,0.7478730236479514,1.7878291932964119,-1.0910892178624576,0.14288590772382925,1.1354224926971423,-0.13269114366682655,1.124848674295852,-0.12217590691335545,-3.2176578758123453,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.341666666666667,0.0,1.0,1.0,0.0,0.7696944911588567,-0.0013394695442694594,0.6140721228460523,0.9879408498424728,-0.0460547051901805,0.08266770732247,-0.12254750714901866,0.5384572154774215,0.046909549087791796,0.0914177453362851,-0.4719183371848393,-0.21110766579456175,-0.45991367607621503,0.05031349966752125,1.0766082611639078,-1.2001575874551955,0.6552765616000301,-0.3094082307357064,-0.3493909292772646,-0.1812215063895784,-0.28381510255900727,0.2748695951420548,0.1381728914764105,-1.1901439021322648,1.0731119501956197,1.1947150312116446,1.2473295192393374,-2.6648128251844927,0.5882099818740771,1.8704558275782335,-0.9609586658736258,0.11811079379632106,1.1322100453998951,0.1278125014485143,1.1040312507209193,0.13561707856694305,-3.2342810557553525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.35,0.0,1.0,1.0,0.0,0.7743175472460357,-0.002042003003573237,0.6140951561688256,0.9877109572326778,-0.04825063656333456,0.08171480116989054,-0.12418386490813962,0.5641345061697634,0.05122609703510869,0.09429554161244555,-0.45411454808439367,-0.32885096486487675,-0.4378955445577713,0.06026067102963556,1.0867585349847233,-1.2214979620601214,0.6594471886939605,-0.2934751772927296,-0.3566634395659465,-0.18035898069704315,-0.2744259953883284,0.277247563689224,0.14727092426859034,-1.1879833213679276,1.0462560993374252,1.1930283193068876,1.1879791253814087,-2.4504365681252605,0.4131726799974156,1.9511947653649275,-0.7722539586374377,0.08923193251770989,1.1165072712583357,0.4621070423925955,1.079597298526875,0.3698414865337396,-3.1894754463512642,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.358333333333333,0.0,1.0,1.0,0.0,0.779156406058993,-0.002778766745604619,0.614111659033931,0.9875287140973446,-0.05043191512827099,0.0802550331181877,-0.12570915014020714,0.5897331796118994,0.054917528523049,0.09546297880504546,-0.43777742146655696,-0.45023678218457475,-0.41542711456973536,0.07019730498930271,1.096407913253598,-1.2409981969239499,0.6621627729333204,-0.27688831797962427,-0.3622618285878886,-0.17973430751428324,-0.265206648038035,0.28257137918193137,0.15616617978519173,-1.1839798773567025,1.0199540260897653,1.191800689728062,1.1269919005331452,-2.2325542684215804,0.24403976586945708,2.0250831135989666,-0.5685516107786115,0.061287301884604406,1.0975038041747809,0.8126164538870306,1.0550612247838116,0.5784272760804532,-3.110261083223418,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.366666666666666,0.0,1.0,1.0,0.0,0.7842013831973548,-0.003553827121391584,0.6141146455083597,0.9873923185771452,-0.05260368100960788,0.07829383128510148,-0.12711938460304859,0.614386134231529,0.05803955019013152,0.09474852418635357,-0.4222416072438349,-0.5698128073154889,-0.39197598513228793,0.08012401585843659,1.1055417333269424,-1.2587071998671477,0.6635145181251181,-0.25972379206608015,-0.36613929974559,-0.17933752566563307,-0.2561342653187487,0.29079117125400783,0.1648552780149872,-1.1783428667665867,0.994418414617035,1.1899311283772231,1.0638189779550755,-2.0218758935188452,0.08630339597932357,2.089254038872976,-0.36072762086185595,0.034411041835459844,1.0834269591263097,1.1513365223132888,1.0299606880212941,0.7619902087901131,-3.0065844859502344,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.375,0.0,1.0,1.0,0.0,0.7894398402256142,-0.004370317595700596,0.6140966995135626,0.9872993479043127,-0.054766482090666674,0.07584212054499256,-0.12840795465425953,0.6378327487522141,0.06061216786260917,0.0921124520007606,-0.4069766433476538,-0.686377680881825,-0.3669345368296856,0.09002949046225643,1.1141382295528492,-1.2746961284825973,0.6636011628663091,-0.24206741733174134,-0.36827395560225284,-0.1791607901503589,-0.24714953205259652,0.3017603212204862,0.1733321912522133,-1.171280040543534,0.9698442846572614,1.1863938866206143,0.9974940676982369,-1.8200657907010331,-0.059234247962207665,2.142474951725326,-0.15038282168079897,0.008591018880288459,1.0782999204950605,1.4680480609785918,1.004224627857356,0.9212540321311957,-2.8807347212128787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.383333333333333,0.0,1.0,1.0,0.0,0.7948583198849011,-0.005230609258075439,0.6140515722246563,0.9872467206355265,-0.05691932906386337,0.07291489289099146,-0.1295666661151493,0.659654800391767,0.06286335777151701,0.08814331042006235,-0.39218343648704745,-0.7959353078308272,-0.3410156466757926,0.0998972473021135,1.1221666344552463,-1.289041629712165,0.6625272806590813,-0.22401587620399138,-0.36864568010693666,-0.17919434201762827,-0.23816259997716438,0.31525863893698436,0.18159235514594313,-1.1629886328977335,0.946406169263487,1.1813341669093735,0.9259782661688165,-1.6305644430379962,-0.1888001856801691,2.181081096495943,0.060742717034530935,-0.016135175335468266,1.0898074672822011,1.739663531266823,0.9773872677688039,1.0602641715685168,-2.744372845258045,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.391666666666667,0.0,1.0,1.0,0.0,0.8004405596293873,-0.006131116101896762,0.6139823887843634,0.9872276328813077,-0.0590604010316591,0.06955580973512059,-0.13059655140118248,0.6795421270601657,0.0650248855889239,0.08343171485016969,-0.37772360207746536,-0.8951841124099409,-0.31503838349073654,0.10971839324407932,1.1295712006556629,-1.3018722025332305,0.660454493104973,-0.20571606572347562,-0.36726157698501066,-0.17942970973928338,-0.22898607426455983,0.33075471340826657,0.18962197904836003,-1.153608971017392,0.9241047372362939,1.174648416181028,0.8474873462618193,-1.4554755350985316,-0.30000419251037247,2.2025452464332442,0.27073565044769543,-0.04013231141714979,1.1233965853311911,1.9486051145527539,0.9487244098890885,1.1829445320842158,-2.607939239920405,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4,0.0,1.0,1.0,0.0,0.8061710707313542,-0.007067963212273352,0.6138921769462597,0.9872356747408013,-0.06118441396954981,0.06580652804507822,-0.13149787402546462,0.697574596263107,0.06713609841623203,0.07804369520320065,-0.36312597021863485,-0.984283011073819,-0.28878891853530775,0.11947472090513063,1.13629142355961,-1.3132995552971405,0.6575272107839084,-0.18730678876343732,-0.36413341926614173,-0.17986321387458076,-0.21943932355497786,0.3477353908461969,0.1974044286440946,-1.1432728906963299,0.9029405152648136,1.1656099327307858,0.7616631461747359,-1.293278113570051,-0.39451181442561767,2.207844062129284,0.4786574015157419,-0.06363291634614743,1.1774732530189003,2.098034796814865,0.9182119034691621,1.2904406886103947,-2.471987379018128,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.408333333333333,0.0,1.0,1.0,0.0,0.8120354797147323,-0.008036875750551035,0.6137840193360783,0.9872646432195632,-0.06328549559371915,0.061709024719047934,-0.1322704296679495,0.7138463012556334,0.06924428600478434,0.07205451534181004,-0.3483174463418502,-1.06314346251996,-0.262132124849276,0.1291452254562591,1.1422655864252418,-1.323426837759398,0.6538792961978793,-0.16891866468798755,-0.35928395362641496,-0.1804902583450525,-0.20936152004757816,0.36572196002184765,0.20492551077284607,-1.1321016262072188,0.8829049475859918,1.1539304326558317,0.6684809219862409,-1.1430740240977055,-0.4735923922511076,2.1980951052257827,0.6829205332735322,-0.08650145567680956,1.2493506239400842,2.1925692557845955,0.886156768449381,1.3839346288967702,-2.337599491956359,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.416666666666667,0.0,1.0,1.0,0.0,0.8180204240049006,-0.009033259576370155,0.613660792188725,0.9873086595078793,-0.06535742148799165,0.057305730395861884,-0.1329137749870618,0.7284403554789272,0.07138964008397435,0.06551767794302168,-0.3332551591377936,-1.1316897636467789,-0.23497143765123998,0.13870689478272782,1.1474327722593807,-1.3323507890321022,0.64963400424639,-0.1506718703430076,-0.35275141037824953,-0.1813049048025276,-0.19861681315597646,0.3842782117759402,0.21217370811825095,-1.1202073135480504,0.8639805237322076,1.1393886183152557,0.5681169963015309,-1.004152983133424,-0.5385574459861187,2.174667922491191,0.8814975220937626,-0.10856434805534387,1.3358623483100063,2.2375904347544817,0.8528801478597986,1.4644152267682076,-2.205771684076643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.425,0.0,1.0,1.0,0.0,0.8241133542469161,-0.010052271183915659,0.6135249294547265,0.98736231376563,-0.06739371362244051,0.052639330893262434,-0.13342731940263247,0.7414219603000666,0.0736036222033298,0.05846771422713168,-0.3179044866551908,-1.189903356568422,-0.20722762157356744,0.14813503576151335,1.1517342030302673,-1.3401627208116218,0.6449033387647773,-0.13267419931313437,-0.3445923282581856,-0.1822996641459749,-0.18709714757574472,0.40301513393442234,0.2191401799038427,-1.107694705761082,0.8461420861847144,1.1218000294539976,0.46087741650801206,-0.8758906733929228,-0.5907810005035241,2.1391511097990263,1.072064738043338,-0.12961930593135995,1.433632226873266,2.2388228326095083,0.8187012941324906,1.5326823624593278,-2.0773453137148867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.433333333333334,0.0,1.0,1.0,0.0,0.8303023312700392,-0.0110888903402612,0.6133782541093433,0.9874207951344028,-0.06938773076368289,0.0477525140272358,-0.13381036417244976,0.752835756295326,0.07590812352506758,0.05092739406573241,-0.3022353540170477,-1.2378256862270267,-0.17883146104126707,0.15740356194029445,1.1551140625345142,-1.3469489669219843,0.6397876542379979,-0.11501935184635717,-0.3348836647441939,-0.18346522656805025,-0.1747229427080887,0.4215919256527653,0.2258187296871258,-1.0946626075070616,0.8293581018369595,1.1010125811878069,0.3471402724017958,-0.7577022480038975,-0.6316655641908642,2.0933214763633257,1.2520698037508815,-0.1494307912543541,1.5392931467699422,2.2019415822598556,0.7839295486563863,1.5893856268632467,-1.9530363243050286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.441666666666666,0.0,1.0,1.0,0.0,0.8365758101145603,-0.012137977808274882,0.6132218909134343,0.9874799969459707,-0.07133273513545141,0.042687738611616066,-0.13406212553194885,0.7627026752510682,0.07831556863878686,0.04291632010575513,-0.2862173930630248,-1.2755521267985293,-0.14972215635738162,0.1664852454479768,1.157519874236964,-1.3527910916116868,0.6343755793615963,-0.09778550804041228,-0.3237244981956709,-0.18479017733354747,-0.16144226179624568,0.43971416030541993,0.23220567238144915,-1.0812049453133612,0.8135914807796306,1.076901980427088,0.22730542308535107,-0.649013541345127,-0.6626082180794812,2.03910905661849,1.4187818600975621,-0.16773032384596043,1.6496291452543288,2.1323052300359313,0.7488513284887022,1.6350674886239558,-1.833489484068016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.45,0.0,1.0,1.0,0.0,0.8429224119138274,-0.01319431285755346,0.6130562604489392,0.9875365957910781,-0.07322193397712405,0.0374870188632583,-0.13418175649081032,0.7710232623324405,0.0808277560873593,0.03445702345860377,-0.2698241274062688,-1.3032222277093288,-0.11985133588298917,0.17535192828074592,1.1589024862526034,-1.3577658592777364,0.6287441839366732,-0.08103420090271567,-0.31123730040923453,-0.18626073196548293,-0.14722912362051654,0.4571303461533642,0.2382995851619375,-1.0674114826966623,0.7987999437691592,1.0493823055325358,0.10175287896883045,-0.5492277296743442,-0.6849562918403396,1.9785869184030886,1.569301157632832,-0.1842106508628627,1.761655185777506,2.034819965665792,0.7137292367135611,1.6701997739217145,-1.7193140662546869,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.458333333333333,0.0,1.0,1.0,0.0,0.8493307688906101,-0.014252667878005868,0.6128811039213088,0.9875880939363159,-0.07504856817811559,0.032191768974824335,-0.1341683984404512,0.7777799743657492,0.08343469243675054,0.025579745268501028,-0.25303668595387313,-1.3210154929557643,-0.08918706435024909,0.18397495054018573,1.159215755553111,-1.3619448871062592,0.6229596411642573,-0.0648090594003608,-0.29756947890179036,-0.1878603548479285,-0.13208134203328725,0.4736278263998498,0.2441011596600085,-1.053368282414666,0.7849362463420525,1.0184159693057,-0.029188899344902985,-0.4576964668531325,-0.6999758987529847,1.9139556223415595,1.7005793099406508,-0.19852212838548045,1.8726448145768062,1.913909571820681,0.6788029157751185,1.6952105028423903,-1.6111040023379974,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.466666666666667,0.0,1.0,1.0,0.0,0.8557893322620513,-0.015307860575516932,0.6126955681126401,0.9876328397281838,-0.07680597661979177,0.026842618105310672,-0.1340212285397171,0.7829330188624771,0.08611425499863536,0.016328376346841172,-0.23583959857303127,-1.329159869701599,-0.057714544461720245,0.19232552776917425,1.158416004596855,-1.3653941337252886,0.6170779189574568,-0.049134940530356344,-0.2828943119102237,-0.18956943410524094,-0.1160183767109031,0.4890288390170422,0.2496129670915228,-1.0391579743159558,0.7719482103968592,0.9840099385174189,-0.16527211620904758,-0.37369098390091615,-0.7088493863627199,1.847489954539147,1.8095101913402223,-0.21027843603202756,1.98012036643085,1.7735594773832464,0.6442822989942198,1.7105051315909137,-1.5094527788357381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.475,0.0,1.0,1.0,0.0,0.862286149144657,-0.016354797250982097,0.6124983430177083,0.9876700247617874,-0.07848765358611266,0.021479175170168497,-0.13373950596474923,0.7864240093684545,0.08882808470644346,0.0067601661275467,-0.21823562873855906,-1.327927336706391,-0.02544030233039362,0.2003751161821427,1.1564612202829603,-1.3681730701712744,0.6111454847248786,-0.034017560158041686,-0.26741097571278666,-0.1913649954484623,-0.09907933592610642,0.5031871510229039,0.25483919797657884,-1.0248598635548174,0.7597787000281235,0.9462428763020908,-0.30636026764257807,-0.29637263478069276,-0.7126381055203712,1.7815155577992245,1.8929546600194747,-0.21904126347261632,2.0818306639344715,1.6173884650435144,0.6103696420994953,1.7164760734709361,-1.4149499387770437,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.483333333333333,0.0,1.0,1.0,0.0,0.8688086979941284,-0.017388603061416576,0.6122877599809151,0.9876996406803557,-0.08008742363096873,0.016139890476786996,-0.13332264740663347,0.788174205755088,0.09152063484853865,-0.0030511874884893223,-0.20024554557185376,-1.3176409164317735,0.007607266833035552,0.2080962423742091,1.1533100001361454,-1.3703336776383002,0.6052006171987839,-0.019443014567035937,-0.2513450675765658,-0.19322012182978454,-0.08132119897866191,0.5159853134344341,0.25978579445984773,-1.0105500397581069,0.7483657114172418,0.9052657565430589,-0.4524458727918379,-0.224767588102468,-0.712282135276856,1.7183458661825675,1.9478431784653005,-0.22432397980003627,2.1757281514908717,1.4487247570306105,0.5772614673209975,1.713513552785575,-1.3281793450895396,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.491666666666666,0.0,1.0,1.0,0.0,0.875343622974827,-0.018404663460071073,0.6120619921512526,0.9877224309637678,-0.081599496717257,0.010861760134145589,-0.13277026652587773,0.7880816729823173,0.0941190272504874,-0.013012832190475922,-0.1819063625351806,-1.2986814894332377,0.04138032238225879,0.2154628787911937,1.1489204557364296,-1.371919196639649,0.5992741158035977,-0.005378462388332229,-0.23494692273836498,-0.19510372844512958,-0.06281720006792522,0.5273325636400807,0.2644602224319288,-0.9963013043417245,0.7376423776099645,0.8612958452285685,-0.6036677824268022,-0.15774378248713639,-0.7086081525315757,1.6601980470426667,1.9713107096714528,-0.2255976022512579,2.2599449445257105,1.2706787979521073,0.545148677834304,1.7020148199956564,-1.249720055812218,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5,0.0,1.0,1.0,0.0,0.8818765106425069,-0.01939873610383891,0.6118192089514674,0.9877398088514112,-0.08301862609781441,0.0056801300626976485,-0.1320822238362015,0.7860252870221494,0.09653195589961922,-0.02301518617443893,-0.16328115711764923,-1.2714779154956573,0.07581311237695681,0.22245117312801857,1.143248870429032,-1.3729627406797524,0.5933904813232577,0.008226952883675176,-0.21848988908204156,-0.1969800818673055,-0.043655449903233404,0.5371632934003026,0.26887160575708613,-0.9821831260915126,0.7275370438203715,0.8146267445420935,-0.7603212818492011,-0.09400273900721068,-0.7023120156837925,1.6091366280776653,1.960763862182081,-0.222284097548755,2.332774160719124,1.0861948849156255,0.5142324474371718,1.6823854338210342,-1.1801415700621898,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.508333333333333,0.0,1.0,1.0,0.0,0.8883916673840534,-0.020367035641629824,0.6115577473363873,0.9877537634402205,-0.08434022392698162,0.0006284940718609061,-0.13125865469696738,0.781867339407004,0.098653293817576,-0.03293228597384901,-0.1444539010593529,-1.236500750716026,0.11082813067425827,0.22903999120022858,1.1362484343722763,-1.3734859089564357,0.5875689155422011,0.021440481412962193,-0.2022675250353303,-0.1988084634042755,-0.023937630722606493,0.5454358117220078,0.2730307632225483,-0.9682615471113739,0.7179733514422614,0.7656092830034422,-0.9228466191703077,-0.03208665291276169,-0.6939728153556946,1.5670018366611589,1.91398185958776,-0.21376950059842414,2.392662954996859,0.8980757762390779,0.4847171441717435,1.6550416957826908,-1.1200007633526776,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.516666666666667,0.0,1.0,1.0,0.0,0.894871943047126,-0.021306305262995106,0.6112762633474927,0.987766755332349,-0.08556046034816445,-0.004261650661499648,-0.1302999732113394,0.7754606922204311,0.10036756977741561,-0.0426253885370428,-0.12552606139021694,-1.1942451832612788,0.14634439011723455,0.2352113278447426,1.1278680934428602,-1.3734975182282985,0.5818242677339961,0.03434365016136116,-0.18659019142224556,-0.20054290687727924,-0.003777733986619092,0.5521312230042872,0.2769502248266152,-0.9545990978284677,0.7088703644311602,0.7146302219266765,-1.0918040294258047,0.029594545818061313,-0.6840627103958408,1.5353633479748283,1.8291648096890112,-0.19941636913634375,2.4382123499252235,0.7089811965890136,0.4568037643741041,1.620406996534256,-1.0698340732414824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.525,0.0,1.0,1.0,0.0,0.9012986391175232,-0.02221386199951615,0.6109738464075829,0.987781610007215,-0.08667632483881685,-0.008960860730747717,-0.12920684431938467,0.7666598798517708,0.10155849626774575,-0.05194886971941185,-0.10660934520026599,-1.1452062122852698,0.1822882607794373,0.24095049489900652,1.1180517005485129,-1.3729926665261347,0.5761678703689371,0.047029870545876,-0.17178144487384678,-0.2021320695565479,0.016699241776147233,0.5572521649984914,0.28064415929545006,-0.941254763835803,0.7001427835549033,0.6620811250007541,-1.2678264076275036,0.0927096565005403,-0.6729627580934605,1.515507018688863,1.7049225234909204,-0.17858269427572404,2.468187192954137,0.52139507549261,0.4306759165378893,1.5789026524290484,-1.030143002800541,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.533333333333333,0.0,1.0,1.0,0.0,0.907651545810004,-0.02308760470354628,0.610650076364035,0.9878014174612619,-0.08768563374508986,-0.013441683887078767,-0.1279801173250766,0.7553365977430982,0.10212030666007484,-0.06075869884184731,-0.08781544895682758,-1.0898463516868924,0.21860645101536624,0.24624601326142184,1.1067376533157351,-1.3719523572866228,0.5706082217657718,0.05960210047284221,-0.15817481603073022,-0.20351928511520798,0.037358719229283195,0.560821140929164,0.28412815676891334,-0.9282840536213169,0.6917013143844846,0.6083196959079645,-1.451550064305045,0.15892459844593532,-0.6609834016371896,1.5084651872004697,1.5401883394819238,-0.1506463703002653,2.4815371903734045,0.33756036641861664,0.40647969323715394,1.5309329438612629,-1.001370676265132,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.541666666666667,0.0,1.0,1.0,0.0,0.9139091538136334,-0.023925976101889453,0.6103050049037418,0.9878294464646941,-0.0885869713561987,-0.017678448403285574,-0.12662071578244644,0.7413996913673444,0.10197133230937101,-0.06892337502174865,-0.06924355040474872,-1.0285573638370207,0.25528048272921006,0.2510891564974726,1.0938591994767621,-1.3703439232187025,0.5651514803416506,0.07217095699921716,-0.14611163921581471,-0.20464284239488564,0.05805819494903731,0.5628781711054683,0.2874188208494026,-0.9157392147714486,0.6834532722838178,0.5536263879603714,-1.6435249404185726,0.2297926132845607,-0.6483886555738594,1.5150937283044679,1.334057191423715,-0.11503442308845035,2.477431037704212,0.15938040369753104,0.3842990171165317,1.4768649452045701,-0.9838674431081684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.55,0.0,1.0,1.0,0.0,0.9200490850097538,-0.024727874024009437,0.6099390472495001,0.9878690805168325,-0.08937955708597091,-0.021646884124558723,-0.1251294807056077,0.7248196322885346,0.10106900347371608,-0.07633693020724687,-0.05096652135954777,-0.9616182721253815,0.2923419201332347,0.25547311972742803,1.0793455709754256,-1.3681224803985468,0.5598017441728741,0.08485366261125,-0.13594052950700164,-0.20543652550001548,0.07864923652435339,0.5634774809907895,0.2905331403875222,-0.9036696378679074,0.6753035236660151,0.49815943628878645,-1.8441074182479333,0.3066179191637364,-0.6354228261844286,1.5361879723852563,1.0855681181575616,-0.0712559738363977,2.4553068660805675,-0.01171450705064414,0.36412854593819377,1.4170042865724675,-0.9778434340645425,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.558333333333334,0.0,1.0,1.0,0.0,0.9260487835926797,-0.02549251110660057,0.6095527758843043,0.9879237803357538,-0.09006303712088755,-0.025323564916351637,-0.12350696600442207,0.7056573801849547,0.09942537186682268,-0.08293344651112242,-0.03301679475124464,-0.889152059681592,0.3298876260048002,0.2593918137689524,1.0631240758392966,-1.3652336245659735,0.5545610999052435,0.09777408987230476,-0.12801883724652202,-0.2058304419588256,0.0989799760503801,0.5626829293212909,0.2934876299483725,-0.8921224766619075,0.6671558817160754,0.44191112768521057,-2.0533399610658387,0.39029467981641197,-0.6223385178454799,1.5726167837997573,0.7934744708670158,-0.018938100680571113,2.4149430773041796,-0.17493722213407503,0.34584622569453605,1.3515678163868605,-0.9833056076375013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.566666666666666,0.0,1.0,1.0,0.0,0.9318865045782766,-0.026219225842277854,0.609146613744227,0.9879970747777723,-0.0906372034300003,-0.028685171510283155,-0.1217531869003856,0.6840971356430022,0.0971222577003185,-0.08870249971080568,-0.015372458915510173,-0.8110829627856736,0.3680942635626946,0.2628383051888482,1.045123238290995,-1.3616175690682732,0.5494294355421161,0.11106394234124596,-0.12271595499255138,-0.20575216051135833,0.11889828781275638,0.5605618606218883,0.2962972441490978,-0.8811435075947931,0.6589150968720567,0.38466743897670796,-2.270822994003203,0.4811218290312169,-0.6094246128258729,1.625442207231176,0.4560643650352339,0.042135620420622466,2.356552778738799,-0.33035230687418426,0.3291871434388094,1.2806531336955462,-0.9999772077959457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.575,0.0,1.0,1.0,0.0,0.9375426264005595,-0.026907249848693207,0.6087204284894738,0.9880925787141082,-0.0911016448278879,-0.031707580010879324,-0.11986732486230517,0.6604812101824827,0.0943249812798513,-0.0937048649425847,0.0020563150453902224,-0.7270954808452665,0.40723085071941634,0.2658029377518975,1.0252770259392432,-1.3572149274154532,0.5444040230248123,0.1248647933261577,-0.12041776449593479,-0.2051281816184819,0.13825585569602675,0.5571770575400545,0.29897408233901934,-0.8707782577669817,0.6504895949194763,0.32597300472105184,-2.4955877217259648,0.5785933239727559,-0.5970325633409779,1.6959830121394623,0.07110516307830189,0.1119833905526102,2.2809005260682005,-0.479120758084679,0.313719932500347,1.20420364534237,-1.0272006648666299,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.583333333333333,0.0,1.0,1.0,0.0,0.9430012877577635,-0.027555436834873333,0.6082730325112787,0.9882140325425264,-0.09145533410275293,-0.034364784865032014,-0.11784739840757162,0.6370542061847004,0.09191905115392662,-0.09794008977232034,0.022018206599327073,-0.6517895661765284,0.4474166479464692,0.26827118860086574,1.0035301095955622,-1.3519743470020607,0.5394788928197665,0.13933032587690367,-0.12153086894124634,-0.20388577066881483,0.15691329658055972,0.5525765146538103,0.30152590969077026,-0.8610734468390869,0.6417950857909462,0.2576516502071269,-2.7219105549608913,0.7045464920930478,-0.5941946637119311,1.767574129950544,-0.29529276639396945,0.18183024896516464,2.200613226753191,-0.6014234033531052,0.2963715479499973,1.1144908014882149,-1.0224567100329596,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.591666666666667,0.0,1.0,1.0,0.0,0.9482823414101541,-0.028157991980973147,0.6078047576607474,0.9883624356154944,-0.09168951686008459,-0.03675548590339597,-0.11567956871577494,0.6171580298804855,0.09083461313545027,-0.10162624798439822,0.047438887857079615,-0.6065307146486075,0.4882991667562715,0.2700971319220163,0.9799118500232283,-1.3454724858805691,0.5345007786296134,0.15432436215866677,-0.12533931060250095,-0.2020976774690625,0.17493274280857993,0.5471533341508361,0.30391360813818596,-0.8522034110755115,0.6334486497522603,0.1702300078222163,-2.937631789917805,0.8867050093018802,-0.6116229377295124,1.8113192158271652,-0.5377638688430564,0.23956765763858023,2.135322685825242,-0.6690812168796345,0.2745746066857324,0.9996001151151779,-0.9217605192474032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6,0.0,1.0,1.0,0.0,0.9534276904865103,-0.028711618369366167,0.6073163326716946,0.9885351174203434,-0.09179950069421702,-0.0390326970088607,-0.11334735049114404,0.6012343596016586,0.09062965850544415,-0.10525554408223348,0.07586900614529626,-0.5859563508236589,0.5293840312202084,0.2711083553979027,0.9545695797635988,-1.3371959301803626,0.5292851771909413,0.16951897947402308,-0.13049360008863062,-0.1998929763748385,0.1925020080109804,0.5414251610391497,0.30610215313553246,-0.8444134449205006,0.6264324104701562,0.06937696796428638,-3.135290225459779,1.1098060511576113,-0.6429165774901957,1.8279169398232404,-0.6669700854994964,0.28861141858160577,2.086464110586061,-0.6948963051142187,0.25145176447450845,0.860683555556423,-0.73301445040308,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.608333333333333,0.0,1.0,1.0,0.0,0.9584630891945267,-0.029219434583048064,0.6068064548399769,0.9887296395012823,-0.0917906949497526,-0.041248843527818775,-0.11084539322873609,0.5879375625395052,0.09068051946085215,-0.10901767653655078,0.1045206929887032,-0.5741445042644531,0.5704097636153614,0.27125341472142106,0.927657012932232,-1.3269757183612756,0.5237855023381102,0.1847896444890541,-0.13645547869415922,-0.19728748715936906,0.20970714465168094,0.5355717290655991,0.30810447087942777,-0.8378586851495711,0.6212317422455423,-0.036356003994346686,-3.3152321825291575,1.3466712347081078,-0.6780294003193776,1.8355981688170682,-0.7521672330832985,0.33702932438527455,2.0460042390004785,-0.7072818746729248,0.22966755113060788,0.7055726229943104,-0.49773583294070445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.616666666666666,0.0,1.0,1.0,0.0,0.9634064621084591,-0.029682952176887534,0.6062743464491249,0.9889442411083578,-0.09166518042672703,-0.04342322412654931,-0.10817211416305346,0.5766104158960526,0.09100253768363493,-0.11287510839961387,0.13341342483137053,-0.5655483705661295,0.6112762010089003,0.2705024219979969,0.8993157100547795,-1.3147514096018942,0.5179846871856183,0.20011228228764089,-0.14302972064001893,-0.19427582096841725,0.2266020786609884,0.529637129794601,0.3099299456543759,-0.8326539012039288,0.6181368132544778,-0.14533909103903841,-3.478492753674547,1.588024344436385,-0.7147610678158167,1.8429093887947763,-0.8221621872126728,0.38634593517682336,2.011327078870856,-0.7176813189844045,0.20871703391967644,0.5377530679635023,-0.23241477395301136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.625,0.0,1.0,1.0,0.0,0.9682729640171917,-0.03010207416612631,0.6057191396361369,0.9891775044077645,-0.09142263844561266,-0.0455626468051842,-0.10532716254346497,0.567041902474893,0.09167764669006503,-0.1168480834992087,0.1627229969315518,-0.558032681439198,0.6519634968191602,0.2688310965374371,0.8696821337043229,-1.3005086459540025,0.5118728178745132,0.21550480096896704,-0.15015818181437043,-0.19084838823975533,0.24322926263286188,0.5236103737491924,0.3115830881114224,-0.828896134016846,0.6173581626796588,-0.2570241403022189,-3.6254650364002217,1.8297368071797937,-0.7525594268102731,1.853406140746758,-0.8883369196582214,0.4368490799152741,1.9816609300363903,-0.7310188376829929,0.1881747303240522,0.3589617569824677,0.05589628105088451,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.633333333333333,0.0,1.0,1.0,0.0,0.9730773884572655,-0.03047591002227763,0.6051397111964948,0.9894281097543189,-0.09106159372118854,-0.047668966805041464,-0.1023106611295122,0.5592439456523487,0.09275850716600946,-0.12098780886419652,0.19254956293360864,-0.5507348740562279,0.6924523246260197,0.26621868632629325,0.8388912927814425,-1.2842557961488976,0.5054420300721137,0.23100238463342018,-0.15783533596765595,-0.18699500296982935,0.25962976082826156,0.5174534824998844,0.3130661911597768,-0.826671205254221,0.6190684179386592,-0.37098662446245156,-3.7562516080662345,2.0696233135646613,-0.7912488352154723,1.8685396561939944,-0.9549166826680011,0.4885530906214003,1.9571429368115079,-0.7499815677559596,0.16787692584237957,0.17048418362220374,0.3634825270516284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.641666666666667,0.0,1.0,1.0,1.0,0.9778352646292741,-0.030803272676431685,0.6045346799789557,0.9896947101108726,-0.09058005908711174,-0.049741949403348765,-0.09912301520809137,0.5533283774932993,0.09426972884083742,-0.1253574270731267,0.22293690461984494,-0.5432794735127436,0.7327058750330373,0.26264798612972956,0.8070779402365523,-1.2660149240612582,0.4986853372875887,0.24664712857220028,-0.16607345985883712,-0.18270583672939866,0.27584831157972034,0.5111106809532597,0.31438103687546204,-0.826054730956476,0.623416204797186,-0.48678816981469364,-3.8708905073165267,2.3062496176883585,-0.8307340160697974,1.8888588587734674,-1.0231470647130032,0.5413968681239362,1.9383574672239245,-0.7765385480454201,0.14781758786136634,-0.026407565268764532,0.6876575930911311,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.65,0.0,1.0,1.0,1.0,0.9825632862744762,-0.031082911569258048,0.6039024415948526,0.9899758724563202,-0.08997582743990712,-0.05178037395268245,-0.09576489599135012,0.5494399106856737,0.09621439510298854,-0.13002283439935852,0.2538984389808253,-0.5354789934773277,0.7726694483356752,0.258105550162715,0.7743764509928337,-1.2458183025207583,0.4915964631376171,0.26248336561297797,-0.174887787046206,-0.1779717218344304,0.29193571861532697,0.5045111733657941,0.3155298176241329,-0.8271113313420337,0.6305293778235114,-0.6039660736327412,-3.9694820447429713,2.538478972680651,-0.8709217178158557,1.914475417538809,-1.092966474437382,0.595298923835314,1.9260815921810492,-0.8124382370872363,0.12808090237495184,-0.23031953420789453,1.0258784097192497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.658333333333333,0.0,1.0,1.0,1.0,0.9872793507671289,-0.03131361501446158,0.6032412136485722,0.9902700517105678,-0.08924660750584876,-0.05378245994234374,-0.09223727411666544,0.5477152681976113,0.09857549527483589,-0.1350469483005507,0.28542969679694796,-0.5272183004841781,0.8122732863260794,0.2525818849025172,0.7409199061575028,-1.2237069411832473,0.4841699753239911,0.2785550521978471,-0.18428956776612682,-0.1727841879988101,0.3079496714494045,0.49757004366847246,0.31651571858171124,-0.8298933898599409,0.6405141782925068,-0.7220343724661937,-4.052269135756548,2.765319410261715,-0.9116954153321422,1.94522407696746,-1.1636671242341419,0.650184384967501,1.921127678368969,-0.8593343982712787,0.10881546518737406,-0.43971635098855266,1.3754198398281647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.666666666666667,0.0,1.0,1.0,1.0,0.9920023313416271,-0.03149425919895057,0.602549089954687,0.9905755796780181,-0.08839010236055911,-0.05574602903852578,-0.08854146484431757,0.5397336658109718,0.09941626330982799,-0.1356612701661178,0.31727891174634193,-0.5099334772748934,0.8449867360794648,0.24607164395494513,0.7068386320635579,-1.199729645683063,0.4764015395487481,0.29490376689576897,-0.19428223911677503,-0.1671353154183054,0.3239545132548098,0.4901889333946061,0.31734340871058914,-0.834439937191843,0.6534530418206475,-0.8309155518746925,-4.152870900012449,3.0068302556536564,-0.947833281074747,1.9416731810941745,-1.2022496407934864,0.7322391187616023,1.5630805155843874,-0.48034602547446736,0.0012507201529021739,-0.575897763932991,2.510934608629465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.675,0.0,1.0,1.0,1.0,0.9965992579358572,-0.031616102444797664,0.60189006209875,0.9908900103057409,-0.08739690477148226,-0.05760311318580736,-0.08473871526302466,0.5520037033106353,0.1050834729596522,-0.14510345300339353,0.3530352119452419,-0.5186314278381332,0.8771056850305287,0.23873329237127233,0.6717053911572953,-1.1735931035890197,0.4683727539727453,0.31091627188275,-0.2043270617793516,-0.16058020268611672,0.33400101337581095,0.48956427657723134,0.31653656391759294,-0.8394916859254907,0.6823630884363312,-0.9538371252546807,-4.167854472868309,3.2304147841157382,-0.9945470171447046,1.996819259609136,-1.2356079812198013,0.7940497563770077,1.053255934340941,0.24378692311690875,-0.10457906746314194,-0.6215066206280673,3.6006146871602684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.683333333333334,0.0,1.0,0.0,1.0,1.0015612206378575,-0.031689619541475776,0.6010839650108535,0.9912019648391621,-0.08626177059988437,-0.059638645510266326,-0.08075149406679048,0.5883347359193626,0.11583526998681104,-0.16616830326322676,0.3903782718996121,-0.5550047625810612,0.9116961241328845,0.23017435853403378,0.6373743908490861,-1.145889399281134,0.4598257559296697,0.32818408788925457,-0.21487570547043838,-0.15390115281202194,0.3415087788271588,0.49425204877988793,0.3156004242528701,-0.8447983808689774,0.7134632866066519,-1.0906386855081425,-4.081120087588617,3.416341827428999,-1.0501328739886995,2.126402658967641,-1.2776753272817571,0.8114072709531978,0.7493970092740865,0.8520958361843545,-0.11721729133629455,-0.6284247306279589,3.8004490454504847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.691666666666666,0.0,1.0,0.0,1.0,1.006824966280166,-0.031708501547008085,0.600165860124038,0.9915073509352437,-0.08499869509609968,-0.061794376399356615,-0.07661494579388285,0.6179163821312531,0.12447102976572579,-0.1836736336120331,0.4243915241362972,-0.5788247254283977,0.9409704359990488,0.22055598094613663,0.6036867230308184,-1.1166540731318697,0.450870539406267,0.34635631619887736,-0.22562165056738087,-0.1470567481702301,0.34649096353037906,0.5037658738469706,0.31458294239532136,-0.8499654314359567,0.745703905860506,-1.2112178642905913,-4.013163961579139,3.5980074045171495,-1.0950838915911398,2.2201994664675153,-1.2922167858871092,0.8342617217437837,0.4461871601364531,1.4080312785340943,-0.1253453968447249,-0.5995916515826938,3.9011058141983135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7,0.0,1.0,0.0,1.0,1.0123324937858724,-0.031670866304964164,0.5991564407384552,0.9918044383901511,-0.08360921966873364,-0.06402524133948656,-0.0723479291174926,0.6415081996228458,0.1311539326491767,-0.19877399263319157,0.4570383967529965,-0.5924168973586545,0.9674128569087816,0.2099873941291906,0.5704883248227671,-1.0859226092058483,0.441574357736484,0.3651874123303798,-0.2364126519018902,-0.13999679078295887,0.3489452314960997,0.5177192367554562,0.313511334305458,-0.8547915750620223,0.7784817168432905,-1.3199281204094815,-3.962517132677117,3.775338340074881,-1.132873148702106,2.288455892180954,-1.293267287317675,0.8633327225580517,0.1448325459144495,1.9167230241481548,-0.13025468255332573,-0.5504930024364207,3.9384604035075377,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.708333333333333,0.0,1.0,0.0,1.0,1.0180349502612398,-0.0315760878449787,0.5980713807999753,0.9920922244986213,-0.08209463283056619,-0.06629180113086038,-0.06796238998743281,0.6601659967455412,0.13615754930539997,-0.21186549687978587,0.4885367895262305,-0.5967285559203094,0.9920905793957501,0.19855717893931193,0.5376447708195331,-1.053731767463955,0.4319893202612319,0.3844972477352266,-0.24717610535600879,-0.13266786946092923,0.3489048392956199,0.5357112575827732,0.3124120310194326,-0.859140314809897,0.8113449125856316,-1.4187264103358166,-3.9269528569734913,3.9481375385475825,-1.1649542678564262,2.3377197316606058,-1.288624543507998,0.898583515534922,-0.1504307169402075,2.3748599001336834,-0.13221710544552678,-0.48714323853382036,3.9269506620140904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.716666666666667,0.0,1.0,0.0,1.0,1.023892687885108,-0.031424088851725394,0.5969248084225842,0.9923702322016218,-0.08045650301047563,-0.06855619368742095,-0.06346748514608826,0.6749835445934261,0.13973232418679998,-0.22309124915258,0.5189432564291878,-0.5920145557299867,1.0154414016057125,0.186341953956927,0.5050391105398756,-1.020120316896722,0.42215845327221024,0.4041494078580566,-0.2578897276270235,-0.12502039885737684,0.34643805288042956,0.5573002350910176,0.3113077158813659,-0.862910629037586,0.8439308945435253,-1.5088409681389603,-3.9043031677382367,4.115889074692101,-1.1922591891834278,2.3727085540867687,-1.2835226984878063,0.9393055084464117,-0.4358984167642954,2.7779559427424783,-0.1317404061087457,-0.41306046725982704,3.8757615464575212,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.725,0.0,1.0,0.0,1.0,1.0298752970561502,-0.0312152107364598,0.5957302596830568,0.9926384456616854,-0.07869670756033409,-0.07078082148620145,-0.058871213030134394,0.6870517927940648,0.14209203182501692,-0.23254178214401905,0.5482757381908965,-0.5783109013286265,1.0376479645636008,0.17340982947032926,0.47257305135722916,-0.9851336162190867,0.4121183337748414,0.4240423903033394,-0.26856815033080556,-0.11701277765348904,0.3416398656828816,0.5820105232951478,0.31021635758428684,-0.8660246559308942,0.8759409383599236,-1.591197553154698,-3.8922562836599686,4.277496069923661,-1.2154698423336219,2.3972640133176704,-1.2818054118937672,0.9843982798103135,-0.7089843716678967,3.1229588322405277,-0.1293810073534929,-0.33059500240786743,3.7916953562284395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.733333333333333,0.0,1.0,0.0,1.0,1.0359613087545938,-0.03095021492116845,0.5945008657185952,0.9928972726539464,-0.07681747110690695,-0.07292802468776434,-0.05418104193169326,0.6974107792056989,0.1434060596011601,-0.24031028218688166,0.5765299856942215,-0.5556081872303713,1.0587886602590133,0.15982199473768202,0.44016817247887613,-0.9488287157313275,0.4019006225666499,0.44410380808001776,-0.2792531511585863,-0.10861376086053828,0.3346216466859646,0.609349548961693,0.3091513657588077,-0.8684205457443838,0.9071258171473326,-1.666567111056052,-3.888404098355646,4.431288932245807,-1.2351023061703892,2.414557278811015,-1.2861972804912214,1.0325329010563298,-0.968298316396925,3.4088863280419712,-0.12564362806191665,-0.24136566480029265,3.6800562704908413,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.741666666666666,0.0,1.0,0.0,1.0,1.0421375530783474,-0.030630333779395814,0.5932493262288219,0.9931475031506211,-0.07482144530499006,-0.07496010321745486,-0.04940416211768133,0.7069822582765848,0.14379175291234592,-0.2464954263526987,0.6036829288612723,-0.5239178420212267,1.0788990753182315,0.1456337109527284,0.40776631638463506,-0.9112788006816566,0.39153329533866826,0.4642850116168563,-0.2900047716723259,-0.09980389596921688,0.32550156040959954,0.6388252954291807,0.30812229711658823,-0.870047417010899,0.937275209534771,-1.7356202198699477,-3.8904124463748513,4.575180211067971,-1.2515382752229165,2.4270502428657106,-1.2983591520472892,1.0822487053078123,-1.213578097884549,3.636772068398566,-0.12093629726116939,-0.14647748453073817,3.5449270142574796,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.75,0.0,1.0,0.0,1.0,1.0483977836159475,-0.030257315364292683,0.5919878818484685,0.9933902572814002,-0.07271178367593689,-0.07683949617287517,-0.04454755977452841,0.7165204394455379,0.14331162240197376,-0.25118964606327193,0.6296898277935155,-0.4832924176861845,1.097994243083021,0.1308949910731829,0.3753279650392953,-0.872575712213528,0.3810416513129346,0.48455464546111293,-0.30089247035937444,-0.09057628243874141,0.31439534505455546,0.6699624167683358,0.30713576080445487,-0.8708618371532294,0.966207934051624,-1.7989438227888173,-3.896164389848278,4.706833415381109,-1.265035201079755,2.4364615431490977,-1.3189743553985922,1.1320116983245094,-1.4454962848950603,3.80927188813444,-0.11555455604954856,-0.04667661929049105,3.3893043588623195,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.758333333333333,0.0,1.0,0.0,1.0,1.0547412363374933,-0.02983349338425909,0.5907283052262097,0.993626918184927,-0.07049225916583605,-0.07852895586714963,-0.03961807601848611,0.7266115761544956,0.14197806810687902,-0.2544687098524976,0.6544811594013421,-0.43382569943715227,1.1160687228562656,0.11565131390624811,0.3428302432204971,-0.8328315770919714,0.37044937532067235,0.5048927040026746,-0.3119876775956358,-0.08093703433047506,0.30140995566134854,0.7023131602314213,0.30619638784909575,-0.8708253606657406,0.9937636155158096,-1.8570454297097194,-3.903767315386786,4.823749846234007,-1.275731494666662,2.443832536855939,-1.3478983644109566,1.180232678014871,-1.6653080297801892,3.93003921539288,-0.10969112588274488,0.05753997610028705,3.2152670221380064,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.766666666666667,0.0,1.0,0.0,1.0,1.0611712692745052,-0.029361847774881534,0.5894819552258819,0.9938590538130114,-0.06816735484954921,-0.07999172682162398,-0.03462248586910506,0.7376380782216763,0.13976043421632367,-0.256372387183086,0.6779700897104821,-0.3756535238673934,1.133106223318473,0.09994423391135424,0.3102651764495155,-0.7921798814429613,0.3597794597351569,0.5252851877420452,-0.32335744309955705,-0.07090573780516023,0.28664021122488564,0.7354630703582171,0.3053075753730758,-0.869902837551558,1.019795717753924,-1.9103811950000782,-3.9116430658228376,4.923411425919624,-1.2836762575778315,2.4495312932882807,-1.384309488166242,1.2253034779859013,-1.8747081464897075,4.0033612956946545,-0.10346227805137387,0.1657919453113177,3.0240528668159516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.775,0.0,1.0,0.0,1.0,1.067693329786603,-0.028846010278623005,0.5882598901380593,0.9940883340860968,-0.06574231706071343,-0.08119172430144493,-0.02956747684908733,0.7497924408892489,0.13659587517051477,-0.25689506465446943,0.7000537812186138,-0.3089469305345104,1.149076431674965,0.08381162732291347,0.2776361921234498,-0.750774719993311,0.3490547710277085,0.5457182255574793,-0.3350595023984065,-0.0605153096973767,0.2701648198865201,0.7690358484929989,0.3044720165482395,-0.8680621615772186,1.0441644966294088,-1.9593656405001771,-3.9184995744177704,5.003341170007068,-1.2888452754465218,2.4533570479116595,-1.4268960458643865,1.2656155835710199,-2.075585781373589,4.033721153398839,-0.09693792037768656,0.27772813128192464,2.816203553501331,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.783333333333333,0.0,1.0,0.0,1.0,1.0743138406274158,-0.02829030848862032,0.5870730106539654,0.9943164362627419,-0.06322322251610994,-0.08209365845337352,-0.024459761955204547,0.763118866447272,0.13240276080062957,-0.25598296323618086,0.7206184319962581,-0.23390692821192668,1.1639268205303028,0.06728813990301795,0.24495685020921934,-0.7087908619428435,0.33829870514438154,0.5661744718739062,-0.3471390438639635,-0.04981214474564323,0.25204711486865916,0.8026917562481978,0.303691943366781,-0.8652740353635259,1.066732443645613,-2.004381898155635,-3.9232144657820993,5.061086856825508,-1.2911603749152523,2.4546888450630933,-1.4740291835644825,1.2995645144065637,-2.2697483537648684,4.025380948505764,-0.09018140967819943,0.39297719372304973,2.591742160612074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.791666666666667,0.0,1.0,0.0,1.0,1.081038881474437,-0.027699744473960567,0.5859322457439671,0.9945449487685556,-0.060616975739322496,-0.08266317478060962,-0.019306130295103884,0.7775143405234415,0.12709318402768421,-0.2535266354759969,0.7395501127189089,-0.1507652496410976,1.1775877747750962,0.05040526235365289,0.21224928436041482,-0.6664232723795526,0.3275354314457876,0.5866297063085308,-0.3596266554578145,-0.03885590112393397,0.2323356806571056,0.8361255309680949,0.30296899305360286,-0.8615125416818344,1.0873601993062767,-2.045807936808254,-3.924828897598685,5.094269546435431,-1.290523567328583,2.4525537240553907,-1.523906573642888,1.3255873031044936,-2.458863669634777,3.9822592282553493,-0.08328891485696599,0.5110806276603652,2.3502623968698133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8,0.0,1.0,0.0,1.0,1.087873103463025,-0.027079958751052832,0.5848487639921609,0.9947752702167056,-0.0579312842798905,-0.08286698246394048,-0.014113514261410732,0.7927497211842012,0.12058461805704694,-0.24935981258826156,0.7567412502715487,-0.059783255599852064,1.1899712297160798,0.03319134095621372,0.17954303524924126,-0.623886369502253,0.3167899790222385,0.6070503672748294,-0.3725374867580116,-0.027719023027235005,0.21106605370807954,0.8690627433857869,0.3023037947858316,-0.8567560249025198,1.1059034835934431,-2.084028201218275,-3.922516319333286,5.100625583291188,-1.2868399083882442,2.44572412692033,-1.5746857028364014,1.342198741606322,-2.6443686207160315,3.907799523916482,-0.07642344159304093,0.6314589507238821,2.091035162296264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.808333333333334,0.0,1.0,0.0,1.0,1.094818778166241,-0.02643716626204427,0.583834209426436,0.9950085056299001,-0.05517459622279163,-0.08267298475956934,-0.008889052098707497,0.8084814166733068,0.11281111811867506,-0.24325907320948278,0.7720989213519296,0.0387476136492256,1.2009731226440459,0.01567145900001497,0.14687401237152672,-0.5814128459913661,0.3060880996393169,0.6273917750905363,-0.38587141717175455,-0.016485922097161942,0.18826287031183842,0.9012555230333696,0.3016952690270522,-0.8509882258364364,1.1222107853445478,-2.1194494557646877,-3.9155903090831736,5.078083282963759,-1.2800441564448295,2.432793570188647,-1.624601963438077,1.348037510784787,-2.8274388467236524,3.804925333579834,-0.06984619955801019,0.7533855233483888,1.8130881044732972,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.816666666666666,0.0,1.0,0.0,1.0,1.1018749242384525,-0.025778064998727594,0.5829009559901536,0.9952453611245231,-0.05235600442062729,-0.08205040761011757,-0.0036401336057847945,0.8242572927498418,0.10373369835138878,-0.23494549318603325,0.7855521667090611,0.14450704401577505,1.2104790021362546,-0.002132816639864405,0.1142831967645217,-0.5392516481195236,0.295455909748158,0.6475969267779735,-0.39961418614864624,-0.005251731180821889,0.163942072929352,0.9324781656121175,0.30113969145986474,-0.84419959951338,1.136121618667998,-2.1525177586016144,-3.9035580590092067,5.0248909657771454,-1.2701267023166418,2.412242563576552,-1.6720865090541426,1.3419203046315553,-3.008995504981346,3.676040318516227,-0.06394068143999232,0.8759696258489957,1.5152649600732282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.825,0.0,1.0,0.0,1.0,1.109036477297625,-0.025109720898075637,0.5820623724663045,0.9954860385513241,-0.049485124002679265,-0.08096991436366435,0.0016255830288993975,0.8395197749056333,0.0933498571515508,-0.22408931483438382,0.797057721740317,0.25715096900835793,1.2183728158176212,-0.02020383697667861,0.08181471138803995,-0.4976646632284137,0.28491932126737285,0.6675958178168122,-0.41373952565599026,0.00587941631336398,0.13811294522881598,0.9625228616753068,0.3006295910030523,-0.8363887320722865,1.1474652013457682,-2.183737476234927,-3.8862148860783066,4.939795805794262,-1.257157547502239,2.382503944436858,-1.715892957002132,1.3228988177488759,-3.1897305359266803,3.523043793562708,-0.05922697094536855,0.9981518539052869,1.196269452567953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.833333333333333,0.0,1.0,0.0,1.0,1.1162934995008198,-0.024439435186539897,0.5813330843988537,0.9957301317946597,-0.046571952834469944,-0.07940368482653654,0.00690019432681542,0.853622191058244,0.08156671750584939,-0.2086170956827615,0.8068468381531368,0.38413067070723245,1.22513919672541,-0.038528441243779854,0.04951294866321659,-0.4569217180229526,0.274503283956454,0.6873053258519212,-0.4282124020986818,0.016796582448326044,0.110779897330574,0.991195562171496,0.30015257527744194,-0.8275637352816252,1.156059442877464,-2.2146209109232946,-3.8674969075527836,4.812442657163843,-1.241604734171109,2.3404388812370014,-1.7658941199992417,1.2909931267914303,-3.375708727788155,3.3311044845617355,-0.05864373885682728,1.1232356499414764,0.8329412065632225,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.841666666666667,0.0,1.0,0.0,1.0,1.1236261738574218,-0.023774243145787542,0.5807573416491755,0.9959815837443419,-0.04362588116939149,-0.07726038758013196,0.012177842406775633,0.8654738226456227,0.0683452990055818,-0.18686756323114256,0.8148985447809365,0.5306517376380198,1.2313599288326316,-0.05711418549206685,0.01735642959549355,-0.4174572856090163,0.2642259090311877,0.7066031325040956,-0.4431710943226443,0.027395968426554482,0.0818511330990134,1.0180412697513357,0.2996521953554385,-0.8176681379065952,1.1613475547884886,-2.2470071730157852,-3.8510818090148646,4.635249606283591,-1.223921263802883,2.2834948091809903,-1.8304695722483266,1.2460155004981908,-3.5722717473396037,3.0910428218904262,-0.0644551521784198,1.2518325040513578,0.4083947583031877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.85,0.0,1.0,0.0,1.0,1.1310042505921833,-0.02312266424062293,0.5803711414080648,0.9962412633753002,-0.040658448788901194,-0.0744687877231969,0.017453806058617204,0.8737513317582367,0.05401202332222255,-0.1611685244815903,0.8206939924384411,0.6836553082465303,1.2362155094987322,-0.07597856079404294,-0.014671748153697818,-0.3796675579182261,0.25410459622640597,0.7253635726716043,-0.45872022830282055,0.03756350745662922,0.05124203487491394,1.0427129425363364,0.29907832274113494,-0.8066998602141026,1.1628660221825171,-2.2807735653612116,-3.833178148910566,4.425640308348652,-1.2039876013922668,2.2128942265832707,-1.8938653704476616,1.1864981452981098,-3.771461885524661,2.8309683685396436,-0.07367645314797833,1.373813938527333,-0.04361181251852919,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.858333333333333,0.0,1.0,0.0,1.0,1.1383948293267847,-0.02249357597263859,0.5801746926019165,0.9965020079186206,-0.03768237702734179,-0.07104628074008211,0.02272031402116701,0.8777990228278274,0.03904474522802776,-0.1339520307588089,0.8240754397014529,0.8297466349698651,1.2384263489109006,-0.09512707824808704,-0.04652987288634922,-0.34369661380320543,0.24415944900798325,0.7434847029471501,-0.47473551716343865,0.04717093751485631,0.018993435006935722,1.065224075893663,0.2984242544696389,-0.7947712389311397,1.1606206912465131,-2.314983775051873,-3.810339035018867,4.205559380110385,-1.1819168628115846,2.1300319885517527,-1.9384063529721574,1.1118567848928183,-3.9622929381501937,2.575770760202465,-0.08361311997093113,1.4815920956887885,-0.48870793842750615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.866666666666666,0.0,1.0,0.0,1.0,1.145765395162721,-0.02189409195769603,0.5801630020585452,0.9967545794265108,-0.03470862027934684,-0.06703337183752205,0.027966893487846263,0.8775823605726616,0.023828139753600132,-0.10565932178174953,0.8252823614269982,0.9653775001506383,1.2373519494299774,-0.11456162371157416,-0.0781773987373456,-0.309574901583053,0.2344059818462129,0.7608641058141336,-0.4910270008523565,0.05609445387150953,-0.014796180760922623,1.0856424552063775,0.2976847707416194,-0.7820066586192894,1.154720889875392,-2.3493139987812963,-3.7829651398652326,3.9850995250694834,-1.158212635118372,2.0354214440928065,-1.9601262617286097,1.023394631229478,-4.139145272581737,2.328121449446323,-0.0944367963002124,1.5750551155841963,-0.9193726123271917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.875,0.0,1.0,0.0,1.0,1.153085324967619,-0.021329748144502125,0.5803309558403674,0.9969893421350058,-0.031746468966160186,-0.06247725507140247,0.0331814101163647,0.8732286450529729,0.008680883048532734,-0.07647637362658262,0.824557672400726,1.0895255764450913,1.23273907504334,-0.13428231156110865,-0.10957929188410309,-0.2772782883853807,0.22485590508934372,0.7774083936820302,-0.5074042881922488,0.06422751470201428,-0.04999231953609323,1.1040261000511018,0.29685030786463534,-0.7685203203380697,1.1452978143743933,-2.3836547869221203,-3.751565154204529,3.769147657943765,-1.1333081588359273,1.9305482565989873,-1.9604710863041697,0.9235813645648709,-4.29847700029202,2.086421660684139,-0.10659366543407711,1.6556175545743557,-1.3340172016476792,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.883333333333333,0.0,1.0,0.0,1.0,1.1603260143340641,-0.020804763778578136,0.5806735846423751,0.9971968942570932,-0.02880382495806628,-0.05742714181432989,0.03835123384104446,0.8649077289217271,-0.006118541409946908,-0.04662393954505965,0.8221339614256664,1.2018697175330053,1.2245941612313391,-0.1542892034936095,-0.1407034846407544,-0.24675577395065693,0.21551751253228077,0.7930399100907833,-0.523701518957426,0.07148747661425738,-0.08643746409912295,1.1204161495511131,0.29590820965105147,-0.7544130327097168,1.1324872698479307,-2.418053974261249,-3.716321982560561,3.5602145380687493,-1.1076169780424538,1.8174265043557658,-1.9426697108211255,0.8153739479416922,-4.437911139662828,1.8488191153778955,-0.12034691710991252,1.7249479071379392,-1.732230618253503,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.891666666666667,0.0,1.0,0.0,1.0,1.1674611495494294,-0.020322205903330625,0.5811857628762923,0.9973683840254145,-0.025887268769727176,-0.051933032099880816,0.043463962586047164,0.8528353804423023,-0.02032379719257555,-0.016382975015276885,0.8182489950396734,1.3022642456783289,1.2130712568899358,-0.17458321113212946,-0.17151799159344577,-0.21794137941756822,0.2063956221219695,0.807698835421293,-0.5397821167059342,0.07781708050104248,-0.12395750519714036,1.1348397519740667,0.29484452591280347,-0.7397711885524374,1.1164273040701682,-2.452632368138092,-3.6770554367329873,3.3596418250314386,-1.0815628693860113,1.6981933891364576,-1.9101103771145245,0.7017382425430921,-4.555715589762522,1.6139319272934838,-0.13575804279626236,1.784797769900397,-2.1136904776376264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9,0.0,1.0,0.0,1.0,1.1744669200345952,-0.019884073314823884,0.5818618675861346,0.9974957186220256,-0.023002071563136106,-0.046045440580840785,0.04850786992938842,0.8372685453956917,-0.03371652481134949,0.013916148402441333,0.8131480586023172,1.390592652814716,1.1984101385998274,-0.19516640962924436,-0.20198774191963753,-0.19076174353346628,0.19749146470918058,0.8213431332430576,-0.5555366919093347,0.08318311398997558,-0.16236605726183165,1.1473150150060045,0.2936455756044471,-0.7246664032113769,1.097259095220637,-2.487524589086118,-3.6331956239825125,3.167929304486932,-1.0555828250976125,1.574924407119691,-1.8657952744255413,0.5853792460533694,-4.650629921673757,1.3809817884969355,-0.15272774975598424,1.8369317126646911,-2.4779313369810563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.908333333333333,0.0,1.0,0.0,1.0,1.1813221501806836,-0.01949132864215194,0.5826954884270261,0.9975717278237913,-0.020152164365750125,-0.039815393902278895,0.053472166053636375,0.8184971958648082,-0.046103476837858544,0.04390924635500902,0.8070864242125326,1.466727897998255,1.1808985992539716,-0.21604195428356476,-0.23207125199315431,-0.16514255767611935,0.18880257503700928,0.8339475755399545,-0.5708787046130266,0.08757340126859864,-0.20146800389170297,1.1578561151156823,0.2922990634168704,-0.7091556600080259,1.0751284484538173,-2.5228393891450165,-3.583771578339745,2.9848143442427233,-1.0301268460077424,1.4495545918944353,-1.8121806753488623,0.4685899166981172,-4.721813523001229,1.1497914598623549,-0.1710495878574647,1.8830585982145398,-2.824305908339788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.916666666666667,0.0,1.0,0.0,1.0,1.1880083099052268,-0.019143896111728256,0.5836791950819237,0.9975903015622342,-0.01734008201138965,-0.03329448605667459,0.0583471422627613,0.7968314301855633,-0.05731352536237064,0.07321299976007678,0.8003300107722824,1.5305274590501112,1.16085124946389,-0.2372137327816613,-0.26171726822529995,-0.14101483779608756,0.18032268394238488,0.8455023764412982,-0.5857397031651491,0.0909929459349442,-0.24106294931185213,1.1664782060037104,0.290794749140156,-0.6932820932411345,1.0501873300816404,-2.5586340129235663,-3.527417594060799,2.809276906697937,-1.0056580994142779,1.323846878058168,-1.7511756909201992,0.35318547954926893,-4.768854967670021,0.9207534612249502,-0.1904597824804244,1.924749114853197,-3.151984010232516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.925,0.0,1.0,0.0,1.0,1.1945093778596783,-0.018840640016151974,0.5848043573504706,0.9975465065411642,-0.014566900171742052,-0.026534910491287794,0.06312425267070933,0.7725856918661422,-0.06719447257089355,0.10143735954399205,0.7931535043013346,1.5818429149675053,1.13860022421897,-0.25868585449895753,-0.29086154522750096,-0.1183212758978204,0.172041606713438,0.8560116901742573,-0.6000649661283632,0.09345982592775312,-0.28094892001953664,1.1732020061360982,0.2891247337088633,-0.6770765080938059,1.0225953816166087,-2.5949000903933497,-3.4623966589823287,2.6395265203245657,-0.9826530711438952,1.1993852062576726,-1.6842169246581373,0.24049854138359916,-4.791809498304223,0.6947826289314785,-0.2106777551358774,1.9633458002111226,-3.459950634469562,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.933333333333334,0.0,1.0,0.0,1.0,1.2008115528063315,-0.0185793383080267,0.5860610110824528,0.9974366810286878,-0.011832183486048203,-0.019589427553475418,0.06779617367098174,0.7460625197230125,-0.07561001025936662,0.12819502901778093,0.7858357151847086,1.6205379228343677,1.114494379680773,-0.28046206762155046,-0.31942387920833876,-0.09702272912401147,0.1639451327566533,0.8654921298789261,-0.6138099852427847,0.09500125495800418,-0.32092644095025585,1.1780579164859017,0.2872834532212247,-0.6605596632376158,0.9925214861738144,-2.631560297389428,-3.3866330921981826,2.4729808445480885,-0.9616003403195739,1.0775839829348843,-1.6123839969591058,0.13141477649245947,-4.791240954629244,0.4732473263031123,-0.23143505627796768,1.9998739730172899,-3.7469937265681796,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.941666666666666,0.0,1.0,0.0,1.0,1.206902829787591,-0.01835666499878712,0.587437761644179,0.9972585036268965,-0.009133961502187407,-0.012511240235633507,0.07235687007797273,0.7175381260431798,-0.0824373200227101,0.15310775959606235,0.7786522605015666,1.6465121467605208,1.0889039128643871,-0.30254519278878134,-0.34730543009747067,-0.0771049284886856,0.15601493437477842,0.873971423223172,-0.6269380327443483,0.09565007220262745,-0.36080293593002405,1.1810894615744834,0.2852674827708972,-0.6437452752101844,0.9601454861738057,-2.6684755397188855,-3.297743754710906,2.3062299845442307,-0.9429965254997935,0.9597097606813954,-1.5365360845110532,0.026432821371142334,-4.768249171768889,0.2578741282404895,-0.25249214641494655,2.0349606316917024,-4.011680346245932,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.95,0.0,1.0,0.0,1.0,1.212772475807642,-0.018168193723257984,0.5889217157363364,0.9970110299325133,-0.006468747106372908,-0.005353759670648034,0.07680168537508858,0.6872518298742691,-0.08756584489877575,0.17580967681577292,0.771865911179295,1.659729224075656,1.0622274042770996,-0.32493665995019855,-0.3743862751201872,-0.05858556271494096,0.1482285239983234,0.8814872925569494,-0.6394189199846356,0.09544180198085656,-0.40039726047973734,1.1823558186232432,0.2830752507809756,-0.6266436527094208,0.9256601470697156,-2.7054619652057013,-3.193058773632602,2.1349809321139372,-0.9273381711121509,0.8469114525155619,-1.4574534531258942,-0.07426417587519218,-4.724467770404164,0.0506250807940134,-0.27364374156462756,2.0687666212666667,-4.2523221240243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.958333333333333,0.0,1.0,0.0,1.0,1.218410455093465,-0.018008432849495302,0.5904984331574508,0.9966946903976581,-0.003831609152693162,0.001829748840303279,0.08112746184033078,0.6554012164630796,-0.09089773249189713,0.19594846486184722,0.7657152968763249,1.6602460363238154,1.0348981587532786,-0.3476362255422097,-0.4005230763246807,-0.04152191295345331,0.1405592981895759,0.8880866140984314,-0.6512289236297799,0.09441233593804091,-0.4395440654367601,1.1819332129210502,0.28070675374482007,-0.6092658315224067,0.8892734507734007,-2.742315519341978,-3.0696293541032804,1.9539903448203169,-0.9151087740619268,0.7402541241777061,-1.3759663577571168,-0.17073467190979574,-4.662020809089368,-0.1464484731573945,-0.294714634217943,2.100936319811073,-4.466931039132199,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.966666666666667,0.0,1.0,0.0,1.0,1.223806868773893,-0.017870899535544757,0.5921518941847718,0.9963112436940665,-0.001216305992594413,0.00898663405538745,0.08533268341966863,0.6221450245416769,-0.0923503381189278,0.2131860683499258,0.7604033432292483,1.648238520965845,1.0073862371476778,-0.3706419186058982,-0.42554676435524186,-0.02601905696793568,0.13297671109729128,0.8938248612932445,-0.6623516926139209,0.09259622411569329,-0.47809760729789347,1.1799150107372867,0.27816334021067657,-0.5916280473792362,0.8512112964175123,-2.7788383078273995,-2.924234739952504,1.7570268899873436,-0.9067609417719685,0.6407486088014447,-1.293046818527479,-0.26320987137184976,-4.583429191453202,-0.3313668794756497,-0.3155493999741632,2.1305695098636868,-4.653165281211125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.975,1.0,1.0,0.0,1.0,1.2289514913962138,-0.01774823524900734,0.5938644883574227,0.9958636831646013,0.0013845228707326837,0.01606541116902818,0.08941761790492521,0.5876162113063631,-0.09186093522317094,0.2272017359891201,0.7560880434416627,1.6240156803266281,0.9801915677190858,-0.393950197339333,-0.44926032199055577,-0.012238131453664251,0.12544661582670977,0.8987657575784554,-0.6727797039385712,0.09002550474851008,-0.5159345519609801,1.176410431596456,0.275447597078584,-0.5737563396913452,0.8117206960865486,-2.814854631299889,-2.75342632722836,1.5369643030075661,-0.9026950569360179,0.5493644452573521,-1.2098255258578727,-0.35203702648930246,-4.491458389752251,-0.5023846207514726,-0.33600159382993433,2.156222238847487,-4.8082621191354935,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.983333333333333,1.0,1.0,0.0,1.0,1.2338335100444044,-0.01763235694778425,0.5956170499534876,0.9953561005817473,0.003979127102353745,0.023016326236941092,0.09338441247134496,0.5519480398206614,-0.08939333285014558,0.2377015901288005,0.7528798277012099,1.588008708483336,0.9538223453233123,-0.41755616246089633,-0.4714372031423812,-0.00040298525114291253,0.11793179348169099,0.902980935380867,-0.6825154513782188,0.08672894034087159,-0.5529552471270976,1.1715419337247621,0.27256331364684433,-0.5556910100651115,0.7710735944319207,-2.8501949965515485,-2.553682667656909,1.286187462630089,-0.9032378194215505,0.4670076748472929,-1.1274793161519314,-0.4376430203439888,-4.388899519233709,-0.6581350061639091,-0.355930744339914,2.175945996384947,-4.928949936921934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.991666666666666,1.0,1.0,0.0,1.0,1.2384415983069859,-0.01751462513157172,0.5973889947159321,0.9947935223322504,0.006576424565358205,0.029791799557528056,0.09723706816893077,0.5153150663246764,-0.08494541756920615,0.24443940817497042,0.7508506808170703,1.5407196662321387,0.928753378397075,-0.4414534472818588,-0.4918216997848376,0.00919832625683723,0.11039265216968393,0.9065492188259103,-0.6915710258744368,0.0827314544094436,-0.589082877281542,1.1654415148270576,0.2695154180062521,-0.5374905730849294,0.7295715304711831,-2.884617857597537,-2.321772867391493,0.9975411549574793,-0.9086257405301821,0.394442917064175,-1.046930909028294,-0.5205257080565179,-4.278283195718864,-0.797730348303034,-0.3752165690584952,2.1873724006017414,-5.011326189791479,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0,1.0,1.0,0.0,1.0,1.2427644673462128,-0.01738599452763639,0.5991586390447367,0.994181746893633,0.009185863048180984,0.03634655558799601,0.10098119691774708,0.3475860581498342,-0.04029281124911628,0.2610231828612406,0.7775662878398124,1.4246726926779805,0.9678027657613508,-0.4656331267541886,-0.5101334175989061,0.016222700664815074,0.10278803113952129,0.9095549839986032,-0.6999642998620237,0.07805351187326295,-0.6242599670557454,1.1582464279197116,0.2663097041625361,-0.5192348033884158,0.6875514912687294,-2.8919588851493607,-1.286018342918862,-0.11562776577794945,-1.0558010178643176,0.23030433713352227,-1.0997684113837547,-0.6595331233048313,-4.483793062749757,-0.7908568655948311,-0.4482218431805529,1.965361534848289,-4.9584024048257085,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.008333333333333,1.0,1.0,0.0,1.0,1.2445581098672436,-0.017052837749820447,0.6013020362986026,0.9934903935717917,0.012118065754029617,0.04217535046536866,0.10512483208295399,0.18597781523625465,0.0008628472515232674,0.25804545149571795,0.7812938073388338,1.3317689316587533,0.9967772719992636,-0.48965276203434815,-0.5132553388334853,0.007271196827204739,0.09279596853861197,0.9103876244448024,-0.7099004993974993,0.07173923568769641,-0.6638127616607046,1.1522605670671437,0.2620450539532429,-0.5047345475041246,0.6469314903907546,-2.8587010092659373,-0.25971488399194165,-1.3213848782200963,-1.1798623735474514,0.21807007442590454,-1.5008466685875144,-0.771525217515236,-4.685623713923732,-0.795128269270764,-0.4907979788683592,1.7086927507475547,-4.85607243290348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.016666666666667,1.0,0.0,0.0,1.0,1.2461529399348474,-0.016786732407836884,0.6031914505000678,0.9927630430857702,0.014837078251388216,0.047955730135249196,0.10909468120712293,0.17399461340120054,-0.003956538550473773,0.233715610656925,0.7428810501873977,1.307289202163893,0.9554713588121925,-0.5132781435752876,-0.5144619989987718,-0.005800380638853195,0.08312365824706376,0.913189485239035,-0.7249784110051489,0.06519475824800902,-0.7023536956211409,1.1449942900985322,0.2581297378480634,-0.4907565908759565,0.606616950720338,-2.8011417893825796,-0.08343545989111689,-1.6271169677298845,-1.1536754506020515,0.4286744876774562,-2.0021648094898015,-0.8056358999694295,-4.505180333424104,-0.9658806963005073,-0.45766854274232216,1.6842070701334277,-4.809596727145786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.025,1.0,0.0,0.0,1.0,1.2477733509195443,-0.016558898418133468,0.6049082986927133,0.9920094372605276,0.017457056338830327,0.05354786707189729,0.11289443569172108,0.17899265604430964,-0.009612896064567486,0.21682955697400802,0.7183058093850174,1.2511930017977337,0.9170426703979893,-0.5363384585240578,-0.5146459298316706,-0.01984741930162667,0.07356804436191111,0.9175321992394266,-0.743269912888996,0.05831197068820592,-0.7388991005511063,1.1361625554621353,0.25441724490753753,-0.4766644296685675,0.5667715449383248,-2.722722729198608,0.026997485996131942,-1.67579374005817,-1.1444417146744645,0.5968167738901964,-2.323932086268745,-0.8446810562095536,-4.251580174688277,-1.1385221066267004,-0.433154188538869,1.701738670321512,-4.723367118091879,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.033333333333333,1.0,0.0,0.0,1.0,1.249476763182817,-0.016350467164669515,0.6064696856883967,0.9912398858228245,0.020007513610908384,0.05884156373454163,0.11653694100063441,0.1893399202102811,-0.01477663900700709,0.20123136884357987,0.6962741311009419,1.1717577135313904,0.8818239939027138,-0.5586568557285977,-0.5140120408988362,-0.03373027630648936,0.06404962966915602,0.9231364314705383,-0.7637106124429613,0.05111674064451646,-0.7732133651992789,1.1260189216547538,0.2509105013724156,-0.4623942797039313,0.5278941654188067,-2.6243194576434092,0.12466062698863967,-1.628668431364669,-1.1426097230393626,0.7390595771209818,-2.542937975046433,-0.8800246196319299,-3.9817090178953896,-1.2756596924916463,-0.40716127677344616,1.715394717433496,-4.570322509375545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.041666666666667,1.0,0.0,0.0,1.0,1.2512846436906546,-0.016148831775989768,0.6078696996646924,0.9904650437467242,0.022503606916981764,0.0637563766850514,0.12003211775108147,0.20260858948343735,-0.019499951432118988,0.18495797810047268,0.6750863645530473,1.0744062518723823,0.8492420688316307,-0.580077116151448,-0.5125682527151932,-0.04699189315770449,0.054524548977921736,0.9298498588581097,-0.7856522124731032,0.04364489369434042,-0.8052609175160295,1.1149015605872745,0.2476312236279801,-0.44807451771134255,0.49059950311539907,-2.507536315426253,0.22661303062900817,-1.5433112726819906,-1.1453062146641182,0.8660177556608861,-2.6933275670541246,-0.9111681667874649,-3.7113503707239848,-1.3718828006217398,-0.37840706871471286,1.7086822818608105,-4.3389507938579905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.05,1.0,0.0,0.0,1.0,1.2532111407765998,-0.015943396918169733,0.6090964351787692,0.9896957172077281,0.02495702963479246,0.0682258892136793,0.12338866278874171,0.21841994188557365,-0.023920405816930744,0.16750959305461816,0.6543459284674631,0.9616621479583123,0.8191146007568706,-0.6004491276523686,-0.5102351570550194,-0.0594521308511892,0.04496119275808738,0.937570060731553,-0.8085994052271968,0.035930604531392046,-0.8350692047113453,1.1031542083110581,0.24460371689383706,-0.4339162416729178,0.4555783188545069,-2.37278100638854,0.34063047806034197,-1.4437778306968168,-1.1513894674443628,0.982204036758707,-2.788358988721602,-0.9382928977529458,-3.4458135478605456,-1.4270388965735048,-0.3466390933993502,1.6733192238320738,-4.019906952635926,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.058333333333334,1.0,0.0,0.0,1.0,1.2552704706357762,-0.015724288247417718,0.610136459924664,0.9889426818121857,0.02737836461925792,0.07219046305078906,0.12661490560846936,0.23686935469177428,-0.02817914915858627,0.14875574748601528,0.6338989348285731,0.8348140183700614,0.7914082657864555,-0.6196234662579236,-0.5068910780808542,-0.07105485700265143,0.03533472452051569,0.9462199261374215,-0.8321248622851299,0.028006678731791326,-0.8626911433137052,1.091117578977716,0.2418539054046576,-0.420185863980808,0.4236010539048003,-2.220210643935203,0.47034131518691513,-1.3409843774875922,-1.1601528472771472,1.0902365758288135,-2.8347779789178817,-0.9615314139096768,-3.187565722703831,-1.4413291963178532,-0.31164446690931935,1.6031628992665092,-3.6035599335435475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.066666666666666,1.0,0.0,0.0,1.0,1.2574781851564603,-0.015481961673789915,0.6109758044022563,0.9882164566134298,0.029777773649853352,0.07559440329031158,0.1297189473095249,0.2580877460602367,-0.03239545835930604,0.1286057577075939,0.6136678055152308,0.6945909028963291,0.7660913494835705,-0.637452638384622,-0.5023961351352375,-0.0818018704759824,0.02562531197013493,0.9557406703286999,-0.8558457048758281,0.019905080966230768,-0.8881953000897425,1.079132055039094,0.2394096424453484,-0.407196860018476,0.3955189866287811,-2.0502350355601617,0.6170730918065559,-1.2397680093111973,-1.171046509402772,1.1921905407780842,-2.8374867743515275,-0.9809841269154044,-2.9383827103355986,-1.4143732101186668,-0.273168271705741,1.4930458738399155,-3.0806735615266345,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.075,1.0,0.0,0.0,1.0,1.2598508084625841,-0.015207018431659043,0.6115997862052441,0.9875271104977936,0.032165349582066884,0.07838417261364258,0.13270839392357875,0.28222269857214943,-0.036570970987241054,0.10673553995023048,0.5935482553196302,0.5404101986357315,0.7426887643647483,-0.6537940501839263,-0.49660652655074494,-0.09171765715783806,0.01581728269713616,0.9660897684837229,-0.8794163085243221,0.011656943283201254,-0.9116641884859652,1.067544692142405,0.23730110087622858,-0.39530176608347606,0.37225649454602305,-1.862511343408284,0.7816415088825424,-1.1413471475233967,-1.1835432162380886,1.2901913233387696,-2.799646884040805,-0.9970670748095767,-2.7004967599598095,-1.3420787524989342,-0.23100264243635593,1.3376916330829813,-2.4391846965086885,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.083333333333333,1.0,0.0,0.0,1.0,1.2624056902635699,-0.014888159311824063,0.6119897481362256,0.9868851532656057,0.03455158202667718,0.08049939594096224,0.135586613298753,0.30728323004811237,-0.03999271704336556,0.08743573095955054,0.5766932454710093,0.3947060129888036,0.7182472879151414,-0.6684944941080934,-0.4893687766538618,-0.10082432293470568,0.00589959169950012,0.9772438590510127,-0.9025064862765082,0.0032872963860711576,-0.933203579422406,1.0567640758307784,0.23555959840474247,-0.38490199946709297,0.3548659083536363,-1.67585508394416,0.944611989765044,-1.0623888862855186,-1.2009284638717586,1.3760560971675395,-2.7527480972997376,-1.018794932598982,-2.4702871791128644,-1.2855464020674834,-0.19517566130217934,1.1746412631520697,-1.7960350852036144,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.091666666666667,1.0,0.0,0.0,1.0,1.265137385640897,-0.014515976369638405,0.6122089370979445,0.9862861891718742,0.03694529047051942,0.08207546999714949,0.13834094040138256,0.32926742974329004,-0.042076439732008517,0.07720542840594558,0.5660785974029683,0.29248404151437324,0.6901141824647856,-0.6817249682496623,-0.4808629933879942,-0.10942413859593003,-0.004198191700726482,0.9890240367698485,-0.9252954434793177,-0.005322972260115112,-0.9528356414711796,1.0461189187746136,0.23404817318785892,-0.37572441169760823,0.34232257645929615,-1.5206409807400445,1.0741118170686292,-1.0261604858964375,-1.2264211538264609,1.4355641240188866,-2.7442599592177364,-1.0542220699308376,-2.2370487560044405,-1.3409351467921615,-0.1779283281673466,1.0713239056057455,-1.353383692185458,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1,1.0,0.0,0.0,1.0,1.2680180870584625,-0.014094400452637728,0.6123562488449295,0.9857160879766825,0.039339699696566754,0.08334385365936901,0.14096093073077073,0.34725968999109286,-0.04378593593176863,0.07427444125537806,0.5577565836961175,0.22799297761462445,0.6605001159588696,-0.6938385104537608,-0.4714669130360513,-0.1179269976996463,-0.014540760864274228,1.0011699277846609,-0.9482441522634705,-0.014283071446109468,-0.9704877253558133,1.0344151567175757,0.23259412626862003,-0.36704660104033054,0.33230951348387866,-1.394332689343487,1.1710787973483872,-1.0234327545118393,-1.2551574911288492,1.4709351746939814,-2.770310596612864,-1.0929710623810314,-1.9972947413744935,-1.490460291764486,-0.17163567230111976,1.0297929685458962,-1.1069576504374445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.108333333333333,1.0,0.0,0.0,1.0,1.271029779750182,-0.013635088505542943,0.6124653085386749,0.9851697832854538,0.04171824049041955,0.08438723781691922,0.14345340918761712,0.3631902030585588,-0.046010291893332195,0.07382167046349832,0.5481666100881183,0.1774201690869503,0.6320336125019567,-0.7049638464053871,-0.46134501343218776,-0.12648135117112735,-0.025117483219540635,1.0135396230147482,-0.9714672867561988,-0.023539156633132302,-0.9861238871607545,1.0212779139118722,0.23118757864950693,-0.3585611955551766,0.32387328228533874,-1.2791312201520033,1.2537194950201247,-1.0322575156134752,-1.2828805429281043,1.4917606823300344,-2.8010576411460875,-1.1251894590245102,-1.7558767486960436,-1.6676465871996715,-0.1652468292575615,1.0144917692230915,-0.9406081409025857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.116666666666666,1.0,0.0,0.0,1.0,1.274166559960874,-0.013144793649049887,0.6125491866448206,0.9846457567439297,0.04407275392099198,0.08523627489291659,0.14582559285570273,0.3784737192090452,-0.04865691509709046,0.07433262698434068,0.5377246271676914,0.13184497311603693,0.604867057368996,-0.7151573641229608,-0.45057158811904924,-0.13513128962653756,-0.0359221032464093,1.0260326058234948,-0.9949284462825719,-0.033036229096517974,-0.9997523378340807,1.0066210469309145,0.22984001244766067,-0.35013840488661235,0.31663271113550223,-1.1689371912261026,1.3298663192650317,-1.043955235607702,-1.310242055057378,1.501604968215724,-2.823862245377946,-1.15136909378833,-1.5165969343065777,-1.848029148626955,-0.1574792398810121,1.0103753927150083,-0.8056395820653273,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.125,1.0,0.0,0.0,1.0,1.2774284084310383,-0.01262627375658523,0.6126130965414887,0.984144102191274,0.046400252808296585,0.08590062252548121,0.14808269889470252,0.3937914649874658,-0.051570547244014726,0.07521787519524689,0.5268568488643678,0.08757813596939054,0.5787321143885115,-0.7244461329258222,-0.43918057477777056,-0.1438806050979224,-0.046954850803830266,1.0385663724850103,-1.0185316575124979,-0.04272864152960447,-1.0114005027325308,0.9904774281014229,0.22856292465149006,-0.34172160567659315,0.3104459559175833,-1.0612294182884097,1.402982892395932,-1.0550797877518243,-1.3377717995814942,1.5020822364955677,-2.8339295138461673,-1.1724331607199143,-1.281298952027612,-2.0213906479638477,-0.14844790263734642,1.0112506068920235,-0.6816666652099546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.133333333333333,1.0,0.0,0.0,1.0,1.2808179078558375,-0.01208021705587752,0.6126590606581189,0.9836656262420636,0.04870017609019187,0.08638113121428598,0.1502282555617061,0.40944001916825806,-0.054663771417110166,0.07622461864573767,0.5157734630505226,0.04305056905786114,0.5533779302463495,-0.7328445210944343,-0.42718853991245037,-0.15271595275573463,-0.05821829990610087,1.0510673097650876,-1.0421606048466747,-0.05257678177518321,-1.0211073203678742,0.9729312027981837,0.22736588073703823,-0.33328422810507863,0.30527160004866966,-0.9549307924170236,1.4744882564195194,-1.0640078409068183,-1.3655927543363915,1.4940231410709748,-2.829808517161223,-1.1889251790405642,-1.0511917957520511,-2.183279076959128,-0.1383408151125648,1.014616706321425,-0.5602128038071508,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.141666666666667,1.0,0.0,0.0,1.0,1.284338637291421,-0.011506398852705758,0.612687766106536,0.9832114169555574,0.05097297293796071,0.08667486216433773,0.15226468358447645,0.42552850394293945,-0.05789506695758201,0.07723157365527326,0.504551493644822,-0.002417859015543672,0.5286310847353501,-0.7403616461327726,-0.4146057705041119,-0.16161406911303602,-0.06971473004277012,1.0634667581695265,-1.0656951327985182,-0.06254406118028054,-1.028920365995065,0.9540894434854374,0.22625724439961398,-0.32481132723790274,0.30110907585413077,-0.8496242880016203,1.544807794161528,-1.069649391219607,-1.3935918963429437,1.4779074380950297,-2.8114402498402535,-1.2011138947379176,-0.8272296295007564,-2.331668691744473,-0.1272614768929503,1.0195696307365576,-0.4379520912909285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.15,1.0,0.0,0.0,1.0,1.2879943893126238,-0.010904250572031232,0.6126993465827043,0.9827826343172335,0.053219449820695444,0.08677720431468981,0.1541937114692657,0.4420754248457838,-0.06124366696521873,0.07817101959867814,0.4932031395668054,-0.049127583379988085,0.5043785552309888,-0.7470049258944613,-0.4014417433430916,-0.17054344260939475,-0.0814448315118166,1.0756991004000047,-1.0890179423440123,-0.07259534668748184,-1.0348944808595535,0.9340700579357758,0.22524485612215572,-0.316291400926136,0.2979723985271542,-0.7452106711430817,1.6138750471352736,-1.0710162320020296,-1.4215410338645753,1.4540369112488705,-2.7793174349924588,-1.2091358099188743,-0.6102353850213937,-2.465566552077134,-0.1152500274546292,1.0259234737687417,-0.3138503140871973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.158333333333333,1.0,0.0,0.0,1.0,1.2917887778062909,-0.010273120587384164,0.612693729079059,0.9823804059188503,0.05544048291039287,0.08668278143355022,0.15601662194894486,0.45905438642665336,-0.06469594608485406,0.0789974831382758,0.4817118989317487,-0.09721453064748016,0.48054516073394404,-0.7527818239851573,-0.38770785305185734,-0.17946433964640318,-0.09340708060717971,1.087700706690341,-1.1120170900483926,-0.08269632467892844,-1.0390909557454215,0.9129966676174852,0.2243364106087035,-0.3077126026750904,0.2958782372860108,-0.641748717780597,1.6813772972881669,-1.06710409547367,-1.449153937652965,1.4226106092223079,-2.73412618794735,-1.213079990129365,-0.4009490970355589,-2.5844095991831195,-0.10231321813926719,1.033829739135832,-0.18792587727104126,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.166666666666667,1.0,0.0,0.0,1.0,1.2957250301962602,-0.009612390095683923,0.6126707963541015,0.9820057718687042,0.057636895132484406,0.08638584737385928,0.15773438974923715,0.4782893392444291,-0.06881561453588356,0.08062105249665633,0.4678205777133295,-0.15960465371534827,0.4583562602708927,-0.7577007378574713,-0.3734187883882888,-0.18832851086728924,-0.10559739713936601,1.0994092772203765,-1.1345867121431348,-0.09281334652297125,-1.0415769658101461,0.8909965646160571,0.2235396358198346,-0.29906090527387214,0.2948403005726368,-0.5233779878239164,1.7481238132604582,-1.0233116242289104,-1.471995005920721,1.3801090600862365,-2.6460247197042186,-1.2093821797870175,-0.19993360031269614,-2.663686817061317,-0.08323133872850608,1.042169032347151,-0.027101192743551605,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.175,1.0,0.0,0.0,1.0,1.2998409213958193,-0.008921957083391241,0.6126398211811899,0.9816682651845524,0.05980917851858522,0.08577164284746551,0.15935339525015396,0.5021910813352553,-0.07402150479751188,0.08371721184950363,0.44993162595301656,-0.2521341089985826,0.439067498838581,-0.7615047904488892,-0.35857245616418304,-0.1965195333835517,-0.1179403307058584,1.110702524358445,-1.1561175020434629,-0.1028526943420454,-1.0424231824172998,0.8686018873331299,0.22294922162989506,-0.29034311880263786,0.29542655074028495,-0.3727732249508531,1.814799760842185,-0.8972492724963571,-1.4859178499314694,1.3242460660372535,-2.4814376650792713,-1.195573363998219,-0.010246014393096026,-2.669103755893729,-0.05287582023752124,1.0471339518899914,0.21456590797426123,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.183333333333334,1.0,0.0,0.0,1.0,1.304181533003206,-0.008195799342894624,0.6126070516378981,0.9813785918730505,0.06196703837857476,0.08470207348072524,0.16087791742791938,0.5294869337912453,-0.07942514385080063,0.08678006764854593,0.4312853777541309,-0.3652421494946715,0.4212374982908966,-0.7639136249399855,-0.3431721257075857,-0.2032826654088952,-0.13036269463822384,1.121480044987664,-1.1759440065611226,-0.1127395692562749,-1.0417477327166977,0.8465115020178283,0.22265837214920925,-0.2816086727423723,0.2984163990388745,-0.20577013572229186,1.879111509695427,-0.7125706967497525,-1.4953602954302367,1.2611537298195952,-2.2692998576999335,-1.1773528137535527,0.16278394430089715,-2.610560127413344,-0.01690712094800706,1.047058244615059,0.5185121892307443,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.191666666666666,1.0,0.0,0.0,1.0,1.3087556646489282,-0.007424327084351021,0.6125660492087448,0.9811382562456896,0.06412412066129794,0.08314549903731074,0.16230417514793696,0.5574107146675865,-0.08429181714933495,0.08841530242866796,0.41425223224119156,-0.48179580414091905,0.4031578363404389,-0.7649342927109274,-0.3272539310025926,-0.20839571166271423,-0.14286300229636234,1.1317217531887716,-1.1939391663384618,-0.12247524123793795,-1.0397101166789515,0.8250925518762409,0.2226674362807616,-0.27289214805905354,0.30406842056079736,-0.04476192935500389,1.9373565066225695,-0.5111965329150975,-1.5044269901377882,1.1957461343757059,-2.0519513849260607,-1.1590897557245634,0.3169331974492806,-2.517713891978721,0.018656276330988875,1.047253307742989,0.8337220212225349,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2,1.0,0.0,0.0,1.0,1.3135573506704687,-0.006602890391788929,0.6125111004269819,0.9809451546192525,0.06628582253036669,0.08110787551089242,0.16362856074247545,0.584636177826981,-0.08872206499135825,0.08855849346935084,0.3983070139150652,-0.5951479025660383,0.3845236082383102,-0.7646596570959022,-0.31088285059720955,-0.21180260762414682,-0.15543647780718697,1.1414091472272592,-1.2101431963098903,-0.1320577318516843,-1.0364655127592097,0.804549603818183,0.22296931008805906,-0.2641544509466558,0.3123117660592501,0.10328850024542202,1.98643092189282,-0.30589269130112284,-1.512411165643471,1.1275220217786996,-1.8427084385608783,-1.1401085559973565,0.4533719708489592,-2.405609811589593,0.053503541052000725,1.0555171421969023,1.1291464588115074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.208333333333333,1.0,0.0,0.0,1.0,1.3185753023354836,-0.005730834761906034,0.6124389555676342,0.9807953683133472,0.06845229287341562,0.07861132896706943,0.1648483789838309,0.6106029523007934,-0.09289411039941187,0.08739639103097341,0.3829705048129835,-0.7022689191837846,0.3652924674433607,-0.763212817706837,-0.2941467489710456,-0.2134939231843996,-0.16806985505708685,1.1505137868850832,-1.2246509736478097,-0.14147705050456055,-1.0321539171648022,0.7849990550164143,0.22355916196496162,-0.25530019568910517,0.3228875282076558,0.235948231508174,2.02419325841685,-0.10034533212077479,-1.5184160043114248,1.0553540784733118,-1.6458505560052128,-1.119628559385194,0.5739472012717206,-2.282651794463484,0.08789898007326657,1.0772126679201706,1.3874283222020234,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.216666666666667,1.0,0.0,0.0,1.0,1.3237966528816492,-0.004809985411131259,0.6123484271680667,0.980683994355403,0.07062070910068441,0.07568592041579109,0.16596162240780885,0.6350977153906106,-0.09694847418994534,0.08512517060500643,0.36794647511587725,-0.8016001723510175,0.3454544780043559,-0.760727186570766,-0.27714629629026205,-0.21347502982615973,-0.1807434112123774,1.158998381868481,-1.2375740389099772,-0.15071820784143752,-1.0268997260713477,0.7665054072437916,0.22443429308928017,-0.24620090648131962,0.3354355714292838,0.3525268833283879,2.04960821983227,0.10398573858870996,-1.5217668330162433,0.9783690002036982,-1.4625832405106598,-1.097200053009499,0.6804035056651259,-2.153938919978402,0.12203831159143919,1.1151443297550545,1.5996949149976991,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.225,1.0,0.0,0.0,1.0,1.3292084656561138,-0.003843707391830411,0.6122397024330172,0.9806056295526316,0.07278647061616744,0.07236610107907689,0.16696669248618298,0.6584096306597076,-0.10057749499434614,0.08145712231757316,0.35278475671192444,-0.8952939399846555,0.3228756116341205,-0.7573373696513639,-0.2599866119738411,-0.21176082754125444,-0.19343263560735757,1.1668199368884782,-1.249027360989654,-0.15976371805471887,-1.02081385873705,0.7491000730167743,0.22559313382481894,-0.23671445685985426,0.34954911012428413,0.4569226079108524,2.0650552955830466,0.3059560645927073,-1.5213254500196327,0.8965449184835306,-1.2905200284979346,-1.0739048239115163,0.7710617401274122,-2.0118591184435375,0.15474974128422414,1.1658665245509248,1.7773745716656453,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.233333333333333,1.0,0.0,0.0,1.0,1.334800310922481,-0.0028270969752537374,0.6121069476786434,0.9805595616013625,0.07494469635054468,0.06866506392685053,0.16784322338801236,0.680737394848961,-0.10365452180661308,0.07624009720450642,0.3375239335632126,-0.9842814371841051,0.2963712262089962,-0.7531118097722518,-0.2427287080305446,-0.20837576208294795,-0.20609883537937126,1.1739407971765399,-1.2590827060516094,-0.16861662157329613,-1.0140486970692242,0.7329744219363993,0.22701345544401724,-0.2267697977388042,0.3650584809570446,0.5511108874417814,2.0720354469010944,0.5044308385566537,-1.5165132889290052,0.8100318545488427,-1.1286203485360558,-1.0505664379456143,0.8453256846049451,-1.8529161719586607,0.18506681919952805,1.22699753296537,1.927373317415495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.241666666666666,1.0,0.0,0.0,1.0,1.3405618043628516,-0.001760705523633021,0.6119480093883534,0.9805423592145713,0.07709151201568376,0.06461044760436413,0.16857956762829165,0.7015564080389869,-0.10690702970281367,0.07025828342449549,0.32263981140555353,-1.0632649725690924,0.2692268986980441,-0.7481521881940009,-0.22545268785882286,-0.20335364689864355,-0.21870785708950766,1.1803204677976256,-1.2678377001319217,-0.17727315868714577,-1.0067250973269677,0.7182181368174633,0.22867758081147774,-0.2162644979770981,0.3816719987478757,0.629568855039524,2.06709439805268,0.697640023168653,-1.5080116866861493,0.7181219859713783,-0.9809725691225957,-1.0252673677465913,0.9090773130315566,-1.696269235198995,0.21473294311509017,1.3043111118304225,2.02675954761539,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.25,1.0,0.0,0.0,1.0,1.3464808214376396,-0.0006559096369081812,0.6117684199103393,0.9805454930110777,0.0792203565634643,0.060257449458387374,0.16918543384912685,0.7205872987246988,-0.11067108874733748,0.0639668556303506,0.3077938492154711,-1.1296752918308122,0.24300593190475137,-0.742618995521593,-0.2082771347296666,-0.1967484283634704,-0.23123236349080709,1.1859094969427295,-1.2754322488703194,-0.18570441103573931,-0.9988974085186982,0.704703268016416,0.23059233782926875,-0.20503127920829717,0.3988378067506344,0.6910455330963305,2.049532698091174,0.8829276007555831,-1.4956281368296154,0.6203758565434203,-0.8488117724913735,-0.9967697899680811,0.9657547334356686,-1.5522183390594746,0.24493591486210664,1.399086028293568,2.0665233373158856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.258333333333333,1.0,0.0,0.0,1.0,1.3525457893192612,0.0004789940445941453,0.6115715621594321,0.9805628762529994,0.08132189694608326,0.055653388411561124,0.16966406558302038,0.7379833141359038,-0.11475460940605656,0.057218164657638876,0.2925816406480983,-1.1848663865331375,0.21662377040980285,-0.7366347626423954,-0.1912938095573033,-0.1886381868860505,-0.24363499270333458,1.1906600654066826,-1.2819845630067779,-0.19388598851994712,-0.9906291851030399,0.692347831166472,0.23275984605917951,-0.19294639750553863,0.41611405436980714,0.7389607293003064,2.0221674314030076,1.057436631166706,-1.4786830996675633,0.5171676288952476,-0.7302695642726897,-0.9657229485025715,1.0146793413781863,-1.417011648372264,0.27503867439844676,1.5063579601073913,2.0581819570592566,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.266666666666667,1.0,0.0,0.0,1.0,1.3587456974356853,0.0016366928502420444,0.6113593706032575,0.9805896565111717,0.0833874430079339,0.05084259391681824,0.17001614786833985,0.7537884881800967,-0.11909314939571466,0.04994656541884007,0.2770405805486873,-1.2294700370642528,0.18963968455265603,-0.7303029833665879,-0.17457434420628315,-0.17912448451069196,-0.2558770818185998,1.194528957424317,-1.2876034082748642,-0.20179979351078217,-0.9819860861623951,0.6810864072102116,0.23517631573590952,-0.17992531320650731,0.4331408393682887,0.775330523206319,1.9872072904869997,1.2184077695542617,-1.4570537584805916,0.40901335405307826,-0.6244312514044648,-0.9327490606719385,1.0557230286948127,-1.2893769794674603,0.30445203777694496,1.6217986317561284,2.0103343701556886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.275,1.0,0.0,0.0,1.0,1.365069294460489,0.0028101972032006975,0.6111327375100809,0.9806219549225008,0.08540860295323772,0.04586766180313214,0.17024132772772277,0.7679769690392805,-0.12363746053716693,0.04212627749187739,0.26119310315537675,-1.263866731440548,0.16187505885465275,-0.7237125872556234,-0.15817368804918663,-0.1683313907268128,-0.26791922201134444,1.1974769546409005,-1.2923917505301856,-0.20943180619781276,-0.9730338012914597,0.6708582148420144,0.23783404668879526,-0.16591642030960316,0.4496196272057353,0.8017201603489066,1.946690063688968,1.3630037048466193,-1.4307258179396665,0.2963211079741779,-0.5305779944754763,-0.8983134223586342,1.0889555910840687,-1.169061037087682,0.33271748465565465,1.741761008181859,1.9295842477142489,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.283333333333333,1.0,0.0,0.0,1.0,1.371504980198576,0.003992812998615491,0.6108917185836861,0.9806567305380323,0.08737735613173894,0.040770069776169586,0.17033900286346332,0.7804766924425905,-0.12833025399829792,0.0337637585145404,0.24505491865394496,-1.288352345641752,0.13327237879832854,-0.7169409806941062,-0.14212950981146702,-0.15640775609658164,-0.27972251211759425,1.19946764255722,-1.2964463748494555,-0.21677168388342608,-0.963836826310994,0.6616020565920836,0.2407216071468371,-0.150895963070143,0.4653005768301928,0.8194710433484631,1.90260399017478,1.4883459227539193,-1.3997705928361603,0.17935940446113907,-0.44798095165358376,-0.862820544788534,1.1145609335847717,-1.056316555507144,0.35939349237058604,1.863049145244705,1.821362521936326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.291666666666667,1.0,0.0,0.0,1.0,1.378040205108178,0.005177994941137358,0.6106358158872564,0.9806917744629585,0.08928591309380797,0.03559015962915765,0.17030857219005016,0.7911677069016024,-0.13309605356532983,0.02489359932692109,0.2286402921837899,-1.303221522950476,0.10383438738069567,-0.710054736533149,-0.12646362154627364,-0.14352562534758082,-0.2912487318919471,1.2004662780485862,-1.299858099724412,-0.223812148610955,-0.9544577857317135,0.6532529389168953,0.24382393822830503,-0.1348656012221914,0.4799756692380074,0.8297913533946555,1.8568566629065808,1.591662852075178,-1.364334555444664,0.05823339739830846,-0.3758296403161454,-0.8266527635517407,1.1327928866055537,-0.951682972114638,0.38400887704013065,1.982751541489421,1.6904106662208063,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3,1.0,0.0,0.0,1.0,1.384661249374986,0.006359470133435552,0.6103641332781475,0.9807256581507315,0.0911269019036672,0.03036710951557545,0.17014966898007142,0.7999066856330227,-0.13783493527925877,0.015572474639786456,0.21199500860688386,-1.3087918034928538,0.07361504312557546,-0.7031111248041952,-0.111181898763024,-0.12988004189532867,-0.3024614213750053,1.200438199180525,-1.3027102021880579,-0.23054922994262175,-0.9449569448675681,0.6457406737235063,0.24712175509750595,-0.11785010404531931,0.49347408793387293,0.8337280397453051,1.8113244283193914,1.6702846711647619,-1.3246801004767694,-0.06713963135012158,-0.31312452203598795,-0.7902160624468185,1.1439566356499764,-0.8558334046240579,0.4060236717429927,2.098199866042938,1.5410131727247345,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.308333333333334,1.0,0.0,0.0,1.0,1.391352938939863,0.007531342082122283,0.6100755511559625,0.9807576846689459,0.0928935150905307,0.025138765478194863,0.16986230095945354,0.8065129590643352,-0.14242310520300652,0.00588454224449677,0.1951723996141646,-1.3054413205615099,0.04269972501847943,-0.6961592692040606,-0.09627488107428378,-0.11568754749483479,-0.31332673356655993,1.1993472841927508,-1.3050768417583452,-0.23698241631840197,-0.9353918418042139,0.6389890488398277,0.2505909994240216,-0.0998956034548091,0.505659222116753,0.8322281099009565,1.767704482859431,1.7219138734835506,-1.2811400411925977,-0.1970354620850534,-0.25867465332100714,-0.7539156625355031,1.1484038664530138,-0.7695362581252341,0.42484687100893925,2.2069013331127096,1.3771789065059648,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.316666666666666,1.0,0.0,0.0,1.0,1.3980981981412426,0.008688111279747732,0.6097689816577118,0.9807878498683262,0.09457953468809505,0.019941281677666053,0.1694468956751673,0.8107791278443305,-0.14671133609632636,-0.004060679921320011,0.1782504248373351,-1.2936002964597078,0.011207944708009177,-0.689240656305846,-0.08172015738203349,-0.1011814773372695,-0.32381375539488194,1.1971542748124409,-1.3070214464100747,-0.24311449098488014,-0.9258168804266845,0.6329150694214191,0.25420253628098827,-0.08106841516010749,0.5164270697089723,0.8261044560560338,1.7274578222451509,1.7447208705827568,-1.234137268836265,-0.331946853543581,-0.21105253133883561,-0.7181727900656298,1.1465358408901327,-0.6936340356904869,0.4398250302082629,2.306525794853898,1.202711441853177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.325,1.0,0.0,0.0,1.0,1.4048778999811176,0.009824868786699354,0.6094435151765952,0.9808167312988774,0.0961795943231028,0.01480904020747071,0.16890446284274316,0.8124822154987787,-0.15052849249993905,-0.014134175653010783,0.16133824325310914,-1.2737566773888565,-0.02072344362783001,-0.6823908616031267,-0.06748391737019793,-0.0866088663184555,-0.33389568804716435,1.1938148366336911,-1.3085943839473257,-0.2489519628194958,-0.9162829111227117,0.6274284815783195,0.2579214165941593,-0.06145350687391081,0.5257044128143059,0.8160392149460538,1.6917844675567648,1.737388135740768,-1.1841721857262366,-0.47257303464526945,-0.16858479784053415,-0.683430972830934,1.1387784508932675,-0.6289524300059202,0.45023587373356877,2.3948873088175975,1.0213244647027464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.333333333333333,1.0,0.0,0.0,1.0,1.4116705893821384,0.01093734957323097,0.6090985763804194,0.9808454297730951,0.0976892540735462,0.009774267460377467,0.16823648898922275,0.8113843233020441,-0.1536890062489226,-0.0241871491952085,0.14455708342035312,-1.2464547078080666,-0.05295473950194668,-0.6756400027234117,-0.053523749589420744,-0.0722250084082567,-0.3435499584903192,1.189278057568353,-1.3098311930407502,-0.25450500719872904,-0.9068372395784634,0.6224325289213204,0.2617064675098811,-0.0411536266798142,0.5334491441206848,0.8026203850045066,1.6615423498111133,1.6992260498725815,-1.1317744026872911,-0.6197897763427163,-0.12938543489266152,-0.6501265627635694,1.1255767639704994,-0.5762843911989268,0.45531358432727154,2.4699375259215257,0.836673224581197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.341666666666667,1.0,0.0,0.0,1.0,1.4184523768750685,0.012022016148217955,0.6087340782271621,0.980875461134287,0.09910509046356301,0.004866949499534757,0.16744498676100147,0.8072482675344806,-0.1560011131181021,-0.03405436957411036,0.12804274524559073,-1.2122505795669576,-0.0853354471295433,-0.6690138551863849,-0.039791544873346046,-0.05828843215391248,-0.3527585947586192,1.1834850070279792,-1.3107508078622034,-0.25978740553222196,-0.89752329838987,0.6178237417250041,0.26550997633294715,-0.020287881441885387,0.5396489665573259,0.7863162549415481,1.6372569136484276,1.6301026122994628,-1.0774974295264106,-0.7746170192538981,-0.09138284029234445,-0.6186759986403267,1.1074065090020047,-0.5364288789464511,0.45426642424237773,2.5298015933256854,0.6522562764725248,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.35,1.0,0.0,0.0,1.0,1.425196943763675,0.013076090893083758,0.608350524358084,0.9809086564304209,0.10042472516463745,0.0001148105585414087,0.16653248672262005,0.7998485566707432,-0.15727910856687896,-0.043561828388460525,0.11193453767020128,-1.1716958715605448,-0.11772312025173706,-0.6625347318077193,-0.02623613436194695,-0.04505663153659899,-0.36150824898242606,1.1763677739141214,-1.311354240378956,-0.2648162738427345,-0.88838046442843,0.6134920476055462,0.2692775745805874,0.001009733208947227,0.5443200820618935,0.767504702134687,1.6191809279541836,1.5303026066314644,-1.0218766277945257,-0.9381570791145855,-0.0523834672397161,-0.5894529169224083,1.0847513673536957,-0.5101443306077358,0.44629780071485214,2.572781144948117,0.4714158110437783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.358333333333333,1.0,0.0,0.0,1.0,1.431875670379302,0.01409754282812235,0.6079490385443095,0.9809470794393056,0.10164679500640213,-0.004456633859700576,0.1655019480824111,0.7889837484925241,-0.15735560614775204,-0.05253561528799836,0.09636503764446835,-1.1253125936739654,-0.14999968010067685,-0.6562221101508068,-0.012805196074109652,-0.03278338871005474,-0.36978987188852797,1.1678490557094028,-1.311623865649532,-0.2696116208142621,-0.8794441089339751,0.6093213362148752,0.272948273011528,0.022591804307249892,0.5475058967413888,0.7464965484725639,1.6074044356450496,1.4002937800870885,-0.9653937875121588,-1.1115247032632425,-0.010148734931583192,-0.5627671326777961,1.0580826590225167,-0.4981165426539391,0.4306268111457068,2.597363436922852,0.2973029223601098,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.366666666666666,1.0,0.0,0.0,1.0,1.4384579058973332,0.015085032095733817,0.6075313323836636,0.9809929583149528,0.10277086045072693,-0.008823891692502134,0.16435663939769662,0.7744898769536379,-0.1560935897819858,-0.06081060093172984,0.0814510256858258,-1.0735620641257206,-0.1820824016668277,-0.6500931226665099,0.0005539395654705435,-0.021718401868480845,-0.37759814544096204,1.1578423621930674,-1.311523385961149,-0.2741957260540311,-0.8707457534447214,0.6051901052279806,0.2764546880996825,0.044299123824328095,0.5492751307678954,0.7235533293798824,1.602002384919275,1.2404289472520924,-0.9084504283120687,-1.2957708487721042,0.03752129440038221,-0.5388445148550713,1.0278479541861807,-0.5009488862181444,0.4065105114977241,2.6022412652036033,0.13280031937281223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.375,1.0,0.0,0.0,1.0,1.4449113848491597,0.016037814138726954,0.607099612060327,0.9810486362405441,0.10379726148625337,-0.01296518570894102,0.16309998711855292,0.7562552388132517,-0.15339784413844668,-0.06823915110069757,0.06728634038233261,-1.0168174584274938,-0.2139352889287201,-0.6441628879944754,0.013894843674544933,-0.012109572922519869,-0.3849307123603958,1.1462528748965344,-1.310998510742859,-0.2785923627285133,-0.8623133096975387,0.6009721881112394,0.27972344820315675,0.06596249206064328,0.5497192353976024,0.6989070596310087,1.6031990596654428,1.0506368596593847,-0.8513462000733352,-1.4918019841137875,0.09270319053056753,-0.5178106790585757,0.9944635761663312,-0.5191492741297932,0.3732639408120386,2.5863416254975746,-0.019570270500359754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.383333333333333,1.0,0.0,0.0,1.0,1.4512028088718947,0.016955613024593964,0.6066564328451268,0.9811165435249857,0.10472693679058849,-0.016860039178863716,0.1617353882456132,0.734239333721304,-0.14922576526228948,-0.07469932708130997,0.053937613102987725,-0.9553420344462592,-0.2455815184240451,-0.6384446716726597,0.02727392389322792,-0.004207787540824437,-0.3917872487755176,1.132978995791171,-1.3099783327856396,-0.2828259040383407,-0.8541713605086159,0.5965376173258173,0.28267575377988313,0.087404817582621,0.5489489595928894,0.672781721726623,1.6115204780483252,0.8301661644448607,-0.7942613990257541,-1.700292483951471,0.15726790090628828,-0.4996791780420118,0.9583123915024538,-0.553103875999581,0.33027715139631986,2.5488766625941657,-0.15776755267647324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.391666666666667,1.0,0.0,0.0,1.0,1.4572986409655848,0.01783847626259085,0.6062045136445097,0.9811991918366205,0.10556122547419813,-0.020488779377961727,0.16026597747243165,0.7084997483411772,-0.14359857785306201,-0.0801027004818043,0.04144274858994229,-0.8892734064357064,-0.27711827612734563,-0.6329498592990317,0.040753518308683685,0.0017265298182278096,-0.39816840234415835,1.1179146668306765,-1.3083773790610875,-0.2869203490292135,-0.8463414365058312,0.5917537901779131,0.2852280673930954,0.10844376977054604,0.5470897761863278,0.6454174094908871,1.6279108398419253,0.5774365509942263,-0.7372395126381948,-1.921581451097918,0.23279554686667758,-0.4843424438272248,0.9197450163270959,-0.6030221224812937,0.277030703407376,2.4894344152123966,-0.28039631532693177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4,1.0,0.0,0.0,1.0,1.4631661939857328,0.018686621348191247,0.6057465207505794,0.9812991903455713,0.10630166634545483,-0.023831978764844265,0.15869433369698255,0.679229701633906,-0.1366145400434976,-0.08440286981072016,0.02981014796500714,-0.8186106589964034,-0.3087346974900849,-0.6276877148478116,0.054405771223926674,0.0054161549757460025,-0.4040745739861542,1.1009526382728723,-1.3060984070045283,-0.29089827810212776,-0.8388422769031643,0.5864872486177958,0.28729293217000607,0.12889539116949428,0.5442756876707738,0.6170978778902647,1.653806440915731,0.2900092183379961,-0.6801646215218926,-2.155542335170022,0.320468205264377,-0.4715611973034195,0.8790773724635259,-0.6688386032150961,0.21311400928037294,2.4081217987825343,-0.3869403196541521,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.408333333333333,1.0,0.0,0.0,1.0,1.4687751103799098,0.019500274823166144,0.6052848162698647,0.9814192834684293,0.10694979296250552,-0.026869833276814407,0.15702211271466746,0.6468045978508269,-0.12846549165577614,-0.08760675649191843,0.019014200996844366,-0.7431958855089877,-0.34073154789585103,-0.6226648946675273,0.06831695899061253,0.006560016790527744,-0.4095044793695232,1.0819889612445095,-1.3030362423066812,-0.2947797023176038,-0.8316901469647724,0.5806064801243281,0.2887799675477683,0.14857913308358828,0.5406407708587586,0.5881806511076948,1.691187786903161,-0.03538357203222264,-0.6227303406660822,-2.401418778269311,0.4209059224109346,-0.46094579184124407,0.8365711446965052,-0.7500693865659769,0.13825405899904997,2.305752797816884,-0.4780712573681667,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.416666666666667,1.0,0.0,0.0,1.0,1.4740992953896757,0.020279486452938738,0.6048211406263704,0.981562410728202,0.10750689107320069,-0.02958143576463178,0.15524960829411763,0.6143748128683881,-0.12071755202901144,-0.08993665053124332,0.005364848794327748,-0.6758468598505936,-0.3734562716783265,-0.6178847039960167,0.08259223433897936,0.0048264287752089585,-0.4144534129972556,1.0609289919683837,-1.2990833082976794,-0.2985807079661485,-0.8248994244915558,0.5739860921750295,0.2895971664866569,0.16732460446644234,0.5363078333813044,0.5690034384745424,1.7286695312077849,-0.34458588773189486,-0.5541985771782698,-2.6514891315030154,0.5510410284788669,-0.44731842756781437,0.7824996543752283,-0.800750033543205,0.06412166461415625,2.197701175752018,-0.5413287734770766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.425,1.0,0.0,0.0,1.0,1.4791661735928197,0.021017561914822624,0.6043534400724171,0.9817314271128554,0.10796089118368159,-0.03205628715734047,0.15336311632092797,0.5869693194355408,-0.11544044747930732,-0.09206525244355106,-0.015442944465423658,-0.6351317469172396,-0.40696831904287306,-0.6131815040262849,0.09712811784407561,0.0008169186616628299,-0.4187411223224944,1.0377974757194592,-1.2938522251653668,-0.30223500944373405,-0.8186484860585186,0.5672606462319414,0.28984866195800424,0.18520748601278858,0.5316186246341407,0.5724126630129511,1.7457672995583493,-0.5498026412869891,-0.46157916641613506,-2.889476087988614,0.7301996595871962,-0.42481330073117496,0.7011345913644229,-0.7497838161955461,0.007800007797380548,2.1089667610329337,-0.5614205567444741,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.433333333333334,1.0,0.0,0.0,1.0,1.4840402696584052,0.02170930273385154,0.6038764109253156,0.9819267673574805,0.1083015034672307,-0.03443082289020403,0.15134439642407047,0.56562320801196,-0.11235140907974434,-0.09452614326264153,-0.040537699609570016,-0.616349346165871,-0.4409003849485114,-0.6083444929458008,0.11168835599828518,-0.004336948579574192,-0.42214639910419116,1.0127710571685735,-1.286913313971226,-0.3056609296450014,-0.8132138479688155,0.5614896952384371,0.28972716661661324,0.2024740504836579,0.5269508241022298,0.5921082429053004,1.744673645670268,-0.660497400658224,-0.3517976731003869,-3.1062837372068275,0.9446964664287183,-0.39682976893141486,0.5932047875165058,-0.6019435925020145,-0.034064581875070665,2.043535941118839,-0.5527436418084442,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.441666666666666,1.0,0.0,0.0,1.0,1.488764414216296,0.02235782817173758,0.6033864125271375,0.982147093584261,0.10853345163805703,-0.03675262997550319,0.14918719995260227,0.5484979944705236,-0.1103324599113909,-0.09725823098562171,-0.0661189746574391,-0.6057000608016266,-0.4748669183915022,-0.6033130333111966,0.12620601193858008,-0.01019137134930757,-0.4246044168741675,0.9860260800993454,-1.2781072840582215,-0.3088488389259243,-0.8087617395999102,0.5572282530235745,0.28928091892675306,0.21926641836476923,0.5224062306039999,0.6170413331719304,1.740411218843151,-0.735756288854654,-0.23623034283737798,-3.303156244372869,1.1731655683603393,-0.3680221849724019,0.46830883768698595,-0.4002042726242583,-0.07216520991644271,1.992544024752046,-0.5381881941075517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.45,1.0,0.0,0.0,1.0,1.4933683568611171,0.02296496173573167,0.6028821412691114,0.9823912100893644,0.10865918716573239,-0.039040640848807304,0.14688948140051142,0.5344456802674784,-0.10913090060889566,-0.10008963292129898,-0.09195064286757075,-0.5983432522363504,-0.5087222587410661,-0.5980604707262687,0.14069520964567103,-0.016599553393818425,-0.4260835714848141,0.9577184530956924,-1.2673605544985538,-0.3117946327278748,-0.8054087006740324,0.5548196240280328,0.28852441311800586,0.23568311756285867,0.517981020867104,0.64459815404174,1.7397467304847114,-0.8006875041106986,-0.117534006283736,-3.481928396532168,1.4080004777895994,-0.3386727995452754,0.3306922457028505,-0.16276539737344997,-0.10914841077517723,1.9520462843301867,-0.5264266898528858,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.458333333333333,1.0,0.0,0.0,1.0,1.497875376473578,0.023530852502102625,0.6023628778505672,0.9826581404221547,0.10867897106410897,-0.041302651531661544,0.1444505150125032,0.5229087913984076,-0.10869833442603072,-0.10298697862619759,-0.11813699274679033,-0.5923310100908157,-0.5424609856374051,-0.5925697307438342,0.15520179077999194,-0.02353616308448588,-0.42656331697889643,0.9279939401571426,-1.2546406094283948,-0.3144933855850122,-0.8032502021715293,0.5545154964006836,0.2874617787471668,0.2518005231036057,0.5136324524397852,0.6740064518279709,1.7453128502275268,-0.8654888397876451,0.003264842519148381,-3.6434426084403038,1.6453326036434923,-0.30870883007477534,0.18233947462453104,0.10218864272496964,-0.14586055553427624,1.9201691849320675,-0.5208677174364862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.466666666666667,1.0,0.0,0.0,1.0,1.5023060778553337,0.024054727594134562,0.6018278321894648,0.9829470136444177,0.1085918591513258,-0.04354176896847912,0.14186997867442608,0.513687524065816,-0.10903519065312711,-0.10598722894509134,-0.14477163567027354,-0.5868161108321021,-0.576101063392713,-0.5868270298624692,0.16978375714946314,-0.031024367390279178,-0.4260291574428283,0.8969944096216873,-1.239938344437829,-0.3169397798957877,-0.8023697094302902,0.5565227680734489,0.28609340385910126,0.26768593731172646,0.5092998922431625,0.7049887793625031,1.7581398380013764,-0.9341800918095803,0.12553918783546614,-3.787972587328776,1.8827744445221706,-0.27811491580776226,0.02457197397061739,0.39034339399869333,-0.18259553962037822,1.896305971816884,-0.5233648475895891,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.475,1.0,0.0,1.0,1.0,1.5066805350160077,0.024535376967986338,0.6012759291415771,0.9832569811755736,0.10839625301422733,-0.04575892539825501,0.13914769868285604,0.5067846426427776,-0.11016152825390181,-0.10915937738521428,-0.17191988332873306,-0.5813844562705285,-0.6096499099341841,-0.5808199177544592,0.1845041214133482,-0.03910583128131222,-0.42447099718163867,0.864861063701663,-1.2232610353530253,-0.31912863418180826,-0.802840669272019,0.5610212196339952,0.2844185197534938,0.2834056226338871,0.5049097049799587,0.7374266132784957,1.778675685909401,-1.0082249402643404,0.2488100629238621,-3.9155095610226187,2.118507332654027,-0.24692014482759816,-0.14137345263047107,0.698782188530509,-0.21941644428664753,1.8806208218233722,-0.5354896478043636,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.483333333333333,1.0,0.0,1.0,1.0,1.511019483821448,0.024971377502028574,0.6007057409010064,0.9835871716229883,0.10809014361022705,-0.04795387497119822,0.13628361071143133,0.5023113318648725,-0.11210618796306547,-0.11258790308564832,-0.19963223112379458,-0.5757920051300207,-0.643097943250304,-0.5745365863078276,0.19942835191461983,-0.04782811639468485,-0.42188232306076395,0.831735916937977,-1.2046298888935951,-0.32105511564291433,-0.804725933640798,0.5681691378822907,0.28243646312099047,0.29902961767544933,0.5003750647797565,0.771255764637151,1.807138115082953,-1.0879709902768089,0.37267599733213363,-4.025935532903982,2.3508930842048237,-0.2151733416043966,-0.31413821963486965,1.0249531027830638,-0.2562727493229555,1.873727318403624,-0.5589015947635256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.491666666666666,1.0,0.0,1.0,1.0,1.5153449175285003,0.02536118209729854,0.6001154712509978,0.9839366687567912,0.10767120836636918,-0.05012557937138503,0.13327778906327406,0.5004258485049017,-0.11489675825600479,-0.11636452552022666,-0.22795247442499159,-0.5698583606019318,-0.6764190322553816,-0.5679656550105067,0.2146230899980641,-0.05723868111925903,-0.41825973055943644,0.7977621381532634,-1.1840794839496116,-0.32271485654188153,-0.8080763062659335,0.5781037713470463,0.2801473072647779,0.3146344112739475,0.4955946784005666,0.8064232198742438,1.8435858752220553,-1.1731727939531962,0.4967781400099791,-4.11914279594227,2.578324822247282,-0.18294084830041468,-0.4921789279449129,1.36622546711201,-0.29306315840949004,1.8764663348594013,-0.5953922253222088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5,1.0,0.0,1.0,1.0,1.5196802546001047,0.025703151892549337,0.5995029665099825,0.9843045010140372,0.10713685238435731,-0.05227234338910186,0.13013049704587404,0.4842539062179343,-0.11362276979336003,-0.11512840638030754,-0.25499890386797985,-0.5496670107916148,-0.7056230022485389,-0.5610961993099235,0.23015478316832075,-0.06738099629390479,-0.41360268739393097,0.7630835370056058,-1.161657808522807,-0.3241041297812546,-0.8129289157732132,0.5909395623341576,0.27755207714749897,0.3303040565897727,0.4904518610243863,0.8327838615257432,1.827534129134026,-1.2265911721903722,0.6058940707703886,-4.253109495690985,2.8217491527518357,-0.021761720102254634,-0.6459881094790343,2.5089490731337127,-0.3534905881489425,1.6709379539572622,-0.38004768694859803,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.508333333333333,1.0,0.0,1.0,1.0,1.5237486498249693,0.025983051718869023,0.5989331299478694,0.9846899857652431,0.10648364885468643,-0.05428044462082555,0.1268877369651022,0.49117548185271415,-0.11910141428390142,-0.11920429854137174,-0.28765931173142273,-0.5442245917331526,-0.7367555991736309,-0.5540859239850776,0.24508199215029786,-0.0776818673224319,-0.40816149604659663,0.7268769798917469,-1.1370503314037477,-0.3230775518769191,-0.8188427747572508,0.6199195892326081,0.2742557974622955,0.3424833771732352,0.4892605502847566,0.8746908883397619,1.8812876109221628,-1.3107296740935284,0.7341021090493816,-4.305386940062064,3.041085247634796,0.14094273525294687,-0.7131414652625723,3.5802327686799296,-0.3899315003732262,1.3348567246231668,0.1281880617256348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.516666666666667,1.0,0.0,1.0,0.0,1.5282323446771484,0.026222095953819663,0.5982803788398857,0.9850917929656565,0.10568504811115559,-0.05638809787977076,0.1234715046278968,0.5333771635576847,-0.13427115245550986,-0.13311401060237227,-0.324731512496911,-0.560983228248677,-0.7727763998588866,-0.5465180178375941,0.2615095766836901,-0.08922649086213026,-0.40136765224310794,0.6913270880045714,-1.1109730543955605,-0.32175508419370547,-0.8248146068609228,0.6506101084788231,0.2710532188079452,0.35255166866682547,0.49258832871981356,0.9354653250740763,2.0459119452090726,-1.4506731897652942,0.8876089249415253,-4.232505226132138,3.208151455515109,0.17160142077213503,-0.698520197696475,3.726716665004104,-0.3868529237453655,1.074518132869794,0.6576126304930929,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5249999999999995,1.0,0.0,1.0,0.0,1.533070316531023,0.02641281249920675,0.5975630236482857,0.9855067804266547,0.10475834504780424,-0.05853878078293913,0.11989698086476554,0.5690827262831372,-0.1472594642761997,-0.1451382068230278,-0.3584030610738941,-0.5665232883722326,-0.8071754397515581,-0.538494835233843,0.27918052457044906,-0.10185975381852014,-0.3933680139642379,0.656335226122878,-1.0835811404784959,-0.3202175281973835,-0.830484778052192,0.6820315336493432,0.2678082487332061,0.3603920127210651,0.5002207607929748,0.9870307194217709,2.181578614204346,-1.5717980006975902,1.0268864468516326,-4.1718377996280465,3.3596933165979026,0.19551839493188283,-0.6528805304015273,3.784154559820345,-0.39768610297093665,0.8038937229665344,1.15985726354484,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.533333333333333,1.0,0.0,1.0,0.0,1.5382078030402737,0.02655071379721344,0.5967913760991068,0.9859341309735228,0.10370167663868979,-0.06069376631348808,0.11617279532915444,0.5992755395281928,-0.1582997920842016,-0.15592895616110455,-0.391480676550232,-0.5636996970045473,-0.8405646341335138,-0.5300675058472313,0.29786922025376256,-0.1154231242070901,-0.38425287812891407,0.6217964580107707,-1.0549781657855954,-0.3184964442781741,-0.8356959490342816,0.7136793511424955,0.2644251170917629,0.3659498973829344,0.5119192831122276,1.033198255411214,2.292519109881065,-1.6747017499545414,1.156217574063808,-4.122419325063844,3.4999285142470704,0.215909931349495,-0.5916846393917541,3.790055572773805,-0.4192044386369931,0.5302176008131299,1.6311140418074777,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.541666666666667,1.0,0.0,1.0,0.0,1.5436010625160201,0.026632791970554674,0.5959729652344256,0.9863731178967134,0.10251310266079781,-0.06282240747577301,0.11230530349299393,0.6251076173070614,-0.16767744170947657,-0.16571101121179976,-0.4241212785160303,-0.553897860959847,-0.8731073721768277,-0.5212748643103228,0.31738917640180014,-0.12977144965109583,-0.3740977210631744,0.5876282373718139,-1.025248998574378,-0.3166190293415586,-0.8403461887087212,0.7451991265289066,0.2608215080892562,0.36922897273461724,0.5274059948230995,1.0750768972337288,2.3828269696405835,-1.7612150962167348,1.2769323141821054,-4.0819384186469065,3.6306013821875682,0.2332539112274612,-0.5199416123391432,3.7583383559838968,-0.45011382900545516,0.25959847475323317,2.066107327587403,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.55,1.0,0.0,1.0,0.0,1.5492150563256806,0.026656844030877383,0.5951147228309172,0.9868230075153079,0.10119140960706946,-0.06489733081143431,0.10830044743204512,0.6475176550057744,-0.17561892827830944,-0.1745260139003263,-0.4562762325398242,-0.5376901645601547,-0.9047617441051753,-0.5121495575600025,0.3375830030811056,-0.14477670914403568,-0.36297067289254564,0.5537641510333222,-0.994468142749136,-0.31460887909104973,-0.8443616425732673,0.7763183237422271,0.256923219941672,0.3702765386288216,0.5463544052386843,1.1132845471636421,2.4556954110014195,-1.8335124078702658,1.3897616127052759,-4.048651575981171,3.752613795742892,0.24798561071399328,-0.440355427391117,3.697035825948747,-0.48953144577036367,-0.0035985974899088724,2.459644832185044,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.558333333333334,1.0,0.0,1.0,0.0,1.5550218506312985,0.026621232905319224,0.594223669676853,0.9872830871496535,0.0997360185751503,-0.06689254363819293,0.10416438946752639,0.6672924490680915,-0.18230435376231743,-0.18236166620486552,-0.48786984224792174,-0.5153201174967125,-0.9354258501760514,-0.5027201218575954,0.3583174332518238,-0.16032998978226692,-0.3509350275180865,0.5201507111054611,-0.9627054353119965,-0.3124859358296587,-0.8476854458319065,0.8068163902947191,0.25266265065975013,0.36916899610978543,0.5684000753595169,1.1482496319358593,2.5138164172569457,-1.8938721886298837,1.4952181086481209,-4.021092515831146,3.8662359658400813,0.26052564639222786,-0.35462361742583326,3.611433689137138,-0.5366918894121792,-0.2566671104997065,2.808173807951475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.566666666666666,1.0,0.0,1.0,0.0,1.5609995041575353,0.02652480961395805,0.5933070578511437,0.9877526936172705,0.09814692788193223,-0.06878265884655022,0.09990366680990172,0.6851004596231756,-0.18787479464647738,-0.18919749061131824,-0.518818549231171,-0.48689903597428946,-0.9649954330037431,-0.4930120636944048,0.3794799433687214,-0.1763412456212004,-0.33805037108174363,0.48674594243613645,-0.9300308766518013,-0.3102667849845126,-0.8502720361970312,0.836508885227846,0.24797835511813568,0.3659987534538265,0.5931573020378755,1.1802913630134393,2.5594866182994904,-1.9444378573142318,1.593711076851022,-3.9979353366277426,3.971211804630417,0.271245873810112,-0.2639016791592286,3.50526877111653,-0.5908546264637993,-0.49835057859797693,3.110137023687294,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.575,1.0,0.0,1.0,0.0,1.567131116752438,0.026366904108192674,0.5923723311350951,0.9882312292789814,0.0964247042003126,-0.07054258560934966,0.09552516691729022,0.7014908660977582,-0.1924322811767852,-0.19501533038512203,-0.5490338910604423,-0.45249113464796575,-0.9933847050264921,-0.48304859914070475,0.4009755435568153,-0.1927372874041708,-0.3243731762372361,0.4535184554949987,-0.8965185719014895,-0.30796517126615686,-0.852083807151227,0.8652375364799946,0.24281507355202014,0.3608631531331525,0.6202356924209718,1.20964811236829,2.594584998792595,-1.9870337625859564,1.6855923228747793,-3.977994606250758,4.066889521161701,0.28044740343380337,-0.16902202358102025,3.3812317621668653,-0.651265724147857,-0.7286200655664921,3.365847513666256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.583333333333333,1.0,0.0,1.0,0.0,1.5734037346589893,0.026147341279532957,0.5914270536322803,0.9887181641817204,0.09457050033598573,-0.07214743867153865,0.09103603340621505,0.7169242115900669,-0.19604476100805834,-0.19980337770200945,-0.5784147763546127,-0.41214453204534923,-1.0205246155333634,-0.4728512618216,0.4227230266819313,-0.209458474997633,-0.3099571657004973,0.42044603233195715,-0.8622493846324396,-0.3055926615939492,-0.8530890699233815,0.8928627479306271,0.23712392638233806,0.35385508569438495,0.6492547605989798,1.2364803543627634,2.6206298506867345,-2.0231182374074588,1.7711678070747738,-3.9601571610823316,4.152276141705471,0.28835413932467024,-0.07059489051947088,3.2412841471067866,-0.7171109334648218,-0.9482760743797292,3.576951496176155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.591666666666667,1.0,0.0,1.0,0.0,1.5798079396569216,0.025866516256011756,0.5904788301016932,0.9892130180869888,0.092586140866791,-0.07357248028764439,0.08644363199881608,0.7317206037478545,-0.19874022553234638,-0.20354002288836426,-0.6068558453592375,-0.36591934009254423,-1.046369621285572,-0.4624405932346587,0.44465270773492754,-0.2264559246942951,-0.2948537127859899,0.3875158361436265,-0.8273139695397317,-0.303159268944079,-0.8532603886598848,0.9192589389317743,0.23086322466093978,0.34505855189349033,0.6798515506905743,1.2608899305567944,2.6386629472759218,-2.053693431287551,1.8507230143376796,-3.943526251012669,4.2262351562216365,0.2951100689093278,0.03088105707398814,3.0867157943315937,-0.7875182481010884,-1.1588691681095942,3.746227282608241,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6,1.0,0.0,1.0,0.0,1.586335882902572,0.025525366624341905,0.5895353361796102,0.9897153452013334,0.09047409781976977,-0.07479326323606551,0.08175537213836352,0.7460668601671326,-0.20051008576489143,-0.2061875678299879,-0.6342394464045497,-0.3138913281172412,-1.070892621026311,-0.4518364296456534,0.4667007424698633,-0.24368669885242553,-0.27911178212820265,0.35472059481507934,-0.7918121320287457,-0.3006741604454604,-0.852574385638815,0.944308011169487,0.22399862224731992,0.33454059955922505,0.7116918819757838,1.2829162449965292,2.649292129165263,-2.0793630450257194,1.9245202408046902,-3.927434645534018,4.28758915916341,0.3007787173402676,0.13495772354433555,2.918263328264432,-0.8615419073998987,-1.3624415014664426,3.877144548285707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.608333333333333,1.0,0.0,1.0,0.0,1.592981005204656,0.025125487676339563,0.5886043107521994,0.9902246906296794,0.08823764236781075,-0.07578560408058528,0.07697871623355894,0.7600771166449826,-0.20132236538689924,-0.20769519796391386,-0.6604296465235427,-0.2561472359383026,-1.094072382954677,-0.44105865581804987,0.4888075765543486,-0.26111197544472375,-0.26277837543924504,0.32205859205139287,-0.7558541502203415,-0.2981462903217412,-0.8510110932674793,0.9678966610695149,0.21650419287094147,0.3223511935357163,0.7444706264953361,1.302538315820626,2.6528628699267744,-2.1004711879055398,1.9928009672924052,-3.911288503126318,4.335079368356863,0.3053654491092206,0.24122068540642916,2.736312880586631,-0.938102873374061,-1.5611126991358582,3.973253103914036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.616666666666666,1.0,0.0,1.0,0.0,1.5997371190114917,0.024669146317472305,0.5876936325261114,0.9907405522429282,0.08588085522301034,-0.07652569446255836,0.07212111297183528,0.7737610935280581,-0.2011245163180906,-0.20798657256535086,-0.6852870701833395,-0.19279782288492925,-1.115899110758037,-0.43012745771530964,0.5109151236353096,-0.2786945519841845,-0.24589843267332923,0.2895324530963074,-0.719560809222798,-0.29558473629364007,-0.8485540408820412,0.9899132258459309,0.20836357435775224,0.3085220545736274,0.7779127670410177,1.3197032970285394,2.6494224237011665,-2.117126104570166,2.055816100684668,-3.8946400299177255,4.3674727094945,0.30883763208434667,0.34922595426791103,2.540914246258399,-1.0159842035279094,-1.757072712726866,4.038117002063433,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.625,1.0,0.0,1.0,0.0,1.6065976087950133,0.024159301595879343,0.5868114047215564,0.9912623347943473,0.08340866660140982,-0.07699019151146304,0.0671899424478334,0.7870431495897118,-0.19985139709893998,-0.20696023479026748,-0.7086663019203356,-0.12397466344083498,-1.1363710766496864,-0.4190636008675742,0.532964616949368,-0.2963974105208932,-0.22851477376116724,0.25714792488609745,-0.6830629383954332,-0.2929989964536688,-0.8451906606963474,1.0102452318404882,0.19957112281214298,0.29306664832360185,0.8117725765297267,1.3343300042093587,2.6388072791116746,-2.129315030854998,2.113827154807465,-3.877156729656937,4.3835905412884335,0.31113809139530435,0.4584733374596639,2.331872461017981,-1.0938202491848887,-1.9524357913967672,4.075094587730659,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.633333333333333,1.0,0.0,1.0,0.0,1.613554857983344,0.02359961792497429,0.5859660495624217,0.9917892998076743,0.08082687991659458,-0.0771563049934559,0.062192482428059616,0.7997906282832876,-0.19743497412329059,-0.204491965346871,-0.730420956656145,-0.04983046994000766,-1.155487481643783,-0.4078886243118203,0.5548952449538375,-0.3141831358317678,-0.2106679800932048,0.22491317426869176,-0.6465009668679907,-0.29039910143705167,-0.8409128185910468,1.0287777668628972,0.19013323687133743,0.27598145805034796,0.8458310101698621,1.3463209125021203,2.6207296772269717,-2.1369777758980093,2.1671136051261057,-3.858549767858006,4.382298665698257,0.31221067279885495,0.5684046952899968,2.108843382458092,-1.1700737740371236,-2.1490882429217097,4.087143991711677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.641666666666667,1.0,0.0,1.0,0.0,1.6205999534245787,0.022994462676327293,0.5851664153103082,0.992320511568144,0.07814216176046598,-0.07700190005718502,0.057135910464877336,0.8118257290717106,-0.19381236671453222,-0.20043639831252663,-0.7504110216198241,0.029458698723692486,-1.1732447393102772,-0.3966249189925389,0.5766434449031509,-0.33201370678586,-0.19239621367573215,0.192838762088464,-0.6100246273004623,-0.28779548524035453,-0.8357172491081808,1.045392621548123,0.1800698932448576,0.25724851094157336,0.8798916430582546,1.3555774422844658,2.5948278343432363,-2.1400614094893413,2.2159829801532753,-3.838544982117859,4.362516754909456,0.312024263608941,0.6783997898534944,1.8713913031629659,-1.2430364574761428,-2.3486230039707934,4.076754651729704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6499999999999995,1.0,0.0,1.0,0.0,1.6277223398498832,0.02234886543148212,0.5844218785889157,0.9928547834514952,0.07536199994089297,-0.07650561006924474,0.05202729639960013,0.8229279687801336,-0.18893246180562698,-0.19462885780908779,-0.7685094546246316,0.11369290594615573,-1.189634211911306,-0.38529566694041256,0.5981423755262247,-0.3498508259899235,-0.17373493042398355,0.16093742456672744,-0.5737923542861665,-0.2851986970435693,-0.8296061554268219,1.0599676219156133,0.16941596258006839,0.2368377413175014,0.9137769210320238,1.3620136410002959,2.5606986590074055,-2.138574376743132,2.2607781842042862,-3.8168915690555094,4.323254582957306,0.3105931791405392,0.7877729341400985,1.6190199009444806,-1.310855064202352,-2.552325801836858,4.045947687240024,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.658333333333333,1.0,0.0,1.0,0.0,1.6349095925992014,0.02166845706823929,0.583742446076234,0.9933906235777348,0.0724946336720138,-0.07564694803394033,0.04687362083287527,0.8328421422867639,-0.18276242795908537,-0.18688886428619664,-0.7846083796167063,0.20264994653849805,-1.2046371657398676,-0.37392469164253395,0.6193217558866076,-0.3676566130649122,-0.15471657727232738,0.12922390260420552,-0.5379703842511738,-0.2826189322546789,-0.8225877002058458,1.0723762865638644,0.15822230884148505,0.21470974757762573,0.947324104512255,1.3655682785392687,2.5179338234486903,-2.1326304204038817,2.301880991862037,-3.793369271856579,4.263654617167862,0.30799837658808116,0.8957863191711102,1.3511997437866086,-1.3715692057174207,-2.7611478202718036,3.996262893974263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.666666666666667,1.0,0.0,1.0,0.0,1.6421472314799304,0.020959379376210143,0.5831388510814753,0.9939261823874974,0.06954895249234286,-0.07440641070495244,0.04168180919847147,0.8414524128406647,-0.17519954314977804,-0.17473222990372939,-0.7988987222956211,0.30686309911546555,-1.2186816776477407,-0.36253619563142475,0.6401079392503696,-0.3853946663299882,-0.13537024722628294,0.09771460336911779,-0.5027314440000354,-0.2800653907671013,-0.8146763834406368,1.0824876176453901,0.14655647581811138,0.190818610979638,0.9803813025982615,1.3665080524529805,2.4646269304796853,-2.1379934247982315,2.339475816514243,-3.7721951135206644,4.169398838777195,0.30746109750188655,1.0088718244277262,1.0365625175064341,-1.4282998922253938,-2.984621745999671,3.907290119575373,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.675,1.0,0.0,1.0,0.0,1.649415804505336,0.02022440437696701,0.582660691352631,0.994466024487754,0.06652910401802123,-0.0726761051031726,0.03646077625828268,0.8481682607652802,-0.1660623157211884,-0.15568920986762635,-0.8112717358721679,0.4366114161300463,-1.2327080929958718,-0.35114955743498427,0.6603988713946024,-0.4032898368115494,-0.11572531366375666,0.06635398404552778,-0.46848040360488724,-0.27749458062964744,-0.805773169798717,1.089652328522305,0.1344173106377285,0.16496605181096455,1.012445606505178,1.3650482835918776,2.3989439293465553,-2.1715128660668594,2.374438090063015,-3.758004384655827,4.024813224621663,0.31167231332581036,1.1315947387160508,0.6446827312090164,-1.4837896213542423,-3.2339053961362576,3.761539106310625,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.683333333333334,1.0,0.0,1.0,0.0,1.656686415076965,0.019469062242139925,0.5823547798050747,0.9950132673993193,0.06344267693506281,-0.07035083111955368,0.031215140616396794,0.8516486949090306,-0.15533176977089505,-0.13222876802469355,-0.821019438681247,0.5788942967786601,-1.246814340088935,-0.33978539090489346,0.6800903380728122,-0.4215865474311025,-0.09579627905856603,0.035081196958187344,-0.4356512235896744,-0.2748708522116711,-0.7958164711287026,1.093232329832207,0.12182664879554067,0.1369201877107004,1.043073621036772,1.3607982185970535,2.3219683007831593,-2.217038526038652,2.4086166594190535,-3.747168006715054,3.844618671487673,0.31654303907286074,1.2522936769299364,0.21124107350542154,-1.5294617199918972,-3.5013647850026537,3.5882196517727483,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.691666666666666,1.0,0.0,1.0,0.0,1.6639255198719782,0.01870436476623234,0.5822243531324186,0.995561823125536,0.06030475223548375,-0.06743014795901961,0.025945487840090698,0.8511429153709384,-0.1432573604534404,-0.10737807844428407,-0.8278979854064918,0.7175015242455401,-1.259993313529657,-0.3284695871250334,0.6990983430743217,-0.4402404789121936,-0.0755817026734391,0.0039011839336102155,-0.40440342574675936,-0.2722188633117664,-0.7849016085165514,1.0931730130807287,0.10892628197119687,0.10660997206092032,1.072249267368057,1.3536468741515384,2.234616054735319,-2.251005406403037,2.443206423360869,-3.7351637283540113,3.652888209795364,0.3183222309082545,1.3601555234315965,-0.2200769572686001,-1.5548664483896346,-3.7723686138300723,3.416893684340674,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7,1.0,0.0,1.0,0.0,1.6711014749613016,0.017940646223949624,0.5822650885702257,0.9961027661776105,0.05712986885092542,-0.0639437801863376,0.020655514374706845,0.8467714155788273,-0.13020059017307484,-0.08175770415364232,-0.8321672652095993,0.8477439652194061,-1.2711495641973563,-0.3172246096690345,0.7173339389850675,-0.4591033042044865,-0.05507617200255154,-0.027171531847712847,-0.37476975342641833,-0.26956548169653355,-0.7731472124048426,1.089564380544397,0.09591220798904676,0.07404737748019918,1.1000218491091165,1.3439415681049094,2.1370818300992744,-2.266083768227322,2.47840555225937,-3.721001256200633,3.4604000736228824,0.3173777822536117,1.4542299995800612,-0.6384276504052977,-1.5556873549493366,-4.038624093788691,3.25057556741998,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.708333333333333,1.0,0.0,1.0,0.0,1.6781864434343734,0.017186691075151653,0.582471648887082,0.9966263093313541,0.05393114474159537,-0.05993106671921915,0.015352472683657444,0.838831646235579,-0.11651765966790532,-0.055604053930240045,-0.8340918742977973,0.9681573138558336,-1.2794991871528285,-0.30607056098995156,0.7347163735759763,-0.4780085417159823,-0.03427494346911626,-0.05811550366973367,-0.346730091186378,-0.26692923360753956,-0.7606644418568838,1.0825325522406404,0.08299815938870793,0.039299570497775466,1.1264255268250567,1.3319576926807686,2.0308250503864933,-2.26218722326362,2.514137922098122,-3.7037486234837016,3.2714089197106224,0.3147445437980134,1.5357191785179425,-1.0411067714162003,-1.5311086237401257,-4.2945128564970085,3.0868206309934187,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.716666666666667,1.0,0.0,1.0,0.0,1.685156134411659,0.016449673867394654,0.5828384518333826,0.9971226319534613,0.05072019161177774,-0.05543459967749364,0.01004610212711853,0.8276447617446279,-0.10253728741054967,-0.029122428965576493,-0.833949631073416,1.0782274342365896,-1.2845511534950136,-0.2950253147910217,0.7511810231581757,-0.49680642459221347,-0.013173873300916175,-0.0889006755724412,-0.3202462714312413,-0.2643197392999,-0.7475518927628769,1.0722126010207937,0.07039373092671133,0.002472163205249043,1.1514688596256735,1.3179884485062898,1.9178420171737343,-2.241641571531494,2.550351028409894,-3.6822881909056973,3.0873575902377373,0.3114343059925784,1.6062714285273971,-1.4274147710237495,-1.4823727994169718,-4.535820543435049,2.922636616576959,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.725,1.0,0.0,1.0,0.0,1.6919899715939268,0.015735297025712792,0.5833597960226179,0.9975822975344871,0.04750701765333993,-0.05049852383415931,0.004747842758618744,0.8135240151777301,-0.08855369108497137,-0.0025357877474358193,-0.83202511218896,1.1777128377950694,-1.2860346431257217,-0.28410408684818006,0.7666804071955385,-0.5153692345748405,0.00823090700438197,-0.11948697351816195,-0.29527413134908237,-0.2617386618409966,-0.7338932513814271,1.0587423060569112,0.058291946065091735,-0.036297438559475356,1.1751361371013394,1.30236564039241,1.8001471592350993,-2.20717459678498,2.587040602188513,-3.6553738604711623,2.908443388476797,0.30827997647360106,1.667634266275797,-1.7971179312944452,-1.4119972224606405,-4.759197875765221,2.7555453097810867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.733333333333333,1.0,0.0,1.0,0.0,1.6986704056988333,0.015047916106038372,0.5840296088355411,0.9979965336291877,0.04430016246633151,-0.04516783742008565,-0.0005300326158915798,0.7967347020011442,-0.07482576049078128,0.02390823184890381,-0.8285887989475682,1.266463761485422,-1.2838726261407862,-0.2733192207844815,0.781183475812094,-0.5335926678719631,0.029943470068892374,-0.14982357324696058,-0.271772214956628,-0.25918173969200664,-0.719757988324947,1.0422606354992197,0.04686044388570066,-0.07684780139083797,1.1973946147886916,1.285444850464833,1.6796077877151383,-2.161428615581449,2.6242442731257265,-3.6216947255646152,2.734079171345345,0.30587772848443384,1.721469372586275,-2.1500595784808585,-1.3233009661664143,-4.962094605131924,2.583885727106421,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.741666666666666,1.0,0.0,1.0,0.0,1.70518242300719,0.014390692783956764,0.584841277813324,0.9983574320887898,0.041106785157130114,-0.03948820634185512,-0.005775082029035848,0.7775108024387571,-0.06157722389000703,0.04994453940945962,-0.8238990919007186,1.3443444324615148,-1.2781356283361374,-0.2626800060070995,0.7946738703241242,-0.5513930448345313,0.05196831155647741,-0.1798485522775722,-0.2497061451599933,-0.25664069969958936,-0.7052020951716559,1.022907979748897,0.036236929962318164,-0.11899901531167409,1.2182008992197797,1.267598872648249,1.5578787515777726,-2.1066636223867174,2.662014729602192,-3.579876631018508,2.5631959852040147,0.3046050084902596,1.769324921294415,-2.486008172250509,-1.2199553521111528,-5.1425738210748495,2.406723578732426,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.75,1.0,0.0,1.0,0.0,1.7115131113827138,0.013765726137771217,0.585787487765513,0.998658101290913,0.03793274708885756,-0.03350593758144039,-0.01097522587724384,0.7560641471459929,-0.04900073199771358,0.07529386570792643,-0.8182018160594529,1.4112096813839141,-1.269008327861733,-0.2521925729070107,0.8071481216717236,-0.5687037282450751,0.07431038222892891,-0.20948818376393571,-0.22905228186989443,-0.2541049895505023,-0.6902692396367067,1.0008271659617112,0.026527854683848114,-0.1625573650754188,1.237506674434232,1.2492116981216934,1.4364121503180693,-2.0447109988894385,2.7003986275591223,-3.528436162139848,2.394291307429663,0.30465184129049083,1.8125890243208853,-2.804579879009428,-1.105636522229293,-5.299217077387991,2.223761121917307,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.758333333333333,1.0,0.0,1.0,0.0,1.7176513117124126,0.01317414893646785,0.5868600673595633,0.998892784680892,0.034782664354760344,-0.027268004549285876,-0.01611914776975205,0.7325946080118003,-0.037262950080411875,0.09966621371151514,-0.8117335823931461,1.466900076800415,-1.2567584490748565,-0.24185981103840462,0.8186140728294253,-0.5854715614826886,0.09697495534912945,-0.23865582164656968,-0.20980129003616557,-0.2515631690114145,-0.6749922780996411,0.9761649817654064,0.017809654591829947,-0.20731929993480727,1.2552635845850681,1.2306774857516152,1.3164867829022153,-1.9769935736509958,2.7394167378977055,-3.465734360467629,2.2254241799129177,0.3060654465271956,1.8524479962338392,-3.105184557946583,-0.9837619688004419,-5.431051622420556,2.035237410473183,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.766666666666667,1.0,0.0,1.0,0.0,1.7235873457433883,0.012616183460543174,0.5880498513123191,0.9990569531773598,0.03165992574579497,-0.020822073522085784,-0.021196573047751802,0.7072984002063855,-0.026509634697870384,0.12276511412550656,-0.8047258353793753,1.5112464331978865,-1.2417095185746698,-0.2316812814778171,0.8290895680534272,-0.6016536211392584,0.11996732786055733,-0.26725042310506286,-0.1919618788713458,-0.24900389877504905,-0.6593951063661427,0.9490740899959348,0.010131821870507414,-0.2530748921157614,1.2714272979421184,1.2124016939342304,1.1992381342021385,-1.904570799511327,2.779044050047941,-3.389942247866308,2.054194081035878,0.3087977028520894,1.8898462627450985,-3.3869828769310306,-0.8573147963548776,-5.537500041846947,1.8418331546245348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7749999999999995,1.0,0.0,1.0,0.0,1.7293128001307045,0.01209116049149225,0.589346565731086,0.9991473752338875,0.028566682580910902,-0.014216499307087356,-0.026198443378365063,0.6803738324844338,-0.0168698726843539,0.14429277698489004,-0.7974078520293648,1.5440801111633684,-1.2242192182960445,-0.22165311613950078,0.8386013750661276,-0.6172144081412108,0.1432923561832618,-0.29515485911100814,-0.17556472201890094,-0.24641654063054635,-0.6434948403872228,0.9197152671498893,0.003521074652581988,-0.29961096729892306,1.2859608038288104,1.1948020157687107,1.0856829492816877,-1.828193533035869,2.8191905281491154,-3.2990281359637885,1.8777294101146846,0.3127478879158596,1.9254475595542986,-3.6488492796085237,-0.7287497812222495,-5.618348695542075,1.6445798254179378,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.783333333333333,1.0,0.0,1.0,0.0,1.7348203494668153,0.011597511789192392,0.5907387439683117,0.9991621653470539,0.02550382269201743,-0.007500269534496265,-0.031117012263646812,0.6520251520847117,-0.008458964489714345,0.16395596692779274,-0.7900077504600179,1.5652467031599435,-1.2046638665819673,-0.2117679145483386,0.8471842838747886,-0.6321235133565228,0.1669538366630426,-0.322234225371126,-0.16066638870276773,-0.2437914339764514,-0.6273043137069044,0.8882599353357927,-0.002014007816530078,-0.34671403704146264,1.298836961699084,1.1783072737119133,0.9767369369889578,-1.7483588462087885,2.859683368152557,-3.190772284568594,1.692705414787743,0.31779614751446306,1.9595985680706596,-3.8893362644382656,-0.599967040003405,-5.673726148956782,1.4447684868163835,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.791666666666667,1.0,0.0,1.0,0.0,1.7401036128960503,0.011132749697179919,0.5922136792199021,0.9991008095449992,0.022470942799316888,-0.0007228872611056454,-0.035945886094837017,0.6224670285096969,-0.0013798751899494754,0.18147179089459162,-0.7827513317461463,1.5746193064616,-1.1834266482262497,-0.20201466157763556,0.8548803240159436,-0.6463537222446906,0.19095374565247109,-0.34833439718715137,-0.1473529651057719,-0.24111993817197197,-0.6108348642527118,0.8548929960759182,-0.006478376014141429,-0.3941730697815361,1.3100402786090835,1.163352758389436,0.8732278180925945,-1.665353989195153,2.900248917553658,-3.0628035699643785,1.4953999188148226,0.3238269701475366,1.992296523408501,-4.106628061756137,-0.4723320132827918,-5.704074846653033,1.243856684276774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8,1.0,0.0,1.0,0.0,1.745157073266136,0.01069344383654399,0.5937574083422302,0.9989641656429978,0.019466331219773623,0.006065794827825394,-0.04068001773768245,0.5919253898044353,0.0042777949181814,0.19657683658436237,-0.7758587820868885,1.572117369828327,-1.1608949812073321,-0.19237870190851467,0.8617380808429985,-0.659879413176442,0.21529131862227022,-0.373280951537199,-0.13574305672252068,-0.23839431780732578,-0.5940993716500961,0.8198161343065238,-0.009886208037909941,-0.44178195115234653,1.3195679064370303,1.1503727400396702,0.775891841585763,-1.5792921473554933,2.940502665231273,-2.912701402080915,1.28184749072291,0.33073919902652293,2.0231649353237424,-4.298518710249233,-0.3467397449601709,-5.710127684801876,1.043358991376384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.808333333333334,1.0,1.0,1.0,0.0,1.7499759861511366,0.010275227212225808,0.5953547894582577,0.9987544337807602,0.016486975350363108,0.012815847832988243,-0.0453157223421608,0.5606471010965847,0.008439445395477432,0.2090323185563885,-0.7695393521359062,1.5577131253589813,-1.137449751518464,-0.1828417825769744,0.8678118547090397,-0.6726752580339488,0.23996212340632564,-0.3968794205551666,-0.12598884026039006,-0.2356076181881966,-0.5771154486639828,0.7832510175717643,-0.01225737176347761,-0.489341864528234,1.3274295951320232,1.1397854164199612,0.6853798119359733,-1.490116958852652,2.979925138843466,-2.7380823496657047,1.0480149227818705,0.3384517180803437,2.0514318173502644,-4.462331790111754,-0.22367619612525566,-5.6928347108050215,0.8447531619521387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.816666666666666,1.0,1.0,1.0,0.0,1.7545565177140878,0.009872799201098185,0.5969895411793095,0.9984750994791406,0.0135285985049996,0.019477481154553982,-0.049850581445813356,0.528912532942684,0.011048909262050426,0.21863158255998338,-0.7639861922847542,1.531435232932875,-1.113454533813812,-0.1733822783015153,0.8731610777085981,-0.6847146958239863,0.26495673760299465,-0.4189156573649607,-0.11827614134282284,-0.23275345583932006,-0.559908841360925,0.7454439378046612,-0.013614144639997536,-0.5366625296657636,1.3336471258028992,1.1319748920963808,0.6022516629239538,-1.3975754016114372,3.017835201356864,-2.5367170603931832,0.7900491172137051,0.3469036195409647,2.0759183992307695,-4.594838076875758,-0.10328912871406926,-5.653265471989715,0.6493855695386719,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.825,1.0,1.0,1.0,0.0,1.7588959374673703,0.009479973954224615,0.5986444053413723,0.998130847308537,0.010585723702929496,0.026001337842078538,-0.05428337254860343,0.49704519480800724,0.012074256701275286,0.22521153478918685,-0.759369827155437,1.4933755193300633,-1.0892502740414773,-0.16397553437536805,0.8778493824244389,-0.6959681813941394,0.29025937676227337,-0.43915803822838634,-0.11282135497349498,-0.22982589119584718,-0.5425168086768033,0.7066703829571683,-0.013978857242045431,-0.5835629557280626,1.3382526879576677,1.1272690544440052,0.5269542616857992,-1.30117692300878,3.0533657742329825,-2.306705140493601,0.5046198092201551,0.3560444859999795,2.0950352101615355,-4.692198307979274,0.014523661300125737,-5.592513649991844,0.4583808699693659,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.833333333333333,1.0,1.0,1.0,0.0,1.7629930142906611,0.00908975598677686,0.6003013247108584,0.9977274487395852,0.007651783332737562,0.03233875531810542,-0.05861393305268127,0.35594027753443575,-0.008618089216158295,0.2447274076576681,-0.7774953027603855,1.3792701077973588,-1.101958783311082,-0.15459446072744856,0.8819436487366947,-0.7064009778741326,0.31584616717354436,-0.4573607430398541,-0.10986581118915359,-0.22681938107265373,-0.5249915878582327,0.6672406326716733,-0.013372083618328773,-0.629871090498961,1.3412868069690553,1.219070928635877,0.33915058391698505,-1.3638929734828342,3.058692229964539,-1.2119032833228394,-0.6449624930004461,0.3999023348411074,1.9437142388714124,-4.685207659858039,0.16486125147847955,-5.7923878720851585,0.41114984083232997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.841666666666667,1.0,1.0,1.0,0.0,1.7650177821796016,0.008568683000927602,0.6023243998581188,0.9972736306698783,0.0044935785610372885,0.03791951341478041,-0.06314446788613737,0.22301052447448236,-0.027432722334059054,0.24651886578016413,-0.7759918103793524,1.288244909020661,-1.1047981989751392,-0.1436576855647701,0.8835018921563886,-0.7186997309521866,0.3412375805950157,-0.459356426283767,-0.12357072985683575,-0.22316085228182872,-0.5101215713622798,0.628583588626201,-0.011231169717404106,-0.6801027535961486,1.3451051853048732,1.279499895471275,0.2953769069199419,-1.7602892158514738,3.023078745966085,-0.15778460492759105,-1.8161022572662828,0.4206097124641206,1.7640081290733334,-4.636627219651206,0.29366474666134734,-5.97512649719564,0.338573118556309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.85,0.0,1.0,1.0,0.0,1.7669202032837668,0.008112858854371902,0.6041128602152714,0.9967694017518466,0.0015325735345462384,0.043494134892450034,-0.0675031197766948,0.21644623500134336,-0.0214691097876155,0.22486063547214716,-0.7414423223494399,1.2721027569406473,-1.0633462415934825,-0.13326946246959398,0.8868665971853604,-0.7357391314716571,0.36623081293964577,-0.45999048645531393,-0.14013418214359163,-0.21980921919825172,-0.4955914523736772,0.5899635123441532,-0.008477671173972984,-0.7294565321188883,1.3469296922783272,1.2291460028150234,0.4874638721454416,-2.2271038424751732,2.972075440331784,-0.03794512533163319,-1.998020772784653,0.3945927009887851,1.7509631877471177,-4.616975135270169,0.3752840986518149,-5.8143568970917325,0.08331495313373072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.858333333333333,0.0,1.0,1.0,0.0,1.7688546709361437,0.007695698530270123,0.6057453507788891,0.9962256724451358,-0.0013346348988289114,0.04891683898966247,-0.0716921974428571,0.22127057586573523,-0.0162423273508622,0.20988154606106038,-0.7198546305150149,1.2244073328515612,-1.0232303407884902,-0.12317191885118638,0.8916262900254793,-0.7558181283267729,0.3907721712672121,-0.4599888450392942,-0.1568710760699133,-0.21658430726534897,-0.48093885156649446,0.5516340030383649,-0.0049764347398738576,-0.7770087018810108,1.346493767857102,1.1995099675684693,0.6387099596666657,-2.534390103333277,2.909167635645115,0.03322528981086981,-1.9671849986115948,0.37990463236000804,1.7664347243340728,-4.55157234755323,0.4635152903192405,-5.579970235317413,-0.17700788424173997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.866666666666666,0.0,1.0,1.0,0.0,1.7708554572845172,0.007302439310029972,0.6072380237808096,0.9956532283332361,-0.004129352470343555,0.05407787629610541,-0.07571776973132328,0.22945483064698094,-0.011777444735456305,0.19596138376823036,-0.7003333539704283,1.1536226361856097,-0.9845399217478674,-0.11327762967678616,0.8975117631798049,-0.7779789665272118,0.4147169402003977,-0.45943673162513277,-0.1729205987871182,-0.21347747532558492,-0.466150873634776,0.5141039732182661,-0.0007524163353189765,-0.8224560360408452,1.3439795608742982,1.1779393171597516,0.7647691752206254,-2.747805433228543,2.828674376038224,0.10333610339227972,-1.8661099095715783,0.3648413197506062,1.7747026764234186,-4.41970976807067,0.5477201349164116,-5.318717161564148,-0.4121031404137243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.875,0.0,1.0,1.0,0.0,1.7729369380864943,0.006923457049984405,0.608585956557081,0.995062997119635,-0.006861679608149387,0.05889683113731263,-0.07958462413198353,0.23987588216122493,-0.0078140885917269,0.1813864119610569,-0.6814701417182059,1.064955912701833,-0.9471431179005882,-0.10353959689852385,0.9043724429458231,-0.8016148855472486,0.4379167442011825,-0.4582665766494229,-0.18797290789610627,-0.21050361860283887,-0.45136047362610415,0.47797217357052035,0.004152234175399669,-0.8656539879070799,1.33962538218354,1.1612540190725884,0.8757093910570135,-2.8962126594445547,2.7301902208153517,0.1854722392821584,-1.740800746125007,0.3477390719112161,1.7630725181298401,-4.21192692874333,0.6268635325896853,-5.043316817661916,-0.6185888122704997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.883333333333333,0.0,1.0,1.0,0.0,1.7751121335349995,0.006550371095173133,0.6097786324011814,0.99446608344141,-0.00953964229637878,0.0633067846744805,-0.08329738965741892,0.25265792138692084,-0.004194595757746743,0.16572406541989743,-0.6629850626782439,0.9608568889139683,-0.9110933879703906,-0.09392339602557635,0.9121069196974217,-0.8262491775179543,0.4602201105473202,-0.4563455276370968,-0.20193394455586833,-0.20768182412706465,-0.4367663316659453,0.4439051910725439,0.009695309207842446,-0.9065113163352104,1.3336697473364565,1.1482978795860328,0.976122027453874,-2.9911962389491342,2.6132799686522534,0.2854015299211843,-1.610067118014732,0.328239403365414,1.7246782754078926,-3.9196841207042077,0.701061691529217,-4.758587014094482,-0.7966677970224989,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.891666666666667,0.0,1.0,1.0,0.0,1.777396387124514,0.0061750773885666,0.6108039234381134,0.9938736389463426,-0.012170745403651631,0.06724777667986515,-0.08686080413794355,0.26809682707602644,-0.0007943780562962507,0.1488527260385319,-0.6447696806274699,0.8426560922608771,-0.876455299369618,-0.0844012989054233,0.9206411434033877,-0.8514681561964008,0.4814714103453867,-0.4535098844840698,-0.21480735986301847,-0.20503296188008197,-0.4226158357026393,0.4126441048921169,0.015836595700886618,-0.9449637714753213,1.3263475855664983,1.1383528957060176,1.0688834661964486,-3.0392146390380415,2.4775592996384,0.4056559860043618,-1.4825082328297945,0.306141508054692,1.6538954618193424,-3.533814613790607,0.770565100730762,-4.4674389479777465,-0.9465222239022975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8999999999999995,0.0,1.0,1.0,0.0,1.7798071800695523,0.00578957535620428,0.6116489780428012,0.9932966654242288,-0.014762334949422293,0.07066408701553237,-0.09027953660830633,0.2864006382404555,0.0024891461195249084,0.13068377561739403,-0.6267605091362896,0.7111504656649102,-0.8432421983895138,-0.07495084776380939,0.9299216441340292,-0.876902754835255,0.5015127655412935,-0.4495845945370241,-0.22664241510303157,-0.20257946565948645,-0.4092014073022896,0.38500828084270045,0.022538060886688478,-0.9809686321348395,1.3178943769380849,1.130828596760239,1.1562930411130745,-3.0452262639050165,2.322973414879962,0.5468574372509705,-1.3618226852474624,0.28125284464593947,1.5456560773655414,-3.0452717340600413,0.8356375904375822,-4.1724388373033765,-1.0677227814169,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.908333333333333,0.0,1.0,1.0,0.0,1.782363168923032,0.0053859024027940695,0.6123001765092541,0.9927458153106014,-0.017321796595747667,0.07350249487808477,-0.09355792212678946,0.307656766505942,0.0057281156463307725,0.11106340416012814,-0.6089370453359303,0.5667114027214517,-0.8114138144361499,-0.06555415562608599,0.9399126940886056,-0.9022219272614844,0.5201876339267194,-0.4443955938632203,-0.23750440461714284,-0.2003454144693163,-0.39685490107988025,0.3618895759911162,0.029763888874846323,-1.014504418763711,1.3085522058762167,1.1252364073664651,1.2403916136631876,-3.01349725445079,2.1499399726825796,0.7084328560282827,-1.2486928394723147,0.25337379722995934,1.3960046011404181,-2.44647512767611,0.8965701998087822,-3.8762102688492583,-1.1589852767805153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.916666666666667,0.0,1.0,1.0,0.0,1.7850832541522486,0.004955964546995213,0.6127426294298477,0.992231220803391,-0.019856880722429162,0.07571046405788785,-0.09669971371792072,0.3296782237367957,0.008583462986397318,0.09368724221302109,-0.5938328682558712,0.43110847397867935,-0.7797120050291015,-0.05619690764103497,0.9505948376950824,-0.9271277090761015,0.5373450984193365,-0.43777738026988605,-0.24745396242757015,-0.19835656903898713,-0.3859346639499493,0.34423369538143195,0.03748089755016818,-1.0455721366156605,1.2985779556584096,1.1239322871787207,1.3141683529204662,-2.976283798679855,1.9758192004126673,0.8681910659500258,-1.1564984294864467,0.22954149168942894,1.2399943573474748,-1.8490152520419856,0.9533724094102659,-3.556004028669313,-1.2703332238309484,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.925,0.0,1.0,1.0,0.0,1.7879596744253192,0.004493912897518425,0.6130303282407864,0.991748769202879,-0.02237778194264377,0.07741707704071013,-0.09970060175706481,0.34915661803700654,0.010799785717902965,0.08412330790856465,-0.5837790373971274,0.3362025058194762,-0.746832756955832,-0.04682195083977398,0.9618154999706133,-0.951826657239482,0.5531179539335972,-0.4299257427640532,-0.25677937844191695,-0.19651972294115916,-0.37618832845742234,0.3310726551237498,0.04565342903168409,-1.073771152574866,1.2873799854790342,1.1290929535567125,1.365117205505204,-2.9766036898156223,1.8265482177800707,0.9950668487515812,-1.1062732781711189,0.21844433410627806,1.140058862797011,-1.4376968078986496,1.004404417989405,-3.187880674128225,-1.4689135729139435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.933333333333334,0.0,1.0,1.0,0.0,1.790973609574622,0.004001831462015266,0.6132480844557113,0.9912859047700993,-0.024884679104906743,0.07883517452611215,-0.10255741362377209,0.3664342432360105,0.01310125152999405,0.08117556568942347,-0.5756102954995017,0.27578882806088933,-0.7139990254339751,-0.0373786917484231,0.9733467911201691,-0.9767377705730286,0.567787568715671,-0.42119293279069303,-0.2658918503970888,-0.19471583013721583,-0.36693368290333245,0.32027208191645445,0.05422097118332493,-1.0987034811844643,1.2740960627765106,1.1368090911383595,1.3946004054657912,-3.0049806994880868,1.6994799813106298,1.0947323550088928,-1.0929790736676592,0.21452617941576158,1.1007070150803733,-1.2082211913715357,1.046769833125805,-2.797150029338291,-1.728685041550282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.941666666666666,0.0,1.0,1.0,0.0,1.7941244306782265,0.0034865425495988565,0.6134270918985161,0.990838752765556,-0.027366526515004316,0.08003949226971671,-0.10527734307215711,0.3833522744873424,0.016020992553557253,0.08077739829759717,-0.5663928454155363,0.2275704922461112,-0.6825255504246203,-0.027875132654134657,0.9850588400617099,-1.0019096688976168,0.5814426202887744,-0.411680203513905,-0.27499569633637794,-0.19294428661756313,-0.3578432115394161,0.3109356352675575,0.06309959291711417,-1.1203903197305043,1.2585685681198628,1.1437949552334998,1.4108163203813096,-3.032175335058971,1.579610865930512,1.186112355763106,-1.0967258107528655,0.20983704830129069,1.089358923672713,-1.0533417518838095,1.0796187040469314,-2.4122046757758353,-1.9931696878699823,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.95,0.0,1.0,1.0,0.0,1.7974151570510257,0.0029519096723831517,0.6135795357569622,0.9904068116299602,-0.029817332621763313,0.08105575748552092,-0.10786676203223311,0.4005029121921479,0.019368291492864537,0.08141482718140201,-0.5564072397991615,0.18327769284546885,-0.6522531357927076,-0.018315442494531438,0.9968603964598576,-1.0272740261573448,0.5941144164811796,-0.4014243935279746,-0.28417061390963655,-0.19121854599886098,-0.34877770084212056,0.3027163860517243,0.07221461625077379,-1.1389068924473948,1.2408765679786775,1.1506302574719185,1.417176535865463,-3.0488026398014334,1.4622531239885417,1.2745321787959074,-1.1067971881587735,0.20366057450994624,1.0899767456901388,-0.9264785217820637,1.1042915559774942,-2.037907906240757,-2.2429150499010175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.958333333333333,0.0,1.0,1.0,0.0,1.8008504380507104,0.0023991941701089195,0.6137102690376222,0.9899909835546052,-0.03223495051893274,0.08189049957579886,-0.11032998927719889,0.4181884367747595,0.022944467655268655,0.08238481202448926,-0.545946849854879,0.13902097093626123,-0.6227459832570508,-0.008697961696269347,1.008678448992801,-1.0527230462276407,0.6058135056885834,-0.3904380005339732,-0.29344231613902416,-0.18954994370906403,-0.33967693244458047,0.2954943265711898,0.08150445218340574,-1.1543554515011836,1.2211866506215125,1.1576970835806328,1.415518957240598,-3.051194280940126,1.3450717710531723,1.3624482890371081,-1.1180603104651088,0.19621688319859554,1.0947900518821152,-0.8052256187442952,1.1221223402804958,-1.6773046981509854,-2.4692915608953747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.966666666666667,0.0,1.0,1.0,0.0,1.8044357205333539,0.0018276767136735934,0.6138195089168945,0.9895932631143014,-0.03461887804429192,0.0825375969780465,-0.1126687710521558,0.4365160385513384,0.026623663819408824,0.08334511297661705,-0.5351890660194967,0.09301585319600147,-0.5936326315696909,0.000979508898479109,1.0204523790805342,-1.0781272641730135,0.6165322793320658,-0.3787169220440228,-0.30280495241738836,-0.18794826461221772,-0.33053119997741864,0.2892959590726527,0.09091665525544872,-1.1668619707499113,1.1997217086304213,1.165084541629825,1.406862574632699,-3.038380521452906,1.227018635456909,1.450725236879491,-1.1277596859405403,0.18779603218942287,1.1001035910561285,-0.6791181866794449,1.1340107107453732,-1.3325189933055714,-2.668812370943008,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.975,0.0,1.0,1.0,0.0,1.8081760378998952,0.0012360273942615173,0.6139067285960037,0.9892157343144554,-0.036969809809807574,0.08298905687470658,-0.11488376990517093,0.4553428568301224,0.030388597928721117,0.08435066591299598,-0.524394420779979,0.04591350332150779,-0.5649643702938455,0.01072011399756107,1.0321261585700126,-1.103362721585189,0.6262638162795319,-0.3662592465859817,-0.31223831090469983,-0.1864200098392403,-0.321341872593645,0.2841756901265324,0.10040463069582863,-1.1765641013896098,1.176706444439129,1.1729389252882503,1.3913038696431013,-3.01231156608031,1.109327705070584,1.5380344867526008,-1.1348108886297847,0.17873525987027183,1.1068627821937904,-0.5515018403953587,1.1403473466236564,-1.004133812506578,-2.8442584982402197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.983333333333333,0.0,1.0,1.0,0.0,1.8120746830379082,0.0006239394753704249,0.6139738764839622,0.9888595070371063,-0.03928885468587247,0.08324431528257667,-0.11697711405788423,0.47449619414568145,0.034242075352000065,0.08542786327306585,-0.5135328487070089,-0.0018398217876101075,-0.5368423966636854,0.02052849098661661,1.0436407769079192,-1.1283324569410187,0.6350210744165755,-0.35308301393147945,-0.3217184672278848,-0.18496934361437986,-0.31208348694085547,0.28010426173273006,0.10992244436584299,-1.1835975342916876,1.1523174003264176,1.1810928619894374,1.3688311525249341,-2.9744966128443195,0.992868143665353,1.6231852542639569,-1.1380364937457532,0.16901975286748805,1.116154358787299,-0.42566703766768077,1.1412165025768282,-0.6926016915529587,-2.9979287738505844,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.991666666666666,0.0,1.0,1.0,0.0,1.8161340673869446,-9.038875700969375e-06,0.6140216607094271,0.9885259311615676,-0.041576177269432156,0.08329896991809456,-0.11895035315416153,0.4938952963155663,0.03814966222472145,0.08643271340346255,-0.5024293607415552,-0.050859824181715266,-0.509157383747037,0.030404995030718363,1.0549400111120948,-1.1529376651325944,0.6428116186739544,-0.33920615901491574,-0.3312055858004624,-0.1836030139581155,-0.30273929994719,0.2770812394987377,0.11942490573877576,-1.1881074629154924,1.1267409648749527,1.1891833983417812,1.3397005704370546,-2.925039389163082,0.8773364039103448,1.7059657116316707,-1.1357085459603022,0.15850675015226467,1.1272097523785651,-0.2992103116081224,1.1368473329355835,-0.3987611567011973,-3.1293111701485365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0,0.0,1.0,1.0,0.0,1.8203557082110997,-0.0006634078035507908,0.6140503745389623,0.9882163486553436,-0.04383198626998259,0.08314721170331241,-0.1208045794492954,0.5147068755799523,0.04234773627234449,0.08823955317000513,-0.4890285764427197,-0.11502798331285492,-0.4831313810912789,0.040348214292312966,1.0659691197485368,-1.17708311342707,0.6496433478150813,-0.3246502520709516,-0.3406469429938898,-0.18232756444517545,-0.29329665773454605,0.275117423205928,0.12886989991476938,-1.1902435535700409,1.1001622141572753,1.1944779763487257,1.3000611746554247,-2.833122497825018,0.7478807458522407,1.7878247783224022,-1.0910937505446505,0.14288702542601506,1.1354222172096329,-0.13270219226133584,1.1248496077412196,-0.12219009309132112,-3.2176550583359598,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.008333333333333,0.0,1.0,1.0,0.0,1.8247641463113549,-0.0013394321649739022,0.614072121133462,0.9879408635114173,-0.04605458618741181,0.082667744669465,-0.12254741648316947,0.5384558413127778,0.04690929170480519,0.09141754079789523,-0.4719193528637249,-0.21110152583297603,-0.45991483046254356,0.05031296130319712,1.0766076973563519,-1.200156373429678,0.6552762977714918,-0.30940907937620904,-0.34939048164287323,-0.1812215635343486,-0.28381559632702946,0.2748695362943821,0.13817239920112942,-1.1901439644670144,1.0731133805693533,1.1947151424010303,1.2473327141236812,-2.664824088248108,0.5882194477405744,1.8704513644529608,-0.9609682948711917,0.1181123993659966,1.1322106244184116,0.12779547231597688,1.104032588676499,0.13560399943019608,-3.2342825619698656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.016666666666667,0.0,1.0,1.0,0.0,1.8293871905069596,-0.0020419639830152217,0.6140951545453437,0.9877109683234019,-0.04825051858152829,0.08171486580790965,-0.12418378000477401,0.5641330983337676,0.05122587626066111,0.09429542439511379,-0.4541154711519961,-0.32884436237191783,-0.4378967157079252,0.060260133332330136,1.0867579983172648,-1.2214968482312052,0.6594470052774242,-0.29347606266340226,-0.356663081241743,-0.18035902445574217,-0.27442648066090586,0.27724734774452764,0.1472704430593777,-1.187983486912871,1.046257504791111,1.1930283824528807,1.1879824074843448,-2.450448553741693,0.41318210968135594,1.9511905458162804,-0.772264927204156,0.08923350106942174,1.1165083634219752,0.46208790345244943,1.0795986199454595,0.36982980154003364,-3.189479288486101,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0249999999999995,0.0,1.0,1.0,0.0,1.8342260377849802,-0.002778725759617265,0.6141116579633473,0.9875287226361438,-0.05043179773313901,0.08025512537289158,-0.12570907126156736,0.5897318129795575,0.05491733913680692,0.09546295931921403,-0.43777827688016896,-0.45023023793770217,-0.41542831899864263,0.0701967676774118,1.0964074041477576,-1.2409971826587063,0.662162666266181,-0.2768892369459377,-0.3622615637629425,-0.1797343385165249,-0.2652071236033299,0.2825710013519229,0.15616570953355374,-1.1839801344413472,1.0199553924279183,1.191800747363044,1.1269952792721805,-2.232565941977076,0.2440486074263304,2.025079386022506,-0.5685628831153522,0.06128880456099273,1.0975047547327899,0.8125976265608925,1.0550625630333343,0.5784169312362719,-3.1102662892211708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.033333333333333,0.0,1.0,1.0,0.0,1.8392710040799574,-0.003553784050114342,0.6141146452852893,0.9873923247304348,-0.05260356407365278,0.0782939502552483,-0.1271193119225966,0.6143848238324453,0.05803939453951029,0.09474861856599753,-0.42224244833395436,-0.5698063494397445,-0.3919772814645031,0.0801234791217142,1.1055412529718012,-1.2587062805974898,0.663514482067863,-0.25972473956302716,-0.36613912929366554,-0.17933754437972563,-0.2561347347486927,0.2907906415205425,0.16485481910993327,-1.1783432047255997,0.9944197333040914,1.189931269908012,1.0638224816779074,-2.0218871557818074,0.0863116521006968,2.089250824122965,-0.3607390544591449,0.03441248966148891,1.0834276058373544,1.1513183858247678,1.0299620508193752,0.7619812381472713,-3.0065910877975166,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.041666666666667,0.0,1.0,1.0,0.0,1.844509450898287,-0.004370272132012122,0.6140967007799772,0.987299351714714,-0.05476636568530973,0.07584226635590591,-0.1284078888832319,0.6378315151686652,0.060612036709128986,0.09211263782701028,-0.40697746044042515,-0.6863714896996551,-0.3669359072332542,0.090028955509212,1.1141377788423894,-1.2746953019217364,0.6636011938011926,-0.24206838987722162,-0.3682738813372616,-0.17916079702216675,-0.24714999683937397,0.30175964111566905,0.17333174371387666,-1.1712804471388927,0.9698455409646264,1.1863941133706297,0.9974977940566854,-1.8200764741700892,-0.05922675489826501,2.1424724275255387,-0.15039434224011883,0.008592401927756677,1.0782998820195029,1.468031718575068,1.0042260272587955,0.9212462611830574,-2.880742214081604,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.05,0.0,1.0,1.0,0.0,1.8499279212399216,-0.005230561575490569,0.6140515748272733,0.9872467224737487,-0.05691921317800963,0.07291506315937864,-0.12956660719754323,0.6596536730282466,0.062863233583243,0.0881435398825629,-0.3921842201718162,-0.7959296788959247,-0.3410170154537478,0.09989671434455803,1.1221662162060793,-1.2890408885003246,0.6625273694862253,-0.22401686577093485,-0.3686457016643342,-0.17919433768092968,-0.23816307004836765,0.315257836830127,0.18159191956424653,-1.1629891003725488,0.946407363069398,1.1813344567892703,0.9259823525185018,-1.6305742988026806,-0.18879373030924462,2.181079514833221,0.060731255303846376,-0.016133842611200655,1.0898062247786477,1.739650605428683,0.9773887570526185,1.0602573049565311,-2.744380346726738,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.058333333333334,0.0,1.0,1.0,0.0,1.8555101525440398,-0.006131066386686415,0.6139823925744681,0.9872276331009707,-0.05906028592996213,0.0695560021773192,-0.13059649929869932,0.679541102309326,0.06502476530041475,0.08343198398193112,-0.37772439038551286,-0.895179023103174,-0.3150397661040766,0.1097178631223665,1.129570818051031,-1.3018715402351144,0.6604546316293719,-0.20571706463000128,-0.36726169374886414,-0.1794296943990201,-0.22898655975972984,0.33075381787281377,0.1896215563314203,-1.1536094920562838,0.9241058685191808,1.1746488266917585,0.8474918244758456,-1.4554846749349526,-0.29999866348877857,2.2025445600426745,0.27072426286270046,-0.040131003518044106,1.1233941862089987,1.948595477132069,0.9487260037322526,1.182938508808311,-2.6079467441419824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.066666666666666,0.0,1.0,1.0,0.0,1.8612406560009587,-0.007067911694702899,0.6138921817610818,0.9872356736722208,-0.06118429995128175,0.06580674049645281,-0.13149782878035518,0.6975736687396732,0.06713597915035406,0.07804399923953403,-0.3631267682363286,-0.9842784646008207,-0.28879032429473117,0.11947419478942067,1.1362910799473434,-1.3132989664159072,0.6575273917614123,-0.1873077897702236,-0.3641336306166225,-0.17986318773956375,-0.219439833611551,0.34773442811566146,0.19740401962645074,-1.143273458559077,0.902941584000365,1.1656104829066,0.7616680247731011,-1.2932865953023676,-0.3945071419730728,2.2078442184208487,0.47864615594210624,-0.06363163926410731,1.1774698230418097,2.0980282268783936,0.9182135867876384,1.2904354392293582,-2.4719948277833392,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.075,0.0,1.0,1.0,0.0,1.8671050580921995,-0.008036822662812184,0.6137840250174403,0.9872646411932733,-0.06328538298509849,0.06170925486849208,-0.13227039129690463,0.7138454668285136,0.06924416624186094,0.0720548507608256,-0.3483182559983424,-1.063139477553913,-0.2621335553657396,0.12914470450414317,1.1422652851305828,-1.3234263168234872,0.6538795125964874,-0.1689196609896538,-0.3592842578164957,-0.18049022172008855,-0.20936206270903301,0.36572095498745366,0.20492511611121428,-1.1321022347357945,0.8829059547227918,1.1539311290346073,0.6684861954456833,-1.1430818708214163,-0.4735885257553507,2.19809604116739,0.6829095497540683,-0.08650021895633853,1.2493463146010604,2.1925655250051035,0.8861585232297003,1.3839300909646868,-2.3376067998100547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.083333333333333,0.0,1.0,1.0,0.0,1.8730899961928018,-0.009033205172818606,0.6136607985924813,0.9873086568317675,-0.06535731063260614,0.05730597592236115,-0.13291374351747443,0.7284396101108331,0.07138951744121919,0.06551804205536052,-0.33325598281639324,-1.1316863413409426,-0.23497289769387758,0.1387063802733308,1.1474325165381047,-1.3323503309295974,0.6496342496654898,-0.1506728557507671,-0.35275180478738805,-0.18130485805550273,-0.19861739503486667,0.3842771868657465,0.21217332834694574,-1.1202079570429988,0.8639814706701974,1.1393894734351757,0.5681226520836269,-1.004160234078575,-0.5385543095511269,2.174669557620461,0.8814869158804917,-0.10856316079365991,1.3358573379577883,2.2375892375274242,0.8528819584387004,1.4644113511912416,-2.205778801631928,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.091666666666667,0.0,1.0,1.0,0.0,1.8791829209074669,-0.010052215731017295,0.6135249364654142,0.9873623107180539,-0.06739360487495022,0.052639589471273715,-0.1334272948690207,0.7414213012417155,0.07360349511547842,0.058468105414061174,-0.3179053264781329,-1.18990049556743,-0.20722911539480876,0.1481345290613961,1.1517339959986432,-1.3401623207247968,0.6449036074373019,-0.13267516836264612,-0.3445928092184875,-0.18229960773331622,-0.18709777374306988,0.40301410894624407,0.21913981541852595,-1.1076953788826072,0.846142974695593,1.1218010533231721,0.4608834359414704,-0.8758973617591437,-0.5907785168424806,2.1391533536135645,1.0720546391993135,-0.1296181794806872,1.4336267007639243,2.2388238548161046,0.8187031443923942,1.5326791103221282,-2.07735219899865,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1,0.0,1.0,1.0,0.0,1.885371893043168,-0.011088834114840903,0.6133782616461507,0.987420791957375,-0.06938762448826788,0.047752783341179925,-0.13381034661636118,0.7528351817304181,0.07590799110106848,0.05092781127131963,-0.30223621144657453,-1.2378233826253489,-0.17883299220123355,0.15740306449538366,1.1551139071371292,-1.3469486202922498,0.6397879410514484,-0.1150202998572077,-0.3348842274673995,-0.1834651610468475,-0.17472361668880126,0.42159091777934826,0.22581838075348565,-1.0946633052042967,0.8293589340202199,1.1010137810865706,0.34714663423251135,-0.7577084054515559,-0.631663657074899,2.0933242278963586,1.2520603558855914,-0.14942973942873417,1.5392872849097834,2.201944521481615,0.7839314224882227,1.5893829664272818,-1.95304294097578,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.108333333333333,0.0,1.0,1.0,0.0,1.8916453676199176,-0.012137921089176811,0.6132218989362346,0.9874799938414136,-0.07133263169623613,0.04268801636171018,-0.13406211499745022,0.7627021843709306,0.0783154305253511,0.04291676228324542,-0.2862182693953539,-1.2755503742191865,-0.14972372772356257,0.16648475874617227,1.1575197732358518,-1.3527907941489894,0.6343758798193869,-0.09778643123104014,-0.3237251366203943,-0.18479010339046179,-0.16144298566124016,0.439713184304271,0.232205339126663,-1.0812056627754858,0.8135922590126633,1.0769033616739632,0.22731210569593596,-0.649019199878782,-0.6626068132342278,2.039112206031937,1.4187732175089174,-0.16772936240811775,1.649623116080657,2.1323098066868496,0.7488532109998325,1.6350653928841075,-1.8334957988890954,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.116666666666666,0.0,1.0,1.0,0.0,1.897991965768096,-0.013194255927564865,0.6130562689545639,0.9875365929165748,-0.07322183374084132,0.03748730278030282,-0.13418175302478585,0.7710228557631441,0.0808276124493925,0.03445748914553182,-0.26982502415415527,-1.303221017197605,-0.11985294975778775,0.17535145385661638,1.1589024422320615,-1.3577656069568962,0.6287444941642113,-0.08103509642334208,-0.3112380071755842,-0.18626065042031614,-0.14722989808745698,0.4571294145574624,0.23829926760348286,-1.0674122153228949,0.7988006707054016,1.0493838719786353,0.10175986278166516,-0.5492329227669934,-0.6849553174694822,1.9785903500466562,1.5692934809098413,-0.18420979726416598,1.7616491445083993,2.034825926178702,0.7137311149694303,1.6701982188712128,-1.71932004656987,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.125,0.0,1.0,1.0,0.0,1.9044003197155803,-0.014252611018947507,0.612881112941383,0.9875880914037424,-0.07504847150789275,0.032192056827631,-0.1341684020893284,0.7777796534816389,0.08343454422619205,0.025580232615105017,-0.2530376035927249,-1.3210148138211157,-0.08918872193216779,0.1839744899458162,1.1592157709488795,-1.361944676195106,0.6229599578615622,-0.0648099253969292,-0.29757024527189696,-0.18786026667819788,-0.13208216658610017,0.47362694974058267,0.24410085770948683,-1.053369025794299,0.7849369249031655,1.0184177210321972,-0.02918163002130658,-0.4577012316376594,-0.6999752893018885,1.913959213302462,1.700572768908848,-0.19852140307603294,1.8726389022974168,1.9139166883735614,0.6788047772281336,1.6952094664630613,-1.611109616252484,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.133333333333333,0.0,1.0,1.0,0.0,1.9108588806925164,-0.015307804062954001,0.6126955777098225,0.9876328376037921,-0.07680588386852073,0.026842907707769856,-0.1340212393457407,0.7829327865725174,0.08611410372002778,0.01632888241455723,-0.23584053813788047,-1.329159707759016,-0.05771624608339826,0.19232508254048633,1.1584160817317064,-1.3653939608175238,0.6170782393425132,-0.04913577620163438,-0.28289512769377007,-0.18956934047158336,-0.11601924971583337,0.4890280260303551,0.24961268055728508,-1.0391587242151772,0.7719488437678602,0.9840118743374981,-0.16526457223229762,-0.37369536294566963,-0.7088490794110558,1.8474935808850106,1.809504952922436,-0.21027786048871955,1.9801147110261863,1.7735675441803134,0.6442841337127686,1.710504592362172,-1.509457994174026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.141666666666667,0.0,1.0,1.0,0.0,1.917355695847674,-0.016354741358396933,0.6124983532714964,0.9876700230657739,-0.0784875651018386,0.02147946440500278,-0.13373952396581146,0.7864238695540321,0.08882793289197709,0.006760687307596838,-0.2182365897489294,-1.3279276755255576,-0.025442047116855257,0.20037468785144116,1.1564613614116745,-1.3681729322442004,0.6111458065380446,-0.03401836571551236,-0.26741182938985636,-0.1913648976863432,-0.09908025473566373,0.5031864088102546,0.25483892660469964,-1.024860615921596,0.7597792916669317,0.9462449902581876,-0.3063524527182704,-0.29637667742092866,-0.7126380463104276,1.7815190940190258,1.8929508915963178,-0.21904086258005884,2.081825381968852,1.617397293767746,0.6103714397128068,1.7164760104576882,-1.4149547236352467,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1499999999999995,0.0,1.0,1.0,0.0,1.9238782436713295,-0.017388548044173502,0.6122877709892037,0.9876996393915638,-0.08008733973499715,0.016140177290423267,-0.13332267262939893,0.7881741630602465,0.09152048614507399,-0.0030506554845778702,-0.20024652568939233,-1.3176417375181337,0.007605481128959233,0.2080958323781228,1.1533102075197352,-1.3703335721078727,0.6052009385706727,-0.019443791301317286,-0.25134594616716477,-0.19322002151458434,-0.08132216001635251,0.5159846475931509,0.25978553788583186,-1.010550790707549,0.7483662650406061,0.9052680372557476,-0.4524377831478832,-0.22477135122047187,-0.7122822776198601,1.718349187088454,1.9478410455210144,-0.22432378199279068,2.17572334904049,1.448734173531816,0.5772632164195501,1.7135139453229975,-1.3281836683743165,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.158333333333333,0.0,1.0,1.0,0.0,1.9304131683793824,-0.018404609557195764,0.612062004015584,0.9877224300221141,-0.08159941770731431,0.010862042558746237,-0.13277029898489348,0.788081733510654,0.0941188860801848,-0.013012294936027465,-0.1819073592853248,-1.2986827705591648,0.04137849887592518,0.2154624884723703,1.1489207316925432,-1.3719191214312083,0.5992744352443803,-0.005379212597371461,-0.23494781196450612,-0.19510362738622306,-0.06281819891832223,0.5273319783691182,0.26445998021169215,-0.9963020501662128,0.7376428971940264,0.8612982791009288,-0.6036594066021017,-0.15774733199603652,-0.7086084547256588,1.6602010359427535,1.9713103605999494,-0.22559763717964476,2.259940718040274,1.2706886386734584,0.5451503683128744,1.7020156466004144,-1.2497238866498983,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.166666666666667,0.0,1.0,1.0,0.0,1.9369460565913263,-0.019398683532038056,0.6118192217685458,0.987739808162855,-0.08301855223911156,0.005680406226407441,-0.13208226353173966,0.7860254578481689,0.09653182764654528,-0.023014650107945595,-0.163282166510486,-1.2714796320441797,0.07581125501148261,0.2224508036964716,1.1432492174097002,-1.3729626943078066,0.5933907976585784,0.008226225964395272,-0.21849077349049895,-0.19697998213424509,-0.043656481382347935,0.5371627915710419,0.2688713773577131,-0.9821838632642088,0.7275375335964411,0.8146293139878164,-0.7603125997038118,-0.09400614997923551,-0.7023124431568495,1.6091391785894797,1.9607654278826088,-0.22228439747985662,2.3327705983064986,1.0862049942603869,0.5142340684441304,1.6823866725108516,-1.1801448781730284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.175,0.0,1.0,1.0,0.0,1.9434612147688473,-0.020366984590714697,0.6115577611893542,0.9877537628822552,-0.08434015544599642,0.000628762208153293,-0.13125870161404418,0.7818676283309264,0.09865318455867879,-0.03293175832550843,-0.14445491799725863,-1.236502876251394,0.11082624383336769,0.22903964370550056,1.136248855030813,-1.373485890597529,0.5875692278584328,0.021439773712453203,-0.20226838816646264,-0.19880836734422067,-0.02393868894654726,0.5454353949401246,0.2730305480190943,-0.9682622722910319,0.7179738158911426,0.7656119677421602,-0.9228376032243979,-0.03209000845805665,-0.6939733397627257,1.5670038559923216,1.9139854492054982,-0.21377009950393933,2.392660136500277,0.8980860061110008,0.48471868470779556,1.6550433240719942,-1.1200035193260205,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.183333333333334,0.0,1.0,1.0,0.0,1.9499414928419825,-0.021306255892589453,0.611276278298596,0.9877667547598167,-0.08556039742815107,-0.004261392208186462,-0.13030002732028922,0.7754611072808592,0.10036748588940457,-0.042624877084311126,-0.12552707999522633,-1.1942476906439632,0.1463424780992557,0.23521100315884094,1.1278685906892936,-1.3734975277821075,0.5818245753291996,0.034342956897600634,-0.18659101600374065,-0.2005428171259774,-0.003778812440676647,0.5521308916728919,0.27695002210284303,-0.9545998078630089,0.7088708082743408,0.7146330004940726,-1.0917946468276263,0.029591156698636212,-0.6840633088328008,1.5353647586764436,1.8291705093505373,-0.1994173017846207,2.43821034662594,0.7089914073624737,0.45680521392156614,1.620408991746738,-1.0698362490969249,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.191666666666666,0.0,1.0,1.0,0.0,1.956368192380702,-0.02221381443754177,0.6109738624934001,0.9877816092580057,-0.0866762676178449,-0.008960613505000317,-0.1292069055783686,0.7666604286046622,0.10155844388141583,-0.05194838239782525,-0.10661035929893664,-1.1452090752301742,0.18228632714340262,0.2409501937137351,1.1180522775836859,-1.3729927046525516,0.5761681727112195,0.0470291863570606,-0.17178221301062035,-0.202131989040631,0.01669815016388508,0.5572519183961658,0.2806439682511204,-0.9412554557619196,0.7001432117395272,0.662083976678558,-1.2678166233237231,0.09270614257501641,-0.6729634120886052,1.5155077582494871,1.7049303988755167,-0.1785839950404866,2.4681860667348823,0.5214051386763563,0.4306772660113456,1.578904992337935,-1.030144572979328,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2,0.0,1.0,1.0,0.0,1.9627211036774679,-0.023087559047005164,0.6106500935943363,0.9878014163614369,-0.087685582317399,-0.013441449329823715,-0.12798018568484754,0.7553372862974048,0.1021202909764305,-0.06075824321448195,-0.08781645270821758,-1.089849546698865,0.2186044978282022,0.24624573610348358,1.1067383136338982,-1.3719524254058573,0.5706085184610562,0.059601419535092084,-0.15817550935581537,-0.20351921704331885,0.03735762200490472,0.5608209773174978,0.28412797653636546,-0.9282847246573767,0.6917017320580187,0.6083226029832034,-1.451539845386547,0.15892087146876843,-0.6609840959236446,1.5084652050949185,1.540198442670578,-0.15064807169080208,2.4815369922405495,0.33757016910384685,0.4064809362231281,1.5309356076382952,-1.0013716191624655,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.208333333333333,0.0,1.0,1.0,0.0,1.9689787174818594,-0.023925932420312858,0.6103050232649007,0.9878294448326013,-0.08858692577742218,-0.017678227867795132,-0.12662079119358402,0.7414005231758296,0.10197135681495022,-0.0689229576236717,-0.06924453902454114,-1.0285608724146427,0.25527850975239336,0.25108890376345516,1.0938599468272434,-1.3703440234614055,0.565151771112492,0.07217027310864257,-0.14611223896611072,-0.2046427902354777,0.0580571000345609,0.56287808788123,0.2874186505215059,-0.9157398623012813,0.6834536847534861,0.5536293381530216,-1.6435142615085763,0.22978859471411095,-0.6483893766945492,1.515092980610977,1.3340695715138913,-0.11503655404936142,2.4774318055207125,0.15938985485371537,0.3843001513037958,1.476867914622202,-0.983867743253124,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.216666666666667,0.0,1.0,1.0,0.0,1.9751186557054787,-0.02472783236572618,0.6099390667130599,0.9878690781658861,-0.08937951738246956,-0.021646678901972458,-0.12512956312833454,0.724820606696049,0.10106906910278673,-0.07633655579234819,-0.050967491886426575,-0.9616220830995411,0.29233992398856745,0.25547289173936727,1.079346409275422,-1.3681226154939554,0.5598020288494804,0.0848529692119417,-0.13594101649725052,-0.20543649294414154,0.0786481520969166,0.5634774748983931,0.2905329790580954,-0.9036702594136733,0.6753039363371333,0.49816242518358145,-1.8440962677273065,0.3066135482651067,-0.6354235609927228,1.5361864147480038,1.0855828339030904,-0.07125855787085245,2.4553086213039785,-0.01170546834404762,0.3641295746219819,1.4170075473941202,-0.9778430850713882,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.225,0.0,1.0,1.0,0.0,1.981118362527431,-0.02549247150775579,0.609552796420988,0.9879237770756916,-0.09006300330314458,-0.025323376271010514,-0.12350705542101112,0.7056584907449909,0.09942547615970573,-0.08293311723277455,-0.033017746811570714,-0.8891561715660953,0.3298855993581359,0.2593916108498482,1.0631250090317883,-1.365233797656987,0.55456137842928,0.0977733800211093,-0.12801919173439255,-0.20583043286665859,0.09897891038962721,0.5626829967421625,0.2934874767652056,-0.8921230698447127,0.6671563000022963,0.441914161031568,-2.0533283478829167,0.39028992307622357,-0.6223392519711535,1.5726143642076016,0.7934916024000713,-0.018941153830625557,2.4149458205069068,-0.17492861640397983,0.345847159249163,1.3515713599152446,-0.9833046160713321,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.233333333333333,0.0,1.0,1.0,0.0,1.9869560928858598,-0.026219188338367866,0.6091466353433963,0.9879970704143778,-0.090637175509835,-0.028685000724714128,-0.1217532833300613,0.6840983682531916,0.09712239400672408,-0.08870221426935757,-0.015373395470331647,-0.8110873860581507,0.3680921943748171,0.26283812775656007,1.04512427014404,-1.361617783442685,0.5494297079832945,0.11106320861540173,-0.12271615645724933,-0.20575217884131863,0.11889724910536505,0.5605619979583267,0.29629709837891477,-0.8811440700817526,0.6589155260692777,0.38467053475889856,-2.270810954713638,0.4811166908982978,-0.6094253291797824,1.625438860666688,0.45608402087155914,0.04213209174931565,2.3565564838161372,-0.33034410188255814,0.3291880006866521,1.280656958517965,-0.9999755980158365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.241666666666666,0.0,1.0,1.0,0.0,1.9926122250565637,-0.02690721448834406,0.6087204511838634,0.9880925730475737,-0.09110162283925681,-0.031707428440043754,-0.11986742837832558,0.6604825411946563,0.09432513807555601,-0.09370461774334031,0.0020553869705049466,-0.7271002401114836,0.4072287216501849,0.26580278642916316,1.025278159786561,-1.3572151861420154,0.544404289609617,0.12486402769888744,-0.12041779138653323,-0.20512823133750333,0.13825485178656283,0.5571772617107865,0.29897394344331646,-0.8707787872027466,0.6504900400353657,0.3259761948689843,-2.4955753271244596,0.5785878589111393,-0.5970332407713297,1.69597865956572,0.07112747822661358,0.11197939195744355,2.2809051334169155,-0.4791128547137413,0.31372074190500365,1.2042077593702216,-1.0271984846239435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.25,0.0,1.0,1.0,0.0,1.9980708974822856,-0.02755540369553717,0.6082730564066393,0.9882140253648737,-0.0914553181259196,-0.03436465399923864,-0.11784750915574062,0.6370554168193987,0.09191914509943379,-0.09793988785706627,0.022016994286727265,-0.6517930249542634,0.44741446883321073,0.2682710643377098,1.003531348025299,-1.3519746524608327,0.539479153970439,0.13932951960816373,-0.12153069848680577,-0.2038858556420279,0.15691233466231364,0.5525767837130977,0.30152577741066483,-0.8610739407589155,0.6417955513255453,0.2576557917107902,-2.721898399645457,0.7045382902757424,-0.5941943433513064,1.7675707292183207,-0.2952752782603199,0.18182674491470985,2.200617403286808,-0.6014180834928728,0.29637261232208445,1.1144960498911938,-1.022458594367941,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.258333333333333,0.0,1.0,1.0,0.0,2.0033519593349727,-0.028157961613099015,0.6078047825907178,0.9883624270516994,-0.09168950776883857,-0.03675536333047575,-0.11567968803604768,0.6171589757793742,0.09083462696535048,-0.10162606064837582,0.047437368306660135,-0.6065321938184378,0.48829696593332617,0.270097049624343,0.9799131864591367,-1.3454728813040864,0.5345010505537618,0.15432353985252611,-0.12533904602420523,-0.20209778558892483,0.17493180850800963,0.5471536269859053,0.30391348698201787,-0.8522038530378934,0.6334490634625667,0.17023526854796467,-2.937620557150169,0.8866934156378781,-0.6116214139195675,1.8113179173926637,-0.537755104742547,0.23956498960934103,2.135325644501156,-0.6690792641223453,0.2745759000228998,0.9996069382392303,-0.9217687566261223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.266666666666667,0.0,1.0,1.0,0.0,2.008497314896675,-0.028711590571842648,0.6073163587369047,0.9885351076213381,-0.09179949810204437,-0.03903257858333409,-0.11334747883180118,0.6012351358802096,0.09062965640884826,-0.10525534724089577,0.0758674698916283,-0.5859571382165737,0.5293818280423492,0.2711083188135092,0.9545710054061295,-1.337196428866868,0.5292854637384462,0.16951815156470812,-0.13049328356584822,-0.19989310581520556,0.19250109540399957,0.541425462644392,0.3061020424110465,-0.844413825121595,0.62643273871511,0.06938256265515697,-3.1352799957412936,1.1097933635621038,-0.6429147483260289,1.8279164386154552,-0.6669648014086366,0.2886088552732252,2.0864665075699707,-0.6948955181900396,0.25145297639924236,0.8606913686573825,-0.7330258167560921,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2749999999999995,0.0,1.0,1.0,0.0,2.0135327189890573,-0.029219409215843088,0.6068064820863754,0.9887296285738927,-0.09179069865539241,-0.04124872772011775,-0.11084553072663204,0.5879382211766626,0.09068050507289947,-0.10901747423371722,0.10451915001871763,-0.5741450350493221,0.5704075679258707,0.2712534256685956,0.9276585198634485,-1.326976325244718,0.523785804748328,0.18478881382945037,-0.1364551260476825,-0.19728763800103774,0.20970625030084247,0.5355720350160713,0.30810436992200524,-0.8378589968936037,0.6212319665166318,-0.03635021589668219,-3.3152228778707804,1.3466581593792215,-0.6780274595447966,1.8355978188635154,-0.752163210822539,0.3370267286696871,2.0460062824111125,-0.70728137133937,0.22966870402466477,0.7055811654929589,-0.4977490624351244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.283333333333333,0.0,1.0,1.0,0.0,2.0184760964283774,-0.029682929213124702,0.6062743749184671,0.9889442291329437,-0.0916651904018925,-0.0434231103786292,-0.10817226085451499,0.5766109768157978,0.0910025059777216,-0.11287490080822402,0.13341186362560353,-0.5655488100629218,0.6112740146380694,0.27050248188189785,0.8993172907749498,-1.3147521262105477,0.5179850060793663,0.2001114485457667,-0.1430293370795572,-0.19427599367071077,0.22660120011085144,0.5296374397887358,0.3099298541447909,-0.8326541390300457,0.6181369210078579,-0.14533314618382365,-3.478484340809269,1.58801118078014,-0.714759062577961,1.842908920319879,-0.8221585410087207,0.38634328023177955,2.0113288432284127,-0.7176807415281283,0.20871815931284843,0.537762226211862,-0.2324293517930398,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.291666666666667,0.0,1.0,1.0,0.0,2.0233426020663954,-0.030102053640012134,0.6057191693825629,0.9891774914550191,-0.09142265474846593,-0.04556253493842398,-0.1053273184295749,0.5670423690870204,0.09167759400308062,-0.11684786838051471,0.16272141014607128,-0.5580330952832967,0.6519613205326493,0.2688312065655319,0.8696837808499607,-1.3005094722317156,0.511873153705362,0.21550396250144835,-0.15015776839782785,-0.19084858333050808,0.24322839768798268,0.5236106893239358,0.3115830059105527,-0.828896293123406,0.6173581439867478,-0.2570180617807194,-3.625457505532992,1.8297237029840785,-0.7525573707380939,1.8534054430953728,-0.8883333100993979,0.43684636212264316,1.9816624246266867,-0.7310180112634534,0.18817584257948328,0.3589714597812588,0.055880598283259975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3,0.0,1.0,1.0,0.0,2.0281470294193586,-0.03047589199279874,0.6051397422885557,0.9894280958943047,-0.09106161644841493,-0.04766885679678332,-0.10231082619412986,0.5592443136241356,0.09275843159417496,-0.12098758300333795,0.19254794717382498,-0.5507352898774059,0.6924501599664158,0.26621884751888586,0.8388929990160666,-1.284256731160813,0.5054423832337314,0.23100153926402292,-0.1578348922478805,-0.18699522096866672,0.2596289071879629,0.5174538062676782,0.3130661181877823,-0.8266712813670247,0.6190682643125789,-0.3709804354502755,-3.756244957064525,2.0696103579831737,-0.791246734194212,1.8685386855185326,-0.9549129955709884,0.48855031245054026,1.9571441381739791,-0.7499803774287228,0.16787802826479958,0.17049436659841932,0.36346589193040124,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.308333333333334,0.0,1.0,1.0,1.0,2.0329049076314143,-0.03080325720975172,0.6045347124981516,0.9896946954173236,-0.09058008835203299,-0.04974184130083417,-0.09912318942109033,0.5533286393754192,0.09426962973701591,-0.12535718693333264,0.2229352586287772,-0.5432799042633439,0.7327037245494706,0.2626481993080273,0.8070796982322186,-1.2660159662653294,0.4986857081354585,0.24664627392675723,-0.16607298499067766,-0.18270607812299908,0.275847466657549,0.5111110163667905,0.3143809730482994,-0.8260547203467656,0.6234159088522545,-0.48678189483718937,-3.870884733177913,2.3062368771731556,-0.8307318748362402,1.888857601374296,-1.0231432819522102,0.5413940339632484,1.938358336454069,-0.7765368970684849,0.14781867779178892,-0.02639697137719388,0.6876401367069862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.316666666666666,0.0,1.0,1.0,1.0,2.0376329303769434,-0.031082898731024686,0.6039024756334339,0.9899758570085841,-0.08997586336273028,-0.0517802678396828,-0.0957650793074566,0.5494400585735842,0.09621427288030165,-0.13002257647234616,0.25389676264509425,-0.5354794464292256,0.772667315456818,0.25810581593826604,0.7743782534631014,-1.2458194498745938,0.4915968519864607,0.26248249928692785,-0.17488728028041733,-0.17797198706927925,0.29193487946219737,0.5045115246498701,0.31552976281764544,-0.827111230889978,0.6305289332576953,-0.6039597384309348,-3.9694771384814342,2.5384665040269283,-0.8709195419411919,1.9144738765671538,-1.092962622751665,0.5952960382959249,1.9260820851050409,-0.8124360347401616,0.12808197339316263,-0.2303086065250759,1.0258602682005091,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.325,0.0,1.0,1.0,1.0,2.0423489949694718,-0.031313604866373294,0.6032412493069023,0.9902700355944505,-0.08924665020870264,-0.053782355926301095,-0.09223746647314274,0.5477152954953866,0.09857535144585433,-0.13504666937688264,0.28542799078950853,-0.5272187807168536,0.8122711752038555,0.2525822036675117,0.7409217459241947,-1.223708191198214,0.4841703824364386,0.2785541718695431,-0.1842890287032054,-0.17278447748473366,0.307948834742633,0.49757041578778777,0.3165156726048521,-0.8298931971221836,0.6405135799889297,-0.7220280040010518,-4.052265078912867,2.765307264053596,-0.9116932120048982,1.9452222684521958,-1.1636632550691601,0.6501814517111848,1.921127752334163,-0.8593315583804695,0.10881650771349283,-0.43970517377753593,1.3754011632417673,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.333333333333333,0.0,1.0,1.0,1.0,2.047071974601011,-0.03149425179685941,0.6025491273380695,0.9905755629861263,-0.08839015196395555,-0.05574592724565446,-0.08854166615850034,0.5397336167439776,0.09941610089202194,-0.13566112791256366,0.3172771092187463,-0.5099341020057846,0.8449850948087805,0.24607201587158184,0.706840502147887,-1.1997309954737005,0.4764019651197124,0.2949028704277978,-0.19428166786490333,-0.1671356295407595,0.3239536753344334,0.49018933201019566,0.317343371279537,-0.8344396504529369,0.6534522859783914,-0.8309094618910218,-4.152867285788142,3.0068175175771295,-0.9478311416814011,1.9416722002097375,-1.202247558155864,0.7322352789540038,1.5631033713692122,-0.4803735850892743,0.001256482018833216,-0.5758935705951473,2.5108779023725147,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.341666666666667,0.0,1.0,1.0,1.0,2.051668900249666,-0.031616098390939526,0.6018900988263967,0.9908899933282594,-0.08739696223808925,-0.05760301432443294,-0.08473892172247054,0.552002677878642,0.10508308255503677,-0.14510281390903446,0.353033273178895,-0.518630604754277,0.877104101034941,0.2387337126359947,0.671707291161059,-1.1735945659052618,0.4683731967417486,0.3109153752063721,-0.20432648800580314,-0.1605805561688336,0.33400055759878655,0.4895641893696332,0.31653661397183264,-0.8394914232987694,0.6823615450284716,-0.9538304651579915,-4.167855235444118,3.230403034925571,-0.9945444494740019,1.9968155024953727,-1.2356066545551732,0.794046962192474,1.0532871090490792,0.24374042812438268,-0.10457353043140549,-0.6215073515469061,3.6005606949575197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.35,0.0,1.0,0.0,1.0,2.0566308446184287,-0.03168961808529395,0.6010840100843988,0.9912019481592822,-0.08626183513623614,-0.059638536813759295,-0.08075171014441089,0.5883329398172784,0.11583473578419794,-0.1661671608434649,0.3903763520651376,-0.5550028528892582,0.9116943228315889,0.23017484145228198,0.6373762482238183,-1.1458909448916077,0.4598262242951457,0.32818312880272066,-0.21487511210748955,-0.15390151350421827,0.3415084604852514,0.49425167247893537,0.31560047910568023,-0.844798106312052,0.7134616308943501,-1.0906316366695912,-4.081124545772465,3.416331909511192,-1.0501301034981725,2.1263963149620704,-1.2776737674894918,0.8114062469577626,0.7494132311251422,0.8520635410812427,-0.11721679121559969,-0.6284246141523231,3.800439188594793,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.358333333333333,0.0,1.0,0.0,1.0,2.061894575395502,-0.03170850305351802,0.6001659110533969,0.9915073346565904,-0.0849987664541424,-0.061794261903070906,-0.07661516964389106,0.6179149348817519,0.12447060995142653,-0.18367273009691382,0.4243897287857133,-0.5788236420333376,0.9409689024957794,0.2205565186915015,0.6036885487315179,-1.116655700746742,0.4508710283501124,0.34635531378907325,-0.22562105079729466,-0.14705711871953756,0.3464907781175389,0.5037652483876539,0.314583000784906,-0.8499651668679747,0.7457021981717181,-1.2112116296274373,-4.013167253689476,3.59799768763553,-1.0950816297337918,2.220195004194664,-1.2922163683846317,0.8342603658374914,0.44620303009480056,1.4080029024310703,-0.1253450421117519,-0.5995934998961694,3.9011015436567797,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.366666666666666,0.0,1.0,0.0,1.0,2.0674020909547473,-0.031670870874210215,0.599156496247529,0.9918044225697576,-0.08360929778719219,-0.06402512378571178,-0.07234815974862908,0.6415070464994896,0.131153612362885,-0.1987732304611497,0.45703667417282146,-0.5924164132177085,0.9674114673467418,0.20998798095849136,0.5704901273289937,-1.0859243167643489,0.4415748637995825,0.3651863788726317,-0.23641205158056675,-0.1399971740735934,0.3489451776534981,0.5177183875194532,0.31351139507048437,-0.8547913313103215,0.7784799899552964,-1.3199225069582095,-3.9625195015518533,3.7753288759649184,-1.132871253767227,2.2884526871455204,-1.2932673639629018,0.8633310292177654,0.14484816888990948,1.9166975878293635,-0.13025447135551316,-0.5504959093176298,3.938459482464496,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.375,0.0,1.0,0.0,1.0,2.073104537871545,-0.031576095501452975,0.5980714400126822,0.9920922091718266,-0.08209471763484934,-0.06629168273365348,-0.06796262677049401,0.6601650789426247,0.13615731303356887,-0.21186484422621643,0.48853512887750106,-0.5967285835421211,0.9920892813823171,0.198557810242198,0.537646557038987,-1.0537335528139933,0.4319898407873253,0.38449619190816525,-0.24717550686334303,-0.1326682682325748,0.3489049142657041,0.53571020818481,0.31241209292898076,-0.8591400986899352,0.8113431895461264,-1.4187213103930185,-3.9269544653216926,3.948128342991666,-1.1649526623320627,2.3377174324666172,-1.2886247748981867,0.8985815141631454,-0.15041551736356684,2.3748373581983317,-0.13221703165881005,-0.48714684688385246,3.926952200876408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.383333333333333,0.0,1.0,0.0,1.0,2.0789622678150756,-0.03142409958840106,0.5969248705837046,0.9923702173813516,-0.08045659440925985,-0.06855607649627433,-0.06346772759632419,0.6749828028631359,0.1397321589017824,-0.2230906948049871,0.5189416542301246,-0.5920150684219021,1.015440173781886,0.18634262578527439,0.5050408862402989,-1.0201221777144878,0.4221589860940481,0.4041483360804087,-0.2578891311622032,-0.12502081550420766,0.3464382523641053,0.5572990101560921,0.31130777787617087,-0.8629104454250524,0.8439291933032366,-1.5088363147275825,-3.904304149005794,4.115880185244077,-1.1922578239079584,2.372706920479659,-1.2835228568449737,0.9393032490957559,-0.4358838007623067,2.7779364186272004,-0.1317404457712723,-0.41306459231551074,3.875765039835135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.391666666666667,0.0,1.0,0.0,1.0,2.084944870689969,-0.031215224522359624,0.5957303240816973,0.9926384313387115,-0.07869680544394,-0.07078070750657071,-0.05887146072244397,0.6870511710635513,0.14209192721012473,-0.23254132002236821,0.5482741934822453,-0.5783118917690296,1.037646797818337,0.17341053833007164,0.4725748212222238,-0.985135549726592,0.41211887705552597,0.4240413072494929,-0.2685675544774259,-0.11701321408097887,0.34164018425299897,0.5820091484952633,0.3102164188327929,-0.8660245085618604,0.8759392735433786,-1.5911932972264216,-3.8922567643308517,4.277487554557835,-1.2154686828023242,2.3972628588580758,-1.2818053321784728,0.9843958262629691,-0.7089704382521622,3.1229424020023178,-0.12938113385238426,-0.330599530870066,3.7917004608978933,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3999999999999995,0.0,1.0,0.0,1.0,2.091030877035787,-0.030950231702240833,0.5945009316697418,0.9928972587980286,-0.07681757534585881,-0.0729279159129638,-0.05418129447055018,0.6974102233480769,0.14340600788645697,-0.24030990636553634,0.5765284995777308,-0.5556096536429812,1.0587875511740634,0.15982273749816736,0.440169940168118,-0.9488307184718572,0.4019011747140094,0.4441027170613766,-0.27925255336517774,-0.10861421839982484,0.33462207839323593,0.609348050189464,0.3091514256452978,-0.8684204376062201,0.9071242009848681,-1.6665632138457143,-3.888404209700682,4.43128089263896,-1.2351013286160217,2.414556449159617,-1.2861968469329788,1.0325303274359463,-0.9682851144700932,3.408872987782001,-0.12564381816768777,-0.24137052394453296,3.680062727171971,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.408333333333333,0.0,1.0,0.0,1.0,2.097207116493658,-0.030630353471385277,0.5932493930759558,0.9931474897130909,-0.07482155574002032,-0.07496000163923303,-0.049404419116485555,0.7069817222295196,0.14379174919423732,-0.24649513129957185,0.6036815031773969,-0.5239197821412113,1.0788980224883558,0.1456344847659764,0.40776808439387907,-0.9112808681826093,0.3915338549119256,0.4642839147354865,-0.29000416859297556,-0.09980437529037976,0.32550209901183075,0.63882369829163,0.30812235519666475,-0.8700473506276026,0.9372736523295782,-1.7356166476035202,-3.8904123111234914,4.575172767926614,-1.251537462640968,2.4270496237456953,-1.298358302335565,1.082246091653884,-1.2135656210791301,3.6367617216756676,-0.1209365325145062,-0.14648262638192966,3.544934630630525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.416666666666667,0.0,1.0,0.0,1.0,2.103467342348315,-0.03025733785679308,0.5919879489579808,0.9933902441976337,-0.07271190012245976,-0.07683940376534368,-0.04454782086076326,0.7165198889446383,0.14331166478336804,-0.25118942751153045,0.629688465205932,-0.48329482699685644,1.097993245845052,0.13089579337144203,0.3753297349827265,-0.8725778390064136,0.3810422170033266,0.48455354412380486,-0.3008918584041038,-0.09057678353892677,0.31439598470858376,0.6699607455507252,0.307135816770056,-0.8708618147125856,0.9662064448287102,-1.7989405455465854,-3.89616411097507,4.706826694900957,-1.2650345423241116,2.436461064887171,-1.3189730786457188,1.132009126958336,-1.4454844763916053,3.8092643584957275,-0.11555482359105418,-0.04668201098576796,3.3893130031326058,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.425,0.0,1.0,0.0,1.0,2.1098107903114984,-0.029833518533035366,0.5907283719888428,0.9936269053785753,-0.07049238140197418,-0.07852887458353058,-0.03961834082453062,0.7266109866340645,0.1419781572492519,-0.25446856481211216,0.6544798642545759,-0.43382857178596895,1.1160677815416724,0.11565214234019998,0.3428320158776279,-0.8328337566009267,0.3704499458731904,0.5048915991502727,-0.3119870532370709,-0.08093755650774083,0.30141069107197066,0.7023114375998921,0.3061964414701472,-0.8708253841440321,0.9937622023817883,-1.8570424219609045,-3.9037669811439493,4.82374397945699,-1.2757309850487808,2.443832164247638,-1.3478966866231346,1.1802302326659686,-1.665296806826676,3.9300342860998394,-0.1096914182251385,0.0575343581320098,3.21527660905899,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.433333333333334,0.0,1.0,0.0,1.0,2.116240818272365,-0.029361875401979043,0.5894820210512304,0.9938590412000523,-0.06816748261447256,-0.07999165858355019,-0.03462275403418355,0.7376374344476169,0.1397605727178432,-0.2563723146924817,0.677968867227953,-0.3756568511545643,1.1331053393327348,0.09994508633876029,0.31026695196366066,-0.7921821060154638,0.35978003391918023,0.5252840801945988,-0.32335680318115606,-0.07090627966116063,0.28664103792813916,0.7354613169857225,0.3053076264663037,-0.8699029087437188,1.0197943883130267,-1.910378433999933,-3.911642751818775,4.923406545439777,-1.2836758969496975,2.4495310221450795,-1.384307466181346,1.2253012438445086,-1.8746974146716933,4.003358734545888,-0.10346259074614728,0.16578611987788205,3.024063349904562,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.441666666666666,0.0,1.0,0.0,1.0,2.1227628734868853,-0.02884604016828564,0.5882599544483647,0.9940883215798029,-0.06574245004964316,-0.081191670992724,-0.029567748009880452,0.7497917357711562,0.13659606690378645,-0.25689506611072727,0.7000526373179992,-0.30895070298842753,1.1490756075690058,0.08381250177353443,0.27763797001398166,-0.7507769808435971,0.34905534759069545,0.545717116186024,-0.3350588443400933,-0.060515869110332354,0.2701657341607758,0.7690340831756569,0.3044720649577114,-0.8680622821460674,1.044163258213531,-1.9593631054407132,-3.9184993472133267,5.003337409230131,-1.2888450670530893,2.453356898629313,-1.4268937574867224,1.265613646358936,-2.0755754470090615,4.033720733469728,-0.0969382501707261,0.27772211642238087,2.8162149167554418,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.45,0.0,1.0,0.0,1.0,2.1293833787002288,-0.028290340389526103,0.5870730728749473,0.9943164237784688,-0.06322336038072483,-0.0820936219115067,-0.02446003574693051,0.7631181020766858,0.13240301031581447,-0.2559830430566602,0.7206173727093252,-0.2339111343142094,1.1639260594752014,0.06728903458141507,0.24495862951010522,-0.7087931491949616,0.33829928280162874,0.5661733618384207,-0.34713836580593477,-0.049812718888511694,0.2520481138113215,0.8026899958768846,0.3036919889634583,-0.8652742068033458,1.066731303592284,-2.004379568568348,-3.9232143800990005,5.061084344866787,-1.2911603234510027,2.4546888608535955,-1.4740267197477785,1.299562957822107,-2.2697383241014553,4.02538245244962,-0.09018175257180294,0.39297101157964587,2.5917544153743055,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.458333333333333,0.0,1.0,0.0,1.0,2.136108413637244,-0.027699778099627856,0.5859323052942477,0.9945449362290447,-0.06061711808753819,-0.08266315679016581,-0.019306406346676554,0.7775135257320834,0.12709349591256347,-0.2535268009982772,0.7395491440229098,-0.15076987631341848,1.1775870810885654,0.05040617563072863,0.21225106367899832,-0.6664255750958173,0.3275360088665121,0.5866285972002506,-0.3596259563358896,-0.038856486479963905,0.2323367620924182,0.8361237907164839,0.30296903574818135,-0.8615127652864066,1.087359165136436,-2.0458057925383057,-3.924829001620303,5.094268408220069,-1.290523678208525,2.45255396336872,-1.5239040309769303,1.3255862078948863,-2.458853863734725,3.982262462756143,-0.08328926425757444,0.5110743055188749,2.350275573573768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.466666666666667,0.0,1.0,0.0,1.0,2.142942629534076,-0.027079993782600013,0.5848488202713048,0.9947752575574954,-0.05793143067836025,-0.0828669847494359,-0.01411379219193661,0.7927488711329039,0.12058499629978593,-0.24936007419306117,0.7567403775522185,-0.05978828811730622,1.1899706086501423,0.03319227137244331,0.1795448128164335,-0.6238886757246271,0.31679055483148666,0.6070492612278994,-0.37253676632221694,-0.02771961542359692,0.2110672160824094,0.8690610369228203,0.3023038345591654,-0.8567563017113645,1.1059025631518469,-2.0840262213231315,-3.922516654853684,5.100625936599997,-1.286840186104281,2.44572465964616,-1.5746831770318426,1.3421981832172698,-2.644358970864346,3.9078043221301817,-0.07642378643498926,0.6314525230308377,2.0910493061684443,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.475,0.0,1.0,0.0,1.0,2.1498882981127307,-0.02643720235238982,0.5838342618018411,0.9950084928048569,-0.055174746201212564,-0.08267300897830732,-0.008889331514568765,0.8084805524299012,0.11281156553993935,-0.2432594442960906,0.7720981489952514,0.038742191658628494,1.2009725801669406,0.015672405275343106,0.1468757860981036,-0.5814151428191507,0.3060886724314407,0.62739067486102,-0.385870675953087,-0.016486516759676075,0.18826411257801243,0.9012538627519869,0.30169530597426486,-0.850988556569226,1.1222099869059101,-2.1194476176725727,-3.9155909096640253,5.078085232805514,-1.2800446031766344,2.4327944740147345,-1.6245995431421367,1.3480375566418397,-2.8274292987914555,3.8049315559483943,-0.06984652283318349,0.7533790329002432,1.8131032719285223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.483333333333333,0.0,1.0,0.0,1.0,2.1569444382219007,-0.025778101778152766,0.5829010037831067,0.9952453481114174,-0.05235615747767363,-0.0820504553453195,-0.003640414098955584,0.8242564411059553,0.10373421607428976,-0.23494599002197405,0.785551497747329,0.14450125043540432,1.2104785445422857,-0.002131855588766238,0.11428496432203308,-0.5392539218445352,0.2954564781118761,0.6475958357948116,-0.3996134253745859,-0.005252322812899593,0.16394339443588513,0.9324765628552936,0.301139725845279,-0.8441999844963605,1.1361209510173222,-2.1525160371662024,-3.903558945883609,5.024894596047127,-1.2701273165843052,2.4122439206325264,-1.6720842694352556,1.341921011159552,-3.008986017340465,3.6760478520602025,-0.06394095915351117,0.8759631244506494,1.5152812160106643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.491666666666666,0.0,1.0,0.0,1.0,2.164105985717611,-0.025109757980918298,0.5820624149377622,0.995486025357364,-0.04948527961313293,-0.08096998711878607,0.0016253018806516944,0.839518968242763,0.0933504441184211,-0.22408995620752423,0.797057157599287,0.257144822824188,1.2183724491722892,-0.020202862010760266,0.08181647033337677,-0.4976668995516986,0.2849198838217023,0.6675947402048954,-0.41373874711034125,0.005878833426316459,0.13811434562233801,0.9625213269529903,0.30062962332170634,-0.8363891711617152,1.1474646738394212,-2.1837358426535842,-3.8862160621017856,4.939801168424175,-1.257158322962132,2.3825058376995445,-1.7158909526567756,1.3229002274013133,-3.189721077883903,3.523052551081931,-0.05922717166177538,0.9981454022472924,1.1962868683715389,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5,0.0,1.0,0.0,1.0,2.1713630030361792,-0.024439472178615477,0.5813331207358382,0.9957301184618899,-0.04657211045696748,-0.07940378402218883,0.006899912957337102,0.8536214680757366,0.08156738335588064,-0.2086180705944478,0.8068463535026543,0.3841234245193785,1.2251388680425515,-0.038527452966325974,0.049514696620336654,-0.456923902370799,0.27450383939584055,0.6873042664231374,-0.4282116079188655,0.016796014310455628,0.11078137647115341,0.9911941053733258,0.3001526063175827,-0.8275642277922389,1.1560590654901812,-2.21461923333134,-3.8674979804828538,4.812450725902361,-1.2416056268984643,2.3404415580036897,-1.7658913451993952,1.2909952117207661,-3.375698726622703,3.3311159930015832,-0.05864359729704005,1.1232288816941538,0.8329619987377113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.508333333333333,0.0,1.0,0.0,1.0,2.178695673956957,-0.023774279678230533,0.5807573681761401,0.995981569867991,-0.043626040328833465,-0.07726052094299247,0.012177561026182572,0.8654732578386529,0.06834603814226996,-0.1868688662460028,0.8148981653461644,0.530643548971746,1.231359629050835,-0.0571131825662826,0.017358170658662547,-0.41745938745332595,0.2642264567067279,0.7066020995049569,-0.4431702695303312,0.027395420288329225,0.0818527001786263,1.01803992683635,0.29965223003342234,-0.817668689800146,1.161347373818383,-2.2470053919867756,-3.851082763771237,4.635260245021052,-1.2239222694924246,2.2834982935749903,-1.8304660843268916,1.2460182909697284,-3.5722611947550695,3.091056627324096,-0.06445468333287074,1.2518256823465168,0.40841860851593914,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.516666666666667,0.0,1.0,0.0,1.0,2.186073749018412,-0.023122699794670007,0.5803711578377874,0.9962412492395666,-0.04065860875419015,-0.07446895536761475,0.017453524991982307,0.8737509881121284,0.05401280781118335,-0.16116992875972158,0.8206937477409557,0.6836473288503851,1.2362153272865593,-0.07597754283277224,-0.014670016109183963,-0.37966956495378146,0.25410513490430015,0.7253625713160539,-0.45871937599098034,0.03756298582661777,0.05124368989190225,1.0427117158287273,0.2990783615953682,-0.806700466419797,1.1628660422987802,-2.280771752886443,-3.833179375967987,4.425651909922051,-1.2039887372795661,2.2128983599456498,-1.8938626472554365,1.1865017380629945,-3.7714515787130827,2.8309821005548486,-0.07367594154999102,1.3738078213647364,-0.043587964090017195,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5249999999999995,0.0,1.0,0.0,1.0,2.1934643278383756,-0.022493610123091208,0.5801746991620259,0.9965019939889972,-0.03768253717544552,-0.07104648079799813,0.02272003377387281,0.8777989083389824,0.039045552359750234,-0.1339534987086731,0.8240753165284304,0.8297391670494101,1.2384263317232078,-0.09512604511438999,-0.04652815227413723,-0.34369852228795844,0.24415997775206846,0.7434837388373844,-0.47473464698458845,0.0471704492560458,0.018995173866741582,1.0652229618455975,0.2984242976742558,-0.7947718927774003,1.160620907750216,-2.3149819540226093,-3.8103405323634925,4.205571204875096,-1.181918098064288,2.130036779991551,-1.9384048442374002,1.1118611600987134,-3.9622832555950596,2.5757840612386973,-0.08361257453407211,1.481586761554381,-0.48868477245183506,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.533333333333333,0.0,1.0,0.0,1.0,2.2008348954552512,-0.021894124371766258,0.5801629990188638,0.9967545662133122,-0.03470878007613295,-0.06703360189175438,0.027966614679657355,0.8775824720889115,0.023828951153846,-0.10566084329020381,0.8252823471318521,0.9653706280680687,1.237352118115218,-0.11456057539981572,-0.0781756916485755,-0.3095767115391965,0.234406499936562,0.760863184315913,-0.491026123394937,0.05609400516159632,-0.014794364368015412,1.0856414501827056,0.297684818686467,-0.782007353727224,1.1547212960912496,-2.349312179018387,-3.7829668730828794,3.9851112335382544,-1.1582139454930591,2.0354268358594796,-1.9601259628858525,1.023399678222914,-4.139136432813416,2.3281343686701605,-0.09443619096752842,1.5750505073631915,-0.9193502712779544,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.541666666666667,0.0,1.0,0.0,1.0,2.208154828641103,-0.021329778564881628,0.5803309434549455,0.996989330146837,-0.03174662795601423,-0.06247751253953961,0.033181133416954695,0.8732289752741341,0.008681682892913357,-0.07647793887786142,0.8245577544010629,1.0895193260000013,1.2327394342253464,-0.13428124809802977,-0.10957760015885189,-0.27728000172898754,0.2248564119938508,0.7774075194350424,-0.507403413032686,0.06422711055976103,-0.04999043334681534,1.1040252013234335,0.29685036115813035,-0.7685210509880138,1.1452984032289169,-2.3836529683962313,-3.7515671025901636,3.7691590736058758,-1.1333095218605471,1.9305541496316958,-1.9604718430687806,0.9235869336112721,-4.29846914878106,2.0864343037699706,-0.10659297984103144,1.6556135886283707,-1.333995716726104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.55,0.0,1.0,0.0,1.0,2.215395522877728,-0.020804792012743302,0.5806735631629043,0.9971968839797454,-0.02880398275734348,-0.057427424056158485,0.038350959922483246,0.8649082680375713,-0.0061177671647425075,-0.046625535280977945,0.8221341270911573,1.2018640986303786,1.2245947055281874,-0.15428812487308624,-0.14070181002507823,-0.24675739364576527,0.2155180079055529,0.7930390868097746,-0.52370065411275,0.07148712072178419,-0.08643551684769975,1.1204153552455385,0.2959082690224498,-0.7544137939167511,1.1324880341458146,-2.418052151229057,-3.7163241445895943,3.5602255629099178,-1.1076183709492837,1.8174327853972194,-1.942671336240438,0.8153798792921888,-4.437904380328431,1.8488315701432478,-0.12034614238596753,1.7249444934812486,-1.7322100050722744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.558333333333334,0.0,1.0,0.0,1.0,2.2225306643284926,-0.020322231817567697,0.5811857325717593,0.9973683759090594,-0.025887425064686206,-0.051933336444924254,0.0434636920927667,0.8528361162738667,-0.02032306105177987,-0.01638458487078083,0.8182492314227542,1.3022592646557904,1.2130719750363064,-0.17458211728518072,-0.1715163359020118,-0.21794290901382224,0.20639610581136275,0.8076980658583294,-0.5397812686366933,0.07781677521463085,-0.12395550635228918,1.134839060825821,0.2948445921183642,-0.7397719760966597,1.1164282364777123,-2.4526305327552014,-3.6770578309945248,3.3596524099960283,-1.081564268664208,1.6981999446800389,-1.9101126962457249,0.7017443846186486,-4.555709998925061,1.6139442506342583,-0.13575717999449566,1.7847948162837324,-2.113670757378534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.566666666666666,0.0,1.0,0.0,1.0,2.2295364422801707,-0.019884096831446436,0.5818618287600035,0.9974957130716783,-0.023002226110698982,-0.046045764332439496,0.048507603460225084,0.8372694636825743,-0.03371583788578836,0.01391454305686346,0.8131483522492026,1.3905883159913028,1.198411015977225,-0.19516530041900626,-0.2019861072083203,-0.19076318681249813,0.19749193676114943,0.8213424192211086,-0.5555358657168454,0.08318286046542833,-0.1623640168297841,1.1473144260894428,0.2936456493558749,-0.7246672136453556,1.0972601881895057,-2.487522733901714,-3.633198290163835,3.1679394417391666,-1.0555842064847905,1.5749311295248103,-1.8657981392693634,0.5853854661584579,-4.650625553121556,1.3809940053595637,-0.1527268070273291,1.8369291277289657,-2.477912540370575,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.575,0.0,1.0,0.0,1.0,2.236391680985127,-0.019491349738930006,0.5826954414312338,0.9975717251914465,-0.020152316996151696,-0.03981573433544475,0.053471904151679656,0.8184982808423674,-0.04610284897848237,0.043907665580781324,0.8070867611145247,1.4667242124800233,1.1808996193916033,-0.21604082951687595,-0.2320696407380757,-0.16514391831816946,0.1888030357032829,0.8339469180170762,-0.5708779042911827,0.08757319965060514,-0.20146593223764844,1.1578556275818137,0.2922991453345754,-0.7091564906345103,1.0751296941382027,-2.5228375088300092,-3.583774577485242,2.9848240661674104,-1.030128184569865,1.4495613820108177,-1.8121839678610718,0.4685961063887256,-4.721810408686585,1.1498035645211768,-0.17104857769462134,1.883056295490022,-2.8242880758715927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.583333333333333,0.0,1.0,0.0,1.0,2.2430778502249242,-0.019143914822536662,0.583679140327908,0.9975903021401926,-0.01734023263121154,-0.03329484041568245,0.05834688540983339,0.7968326653742767,-0.05731296531686283,0.07321146431907612,0.8003303764094677,1.5305244325006528,1.1608523948063547,-0.23721259223283975,-0.261715683499741,-0.1410161190430413,0.180323133684985,0.8455017755879556,-0.5857389318478633,0.09099279557190709,-0.2410608569745605,1.1664778188314624,0.2907948397276312,-0.6932829420538552,1.0501887202583124,-2.558632105307746,-3.5274210078148265,2.8092862865541184,-1.0056593695575766,1.3238536461498684,-1.751179320598304,0.3531915562384641,-4.768853116216699,0.9207654193428993,-0.19045871932036773,1.9247470174096981,-3.1519671920111403,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.591666666666667,0.0,1.0,0.0,1.0,2.249578928525978,-0.018840656432334103,0.5848042953175706,0.9975465105564616,-0.014567048767152597,-0.02653527598985445,0.06312400128393773,0.7725870609458136,-0.06719398815342797,0.10143589030967623,0.7931538837839136,1.5818405548418675,1.1386014763607006,-0.2586846979386717,-0.2908599908683228,-0.11832248020893416,0.17204204621065664,0.8560111454529074,-0.6000642263011544,0.09345972558791288,-0.28094681750792677,1.1732017179041954,0.2891248333459026,-0.677077373677682,1.0225969076046837,-2.594898156857898,-3.462400588087653,2.6395356733070714,-0.9826542465968252,1.1993918718822916,-1.6842208232514788,0.24050444738001525,-4.791808892734524,0.6947943805715129,-0.21067665347175746,1.9633438454961127,-3.459934890536378,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6,0.0,1.0,0.0,1.0,2.2558811145443287,-0.018579352579612022,0.5860609423240953,0.9974366886387894,-0.01183233012491533,-0.0195898013791549,0.06779592809967579,0.7460640073724599,-0.07560960849086937,0.12819364655213616,0.7858360936080684,1.6205362352542105,1.1144957192377896,-0.28046089484713804,-0.31942235996786855,-0.09702385782125676,0.16394556290837126,0.8654916401193271,-0.6138092789020546,0.09500120302824068,-0.3209243385201359,1.178057725174321,0.2872835621697686,-0.66056054462892,0.9925231387493728,-2.63155834278479,-3.3866376548024903,2.4729899294265874,-0.9616013943128665,1.0775904741161835,-1.612388111660299,0.1314204762766158,-4.79124155038452,0.4732587902008101,-0.23143392949276587,1.9998721174325174,-3.746979127819836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.608333333333333,0.0,1.0,0.0,1.0,2.2619724032413635,-0.018356677334809914,0.5874376867923118,0.9972585149169404,-0.009134106334077473,-0.012511619559606479,0.07235663059958736,0.717539718621459,-0.08243700722735653,0.15310648389497766,0.7786526234077531,1.6465111351194228,1.0889053191373705,-0.30254400365175155,-0.34730395178169765,-0.0771059813851577,0.1560153563054422,0.8739709866881771,-0.6269373614954927,0.09565006685918981,-0.36080084334766876,1.1810893644075422,0.28526760118768985,-0.6437461717204733,0.9601472554743531,-2.668473571696787,-3.297749085036943,2.306239206279698,-0.9429974310965211,0.9597160125054471,-1.536540370440218,0.026438298000285854,-4.768250895947016,0.25788520757016986,-0.2524910062129737,2.034958854592621,-4.011666975965729,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.616666666666666,0.0,1.0,0.0,1.0,2.2678420615695902,-0.018168204390700327,0.5889216355046103,0.9970110449144473,-0.006468890360111289,-0.005354141663721079,0.0768014521896333,0.687253515842405,-0.08756562672642125,0.17580852719758325,0.7718662451168995,1.6597288874892802,1.0622288548681829,-0.3249354543754178,-0.37438484471848427,-0.05858653771659513,0.14822893905676257,0.8814869069944179,-0.6394182850760582,0.09544184132824544,-0.4003951867859195,1.182355811967157,0.2830753787328857,-0.626644563719043,0.9256620224832773,-2.7054599930549417,-3.193065021379522,2.134990545538481,-0.9273389017653022,0.846917405371983,-1.4574578659675796,-0.07425892468775563,-4.72447052290633,0.05063567032794314,-0.27364259795440105,2.0687649281389953,-4.252310079959694,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.625,0.0,1.0,0.0,1.0,2.2734800537347146,-0.018008442170278787,0.5904983483435371,0.9966947090116155,-0.0038317511306785374,0.0018293669853586833,0.08112723506326694,0.6554029864481121,-0.09089761383630976,0.1959474599334493,0.7657155900404045,1.6602463681164819,1.0348996293127,-0.3476350035360006,-0.400521702138023,-0.04152280562618302,0.14055970794268716,0.8880862767777101,-0.6512283259282857,0.09441241811439388,-0.43954201872944093,1.1819332922463412,0.28070689122178316,-0.6092667562514901,0.8892754208083582,-2.742313552569353,-3.0696366844026115,1.9540006582559006,-0.9151093044681541,0.7402597219950757,-1.3759708476609323,-0.1707296376594783,-4.662024466204731,-0.14643847884328487,-0.2947134959507458,2.1009347443856763,-4.466920436055801,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.633333333333333,0.0,1.0,0.0,1.0,2.2788764808718285,-0.017870907881326063,0.5921518056718285,0.9963112658122156,-0.0012164470618283125,0.008986255095970496,0.0853324630740699,0.6221468709211817,-0.09235032292140935,0.2131852259326078,0.7604035860427723,1.6482395075288636,1.0073877014657302,-0.3706406802515737,-0.42554545612519445,-0.026019860078996787,0.13297711731562667,0.8938245690276692,-0.6623511325370738,0.09259634736725414,-0.47809559455599837,1.1799151706531024,0.2781634871337066,-0.5916289846459484,0.851213348549014,-2.7788363548883024,-2.924243332615352,1.7570382651693333,-0.906761248943147,0.6407537977879185,-1.2930513268752275,-0.2632050381504217,-4.583433612354168,-0.3313575773083599,-0.3155482751583327,2.130568114872504,-4.653156254053057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.641666666666667,1.0,1.0,0.0,1.0,2.2840211175541167,-0.017748243033840535,0.5938643971139602,0.9958637085974463,0.0013843822903510208,0.016065037781892933,0.08941740391471106,0.5876181271672437,-0.09186102616123146,0.2272010728145839,0.75608822890799,1.6240173009276042,0.9801929984482838,-0.39394894278413894,-0.44925909101494554,-0.012238834540027466,0.12544702046030137,0.8987655067408421,-0.6727791813762062,0.09002566747855352,-0.5159325789353437,1.1764106659578686,0.2754477533024776,-0.5737572876702817,0.8117228165741406,-2.814852699393038,-2.753436372284307,1.5369771436768687,-0.9026951213822054,0.5493691739925488,-1.209829987415303,-0.3520323735073369,-4.491463426363156,-0.5023760908474761,-0.3360004903633995,2.1562211149693034,-4.808254826961729,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6499999999999995,1.0,1.0,0.0,1.0,2.288903150896766,-0.01763236461927446,0.595616957029528,0.9953561290863915,0.0039789865507234646,0.023015960989851626,0.0933842046588119,0.5519500171424793,-0.08939353094405207,0.23770112104834332,0.7528799512573596,1.5880109368528943,0.9538237156623294,-0.41755489190812434,-0.4714360623299329,-0.0004035743510489747,0.11793219862592325,0.902980721927545,-0.6825149656606622,0.08672914114213186,-0.5529533183287176,1.1715422358056444,0.27256347896098326,-0.5556919660631267,0.7710757680996518,-2.850193093939194,-2.553694352214937,1.2862021797912513,-0.9032376262074108,0.4670118968667669,-1.1274836699256063,-0.4376385231299909,-4.388905029835318,-0.658127305117282,-0.35592966965180217,2.175945258845038,-4.928944568333886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.658333333333333,1.0,1.0,0.0,1.0,2.2935112545027585,-0.01751463316196998,0.5973889012316226,0.9947935536214332,0.006576283552510333,0.029791444892417942,0.09723686626138552,0.5153170933672763,-0.0849457217810119,0.24443914466149613,0.7508507394325534,1.5407224746950818,0.9287546649355192,-0.44145216101645884,-0.49182066355186116,0.009197868456493388,0.1103930600235112,0.9065490383552882,-0.6915705758749663,0.08273169209305367,-0.5890809960992657,1.1654418775392472,0.26951559214161425,-0.5374915333561977,0.7295737404352425,-2.8846160001448617,-2.3217863487660364,0.9975580973087285,-0.9086252799162708,0.39444659689046535,-1.0469351203869026,-0.5205213380473167,-4.27828906183166,-0.7977235057234111,-0.3752155287083425,2.187372183298233,-5.011322970565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.666666666666667,1.0,1.0,0.0,1.0,2.297834139502902,-0.017386003407085168,0.599158546166756,0.9941817806436326,0.009185721057796291,0.036346213826884056,0.100981000568539,0.3475945802055622,-0.04029514280142378,0.2610225390945401,0.7775651740992359,1.4246788284437708,0.9678006527664813,-0.46563182524387203,-0.5101325014760335,0.016222393937429833,0.10278844396065207,0.9095548318757194,-0.6999638843337772,0.07805378550800991,-0.624258136025912,1.1582468440435876,0.2663098868158442,-0.5192357630081561,0.6875537185902352,-2.8919597373300565,-1.2860730692261013,-0.1155701879131482,-1.055793212482645,0.23031009983396578,-1.0997597895834743,-0.6595262122605577,-4.4837836307210726,-0.7908562284697185,-0.4482184691822222,1.965372977262585,-4.958406203854526,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.675,1.0,1.0,0.0,1.0,2.2996279092212544,-0.01705285662166361,0.6013019253381772,0.993490431430254,0.012117909243596563,0.04217504615223281,0.10512461442756338,0.18598595495533538,0.0008607357053144818,0.2580458219062524,0.7812938962980402,1.331773855497953,0.9967757770269028,-0.4896514899719598,-0.5132552147056295,0.007271698657940918,0.09279650648213378,0.9103875400191876,-0.7098999057013575,0.07173958855537771,-0.6638107232779502,1.1522609403980852,0.26204528432191054,-0.504735317068488,0.646933637037667,-2.8587041816033665,-0.2597682006399049,-1.3213241034977519,-1.1798558145124771,0.21806778789857706,-1.500819720619797,-0.7715197191641108,-4.685614591549896,-0.7951271180913855,-0.4907962017031142,1.7087060355886052,-4.856079000393725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.683333333333334,1.0,0.0,0.0,1.0,2.301222749818215,-0.016786747708445827,0.6031913535831859,0.9927630826261011,0.014836932607465703,0.047955429686784824,0.10909447326755166,0.17399523596023198,-0.003956284285286216,0.23371697027195884,0.7428830471641255,1.3072908304380146,0.9554736402963265,-0.5132768949372615,-0.5144619714866986,-0.005799674454199363,0.08312418038544411,0.9131892950073623,-0.7249775463441072,0.0651951235219414,-0.7023517125517436,1.1449947254087312,0.2581299501207923,-0.49075732908167935,0.6066190685836731,-2.8011452034730735,-0.08344441945670633,-1.627102083509049,-1.153676730470765,0.4286632889406583,-2.0021386554243747,-0.8056341332367972,-4.505189969602619,-0.9658724972324828,-0.457670304815716,1.684208842446221,-4.80960071900459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.691666666666666,1.0,0.0,0.0,1.0,2.302843159622281,-0.016558911779464246,0.6049082113848268,0.992009477951441,0.017456915865791317,0.05354757804311176,0.1128942369510033,0.17899238313499582,-0.009612602505764796,0.21683050193379919,0.7183071246083015,1.2511963228167116,0.9170447322921005,-0.5363372433631777,-0.514645955029908,-0.019846669400543235,0.0735685609742877,0.9175319281681986,-0.7432688832917638,0.05831235300143109,-0.7388972227713272,1.1361630654442105,0.2544174459083153,-0.47666516969438427,0.5667736250542572,-2.722727327770178,0.026991689095399174,-1.6757919277450712,-1.1444421197543326,0.5968079775670865,-2.323915742988343,-0.8446791006715808,-4.251593530820304,-1.13851396301746,-0.4331555591722258,1.7017382824682392,-4.723373325693618,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7,1.0,0.0,0.0,1.0,2.3045465675067565,-0.016350479633213393,0.6064696070146679,0.9912399271026119,0.020007376715159612,0.058841291979378076,0.11653675059925749,0.18933934388555665,-0.014776370110925752,0.201232234892874,0.6962753114741131,1.1717622730268729,0.8818258475582565,-0.5586556837334311,-0.5140121100017753,-0.033729539916617216,0.06405014505620524,0.9231360946334805,-0.7637094753939129,0.05111713851074839,-0.773211604732082,1.1260194926917735,0.2509106908012552,-0.46239502437387536,0.5278961798221128,-2.6243251456671346,0.12465529725631086,-1.628671374746764,-1.1426097273008966,0.7390521714721543,-2.5429271795470654,-0.8800228676257698,-3.9817231976113443,-1.2756534371364525,-0.40716273839766615,1.7153946147400023,-4.570332471373195,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.708333333333333,1.0,0.0,0.0,1.0,2.306354442316448,-0.01614884405078533,0.6078696298932346,0.9904650850419107,0.022503472757899816,0.0637561264572119,0.12003193505987526,0.2026078382875421,-0.019499702901849533,0.18495887313471834,0.6750874982126258,1.0744117567577534,0.8492437603258257,-0.5800759957909633,-0.5125683667423028,-0.0469911923129893,0.054525065519272754,0.9298494643594012,-0.7856510029508815,0.04364530520766826,-0.8052592760648496,1.1149021748252697,0.24763140026835417,-0.44807525944871757,0.4906014171980373,-2.5075429956588002,0.22660732993641686,-1.5433160158589305,-1.1453059760446895,0.8660111556313899,-2.6933204548322265,-0.911166637456446,-3.71136455498126,-1.3718787061751447,-0.3784086841218909,1.708683363145882,-4.338965162601863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.716666666666667,1.0,0.0,0.0,1.0,2.308280932804823,-0.01594340957789979,0.6090963749138626,0.9896957579435213,0.024956897570644277,0.06822566400071264,0.1233884872879645,0.21841904079583718,-0.023920169802163833,0.16751054640857194,0.6543470378875407,0.9616684600048868,0.8191161493787609,-0.6004480669944111,-0.5102353211695017,-0.05945147351426606,0.04496171212212708,0.9375696138940036,-0.8085981496411166,0.03593102788647429,-0.8350676806484363,1.1031548475888544,0.2446038793992237,-0.433916968321444,0.4555800937787484,-2.3727886474350757,0.3406240483404255,-1.443783166559677,-1.151389052768778,0.9821979899054023,-2.7883548071285835,-0.9382915806399126,-3.4458274523730803,-1.4270369767554403,-0.346640875638618,1.6733219459393434,-4.01992623623657,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.725,1.0,0.0,0.0,1.0,2.3103402552085837,-0.01572430182200557,0.6101364098664543,0.9889427214215469,0.027378234078814203,0.07219026596900595,0.1266147368288031,0.23686830400062486,-0.028178918274214426,0.14875676874076382,0.6339000291074139,0.8348210682216711,0.7914096797892705,-0.6196224732482145,-0.5068912992699623,-0.07105424508898392,0.035335247973126455,0.9462194308578246,-0.8321235830696913,0.02800711219700305,-0.8626897336044009,1.091118225212679,0.24185405234104387,-0.4201865603497285,0.42360264659409447,-2.220219226240563,0.4703340087488339,-1.340989788351893,-1.160152297680521,1.090230935852441,-2.8347763353700106,-0.9615303017115221,-3.1875792099675704,-1.4413294532073229,-0.3116464275823816,1.6031675895489383,-3.6035846304955577,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.733333333333333,1.0,0.0,0.0,1.0,2.3125479613838675,-0.015481976671317428,0.6109757652940019,0.9882164945485672,0.02977764408852845,0.0755942372521093,0.129718784815482,0.25808654295272304,-0.032395226926419954,0.12860685468390018,0.6136688885981665,0.6945986556831841,0.7660926350053775,-0.6374517207650872,-0.5023964210236878,-0.08180130332013094,0.025625840494118396,0.9557401294915443,-0.8558444218972835,0.01990552285794892,-0.8881940008145625,1.079132690035399,0.23940977227285068,-0.40719750849562836,0.3955203499371558,-2.0502445253154966,0.6170648717212268,-1.2397732957502505,-1.1710458547327955,1.1921851940214467,-2.837487392441853,-0.9809832132485682,-2.938395679537378,-1.4143756846995537,-0.27317042478399667,1.4930527837167895,-3.0807041178843355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.741666666666666,1.0,0.0,0.0,1.0,2.3149205754314552,-0.015207035355027173,0.6115997588471721,0.9875271462392342,0.032165220454683056,0.07838404044395848,0.13270823732283943,0.2822213338495286,-0.03657074449631378,0.10673674159099608,0.5935493358757314,0.5404187406462084,0.74268997093549,-0.6537932153368061,-0.49660688474127523,-0.0917171333514881,0.015817817060913196,0.9660891840915153,-0.8794150396103888,0.01165739197619358,-0.9116629949300239,1.067545297134353,0.23730121192797726,-0.395302347287782,0.3722575779626889,-1.862521808564126,0.781632309634972,-1.141352303802895,-1.183542487386333,1.2901861436904793,-2.7996496488941247,-0.9970663196808642,-2.7005090567776535,-1.3420838368111454,-0.23100499400219132,1.3377010717358206,-2.4392219143706706,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.75,1.0,0.0,0.0,1.0,2.3174754470147687,-0.014888178870009273,0.6119897336997955,0.9868851862161881,0.03455145275266492,0.08049930125414978,0.13558646262301927,0.30728192721050823,-0.03999256739878383,0.08743655443156934,0.5766939757061552,0.3947128659545029,0.718248687250636,-0.6684937509078226,-0.4893692158631049,-0.10082384171684586,0.005900132371012847,0.9772432318863856,-0.9025052493788522,0.0032877508632678477,-0.93320248509419,1.0567646260885466,0.23555968903948082,-0.3849024906333647,0.3548666513643113,-1.6758644419150048,0.9446039337360634,-1.0623921135945087,-1.2009272762795469,1.3760520826936062,-2.75274976150222,-1.018793415868944,-2.4702993507929483,-1.2855472204851504,-0.19517712962754397,1.1746488868894378,-1.7960656188233304,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.758333333333333,1.0,0.0,0.0,1.0,2.320207133700994,-0.01451599885283108,0.6122089276943324,0.986286220410413,0.03694516068694841,0.08207539476620647,0.13834079698284948,0.3292663863987184,-0.042076352992176554,0.07720566861800769,0.566079021636949,0.29248799264567993,0.6901157748845137,-0.6817242893687229,-0.4808634858456742,-0.10942366857806324,-0.004197637543745918,0.9890233854697421,-0.9252942023020925,-0.005322498288288818,-0.952834650776573,1.0461195101262672,0.2340482597675182,-0.3757248658396247,0.34232315098230004,-1.5206481334913757,1.0741061365902416,-1.0261611182587074,-1.226419568170621,1.435561774257088,-2.7442587649591244,-1.0542198809227386,-2.237061398871787,-1.3409283946114003,-0.17792872154422268,1.071326993017122,-1.3533996575757246,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.766666666666667,1.0,0.0,0.0,1.0,2.3230878277771887,-0.01409442512823914,0.6123562419193881,0.985716117893377,0.03933957052483026,0.08334379159665847,0.1409607942726463,0.3472588022518374,-0.04378582158842642,0.07427449321584446,0.5577570815316572,0.22799586923640933,0.6605016599057537,-0.6938378864660122,-0.4714674469199342,-0.11792652702115765,-0.01454019376516417,1.001169261457337,-0.9482428954615043,-0.014282580485444464,-0.9704868417420531,1.03441581951169,0.2325942103470771,-0.367047040749746,0.33230999040471587,-1.3943390368294373,1.1710741433482719,-1.023432441740687,-1.2551559705010777,1.470933733531199,-2.770308718471002,-1.0929692146733256,-1.997307599494429,-1.4904511964433231,-0.17163600592315642,1.029794134343971,-1.1069676499047088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7749999999999995,1.0,0.0,0.0,1.0,2.3260995136334603,-0.013635114889638816,0.6124653031164966,0.9851698120147195,0.0417181125342744,0.08438718655386554,0.14345327925574514,0.36318937188701966,-0.04601015004579341,0.07382165026967002,0.5481671667704233,0.17742266699211898,0.6320350807020247,-0.7049632733158802,-0.4613455834565363,-0.12648087594040802,-0.025116903718763878,1.013538947695262,-0.9714660142766092,-0.02353865186617758,-0.9861231107681468,1.0212786568522119,0.23118765966879892,-0.3585616302672252,0.3238736901505549,-1.2791372165724035,1.2537153004054025,-1.032256919819656,-1.2828790594560167,1.491759888781301,-2.801056030639959,-1.1251879594804877,-1.7558895463803026,-1.6676369721924678,-0.16524723679181952,1.0144921258781503,-0.9406157696905204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.783333333333333,1.0,0.0,0.0,1.0,2.3292362870916983,-0.013144821527379572,0.6125491823391349,0.9846457843039463,0.04407262742090675,0.08523623361693095,0.14582546912260844,0.3784728955652451,-0.0486567558844701,0.07433257828595673,0.5377252137620023,0.13184734917708732,0.6048684632427751,-0.7151568400755522,-0.4505721919131775,-0.13513080901815192,-0.035921511422764445,1.0260319262703588,-0.994927162638837,-0.03303571314345259,-0.9997516675150582,1.0066218699751488,0.22984008973388012,-0.3501388386517768,0.31663306090987386,-1.1689430205466556,1.3298623321470393,-1.043954614271283,-1.3102405684179306,1.5016047094306106,-2.823861276313191,-1.1513678837245387,-1.516609552173216,-1.8480197616521377,-0.15747972121218534,1.0103753966623508,-0.8056463379523637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.791666666666667,1.0,0.0,0.0,1.0,2.332498128700744,-0.012626303062651317,0.612613093200209,0.9841441285478765,0.046400127828176575,0.085900591069726,0.1480825811393373,0.3937906269309013,-0.05157037687217377,0.07521781609444227,0.5268574498327072,0.0875805047935167,0.578733473469752,-0.7244456569916577,-0.43918121125408566,-0.14388011951159607,-0.04695424652572939,1.038565692852439,-1.018530368881829,-0.04272811659491989,-1.0113999366377004,0.9904783274913429,0.22856299764859583,-0.3417220403228527,0.31044625118468216,-1.0612351599287528,1.4029790055259694,-1.0550792516563678,-1.3377702955651707,1.5020824566682878,-2.8339293120965836,-1.1724322023177491,-1.2813113179571856,-2.0213818101876035,-0.14844844556932246,1.0112504449064752,-0.6816731743769733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8,1.0,0.0,0.0,1.0,2.335887621077817,-0.012080247790657264,0.6126590582267656,0.9836656513392003,0.04870005261810706,0.08638110968707458,0.1502281436350381,0.40943915802711406,-0.054663592860537555,0.0762245574667346,0.5157740721210061,0.04305297991861426,0.5533792536751252,-0.7328440927410315,-0.42718920848774466,-0.1527154632124247,-0.05821768301551729,1.051066633881497,-1.0421593178404467,-0.05257624984874841,-1.021106856147678,0.9729321731386887,0.2273659489743914,-0.3332846645700022,0.3052718413369243,-0.9549364789216641,1.4744844321522832,-1.0640074550629148,-1.365591235293275,1.494023808891387,-2.829809104485239,-1.1889244533503447,-1.051203855052969,-2.1832709318431265,-0.13834141207967887,1.0146164502624944,-0.5602193196806216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.808333333333334,1.0,0.0,0.0,1.0,2.33940834325614,-0.011506431044133765,0.6126877645715165,0.9832114407299821,0.05097285093327374,0.08667485079398052,0.15226457738234786,0.42552761741222705,-0.05789488162804228,0.07723151478948989,0.5045521092031745,-0.0024153845557512155,0.5286323797645346,-0.7403612649736855,-0.41460647071821427,-0.16161357709597798,-0.06971410044728397,1.0634660896672954,-1.065693853956583,-0.06254352415075896,-1.0289200008885833,0.9540904786272908,0.22625730744726785,-0.3248117661518111,0.3011092625233385,-0.8496299295804777,1.5448040290677612,-1.06964920995779,-1.3935903727454926,1.4779085341655707,-2.8114416059388603,-1.2011133926095872,-0.8272413358148212,-2.331661307211481,-0.1272621246047828,1.019569301517762,-0.43795870331902687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.816666666666666,1.0,0.0,0.0,1.0,2.3430640878146862,-0.010904284256266682,0.6126993459466166,0.9827826567057175,0.05321932923495335,0.08677720338347457,0.15419361091580708,0.44207451371929835,-0.06124347568245865,0.07817096581152684,0.4932037621003921,-0.04912503567178246,0.5043798265999377,-0.7470045915673728,-0.40144247466994865,-0.17054295004505454,-0.08144418922794217,1.0756984427842564,-1.0890166779394277,-0.07259480639224153,-1.0348942117445916,0.9340711513518307,0.2252449135643117,-0.3162918428780395,0.29797252961494053,-0.7452162670277107,1.613871354790537,-1.0710163093847498,-1.421539520117696,1.454038422790016,-2.779319524042725,-1.2091355261574066,-0.6102466970327214,-2.465559964169548,-0.11525072499354916,1.0259230687146748,-0.313857037346863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.825,1.0,0.0,0.0,1.0,2.346858468658347,-0.010273155800470777,0.6126937293493475,0.9823804268618832,0.05544036369629686,0.08668279124928063,0.1560165269872378,0.45905345307399775,-0.06469574952722934,0.07899743651976367,0.4817125298077723,-0.09721190524486975,0.48054641169155105,-0.752781536090814,-0.38770861480503865,-0.17946384891905715,-0.0934064257825789,1.0877000633804623,-1.1120158460239618,-0.08269578292004907,-1.039090779172462,0.9129978125577983,0.2243364620307087,-0.3077130483398999,0.29587831190089076,-0.6417542616128102,1.6813736998039164,-1.0671044873169095,-1.4491524503388482,1.4226125276201484,-2.7341289697944093,-1.2130799204778462,-0.4009599769790517,-2.5844038312935003,-0.10231396571359963,1.0338292441027908,-0.18793269183740247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.833333333333333,1.0,0.0,0.0,1.0,2.3507947132367155,-0.009612426869900976,0.6126707975375075,0.9820057913125741,0.05763677724763746,0.086385868257272,0.1577343003361502,0.47828818775145776,-0.0688153521809273,0.08062091339793824,0.467821457281958,-0.15960057387956023,0.4583573534780722,-0.7577004959275863,-0.3734195796732167,-0.1883280248336697,-0.10559673006692297,1.0994086515779256,-1.1345854941026678,-0.0928128050668723,-1.0415768780275758,0.8909977541636057,0.22353968080241837,-0.29906135547632634,0.29484031808431715,-0.5233851701520154,1.7481202178014876,-1.0233159935973142,-1.4719940083206702,1.3801117604511282,-2.646031398335653,-1.2093827087174611,-0.19994400757442854,-2.6636844867131426,-0.08323269743395256,1.0421685699946681,-0.027111634058371026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.841666666666667,1.0,0.0,0.0,1.0,2.3549105927654135,-0.008921995401594164,0.6126398222720592,0.9816682821689728,0.059809061943661486,0.08577168675911621,0.15935331073860642,0.5021896432170733,-0.07402119018694378,0.08371700573738054,0.4499326927082979,-0.25212821230385196,0.43906843597364076,-0.7615046222600143,-0.3585732778416805,-0.19651911547901238,-0.11793965925459007,1.1107019260546478,-1.156116369329556,-0.10285216139867343,-1.0424231792987024,0.8686030711125793,0.2229492504068095,-0.2903435721733221,0.29542645133325124,-0.37278226670122816,1.8147961805723645,-0.897258606315523,-1.4859173333118598,1.3242494366228774,-2.4814487472083524,-1.1955743841957702,-0.010255672123791193,-2.669105989780325,-0.05287779352500632,1.0471338149060405,0.21455033966503612,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.85,1.0,0.0,0.0,1.0,2.3592511916176706,-0.00819583986470861,0.6126070529564979,0.9813786061801656,0.06196692210216519,0.08470214362519984,0.1608778380087747,0.529485409732476,-0.0794248585049752,0.08677993068716677,0.4312863439204797,-0.3652358079066358,0.4212384352311837,-0.7639135337059401,-0.3431729766636773,-0.20328233493892842,-0.13036201895545396,1.1214794755216402,-1.175942973222807,-0.11273904480346847,-1.0417478058963057,0.8465126543339336,0.22265838424366827,-0.28160912522789233,0.2984161570787344,-0.20577914366118666,1.8791081600813775,-0.7125814920991286,-1.4953597869725133,1.2611572359489553,-2.2693117926537854,-1.177353820831891,0.16277530962497622,-2.610564745603141,-0.016909095906508798,1.0470583386640575,0.5184949107275494,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.858333333333333,1.0,0.0,0.0,1.0,2.363825310609956,-0.007424370198627758,0.6125660511333367,0.9811382679235103,0.06412400420349594,0.08314559570201814,0.1623041010460104,0.5574092064984767,-0.08429156098514515,0.08841525058450507,0.41425312269334225,-0.48178952418234466,0.40315880181741387,-0.7649342746543674,-0.3272548085069909,-0.20839547368066452,-0.14286232237079863,1.1317212133204637,-1.1939382325404524,-0.12247472507920494,-1.0397102574716195,0.8250936586858603,0.222667432141701,-0.27289259986225445,0.3040680331787104,-0.04477033848905965,1.9373535767063632,-0.5112076933584669,-1.5044265114106787,1.1957497618355717,-2.05196306540258,-1.1590907703378683,0.3169255603514465,-2.517719827309781,0.018654349165754813,1.0472531548994746,0.8337051879695268,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.866666666666666,1.0,0.0,0.0,1.0,2.368626984519214,-0.006602936219699517,0.6125111031999727,0.9809451638442493,0.0662857057789592,0.08110799777856453,0.16362849212889896,0.5846347294076697,-0.08872182738812216,0.08855851816714837,0.3983078607787452,-0.5951419060088035,0.38452460652774867,-0.7646597060140911,-0.3108837503852379,-0.21180246316156953,-0.15543579414563194,1.1414086382188997,-1.2101423576461834,-0.1320572243090996,-1.0364657132237816,0.804550657212104,0.2229692900630975,-0.26415490597956776,0.3123112435448932,0.10328088915910749,1.9864285612970045,-0.30590390799449696,-1.5124107722770463,1.127525834198213,-1.8427195027147913,-1.1401096306869305,0.45336523321610755,-2.4056164864705476,0.053501646834835936,1.0555163769119902,1.129131298319409,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.875,1.0,0.0,0.0,1.0,2.3736449247591906,-0.005730883256827295,0.6124389593010715,0.9807953753314967,0.06845217592088326,0.07861147535515171,0.16484831598363128,0.6106015811654149,-0.09289388260108547,0.08739648082753547,0.38297132815112767,-0.7022633154497,0.3652934987952753,-0.7632129265017156,-0.2941476658187075,-0.21349387214723947,-0.16806916857541607,1.1505133105571006,-1.2246502242523656,-0.14147655225732045,-1.032154170251351,0.7850000505780178,0.22355912625561494,-0.2553006602470546,0.32288688815070055,0.235941486681297,2.0241915508996824,-0.10035650726712975,-1.518415738474932,1.055358133121569,-1.645860893495943,-1.1196297270148636,0.5739412615490602,-2.2826588694925065,0.08789710481217516,1.0772110749679553,1.3874154945440276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.883333333333333,1.0,0.0,0.0,1.0,2.378866264595473,-0.004810036424584624,0.6123484318817175,0.9806839994502676,0.07062059215806485,0.0756860891412252,0.16596156511719004,0.6350964273372531,-0.09694824968414406,0.08512531582227977,0.36794728706235014,-0.8015950218537862,0.3454555432112159,-0.7607273479027361,-0.2771472245369099,-0.2134750716160217,-0.18074272312021414,1.1589979404375925,-1.2375733725377824,-0.15071771975934734,-1.0269000255312972,0.7665063427205622,0.2244342418099671,-0.24620138806343517,0.335434835120627,0.35252101313808737,2.0496071946434893,0.10397466711742187,-1.5217667258761998,0.9783733341876433,-1.462592828601088,-1.097201330075019,0.6803982757931104,-2.1539461787731806,0.12203644788156942,1.115141819787336,1.5996847249777046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.891666666666667,1.0,0.0,0.0,1.0,2.38427806735602,-0.0038437607102153573,0.6122397080905436,0.980605633024515,0.07278635396878094,0.07236629018188569,0.16696664098575761,0.6584083894207405,-0.10057731306367552,0.0814573629174236,0.35278559393045933,-0.8952889559998156,0.32287693936455636,-0.7573375762827474,-0.2599875459079827,-0.21176096102861577,-0.1934319473400194,1.1668195327935613,-1.249026771395717,-0.1597632410919041,-1.0208141989881325,0.7491009475984648,0.2255930670536411,-0.23671496325059901,0.3495483002336623,0.4569171941729344,2.0650546746373566,0.30594515559631774,-1.5213255943461235,0.8965494997366941,-1.2905291380671935,-1.0739060793632023,0.7710574852716912,-2.0118675813276643,0.1547480241273841,1.165863536781538,1.7773655314018244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8999999999999995,1.0,0.0,0.0,1.0,2.3898699030573956,-0.0028271533332698178,0.612106954933255,0.9805595632360928,0.07494458024316766,0.06866527387183118,0.1678431797923667,0.6807362134169364,-0.10365435846575631,0.07624041181267224,0.33752475653457137,-0.9842767903242609,0.2963727228258815,-0.7531120613331872,-0.24272964662628727,-0.2083759856894164,-0.20609814969264953,1.1739404320998708,-1.259082191505569,-0.1686161544154007,-1.0140490674434357,0.7329752163651011,0.2270133755454235,-0.2267703291170762,0.36505759397732407,0.5511061103271842,2.072035329113473,0.5044201598362408,-1.5165136561245691,0.8100366952830029,-1.1286288416464707,-1.0505677091779553,0.8453222126575222,-1.8529252401255114,0.1850652191230251,1.2269939204015452,1.927366073350174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.908333333333333,1.0,0.0,0.0,1.0,2.3956313876071524,-0.0017607641648283456,0.611948017862345,0.9805423595723084,0.07709139662134841,0.06461067504640254,0.16857953114689755,0.7015553298676873,-0.10690682998413005,0.07025860883502824,0.32264060623979857,-1.063261064697759,0.26922830057209685,-0.748152474443961,-0.22545362375609146,-0.20335395836467843,-0.21870717494209554,1.1803201443816114,-1.267837252089825,-0.17727270291153668,-1.0067254954438405,0.7182188602630396,0.22867748737235818,-0.21626506457723993,0.38167106812283186,0.6295651302872707,2.067095055113979,0.6976297008083948,-1.508012228869251,0.7181271488031005,-0.9809801451174138,-1.0252688242001073,0.9090741766291055,-1.696277430782993,0.21473129970021598,1.3043064104006004,2.0267559100266896,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.916666666666667,1.0,0.0,0.0,1.0,2.4015503964426617,-0.0006559700740153629,0.6117684293754618,0.980545492463048,0.07922024240663691,0.060257691709044894,0.16918540419804956,0.7205863121961191,-0.110670869459258,0.06396720325291709,0.3077946649063002,-1.1296720170606365,0.24300732482072818,-0.7426193091617327,-0.20827806237438762,-0.19674882400927649,-0.23123168684047038,1.1859092179132558,-1.2754318605908592,-0.18570396815206916,-0.998897831166284,0.7047039258520512,0.2305922305404271,-0.20503188894373287,0.39883685914443556,0.6910426092677047,2.0495339508409076,0.8829177948018824,-1.4956289205544788,0.6203813313438866,-0.8488185782523017,-0.9967714026558561,0.9657519939335701,-1.552225969832941,0.24493425825630077,1.399080519792486,2.066522585921915,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.925,1.0,0.0,0.0,1.0,2.4076153566912657,0.00047893222261605434,0.6115715724766125,0.9805628750901737,0.08132178451081126,0.05565364300272175,0.16966404268349647,0.7379824147392301,-0.11475437509424537,0.057218539327648046,0.29258247472811005,-1.1848636998157462,0.21662518899063127,-0.7366350976228326,-0.19129472457540966,-0.18863866178464705,-0.24363432361800352,1.1906598332373428,-1.28198422839403,-0.19388555962246762,-0.990629628878281,0.6923484274324906,0.2327597250099632,-0.19294705591403183,0.41611311122153044,0.7389584787485282,2.0221691534052817,1.057427487684235,-1.4786841351202968,0.517173386101839,-0.7302756593584991,-0.9657246773234346,1.0146770127528604,-1.4170188215750223,0.275037042839264,1.5063519041827578,2.0581835512924385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.933333333333334,1.0,0.0,0.0,1.0,2.4138152577846714,0.0016366300294548227,0.6113593816985886,0.9805896549672005,0.08338733275709052,0.05084285849745928,0.17001613172593633,0.753787675949033,-0.11909290277255874,0.04994696949216209,0.2770414313676941,-1.2294679134578275,0.1896411430709194,-0.7303033345159239,-0.17457524315096626,-0.17912503254787257,-0.25587642242580866,1.1945287743482864,-1.2876031215801675,-0.20179937944079307,-0.9819865476204029,0.6810869454924675,0.23517618125441483,-0.17992602387402024,0.43313991833264287,0.7753288528389812,1.9872093695792932,1.218399438887785,-1.4570550487190725,0.40901936835761266,-0.624436677034077,-0.9327508779595572,1.0557211107949738,-1.289383727324993,0.30445045775998936,1.621792242167895,2.010337908548141,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.941666666666666,1.0,0.0,0.0,1.0,2.4201388484057573,0.0028101337515155462,0.6111327493610627,0.9806219531839999,0.08540849532883264,0.0458679340914763,0.17024131837388076,0.7679762461597393,-0.12363720436857242,0.042126711461682495,0.26119396924556043,-1.2638651540490062,0.16187656234510983,-0.7237129500755163,-0.15817456841575478,-0.16833200446985064,-0.26791857442998807,1.1974768227099697,-1.2923915063445979,-0.20943140758846024,-0.9730342770316981,0.6708586986437407,0.23783389930596302,-0.16591718521123358,0.4496187430306661,0.8017189938761948,1.9466923888020315,1.3629963457015826,-1.430727360410874,0.2963273609042716,-0.5305827904052096,-0.8983153050002851,1.0889540759857552,-1.1690673566077425,0.33271598006564207,1.7417544672661618,1.9295894110763068,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.95,1.0,0.0,0.0,1.0,2.426574528393095,0.003992749272487362,0.6108917312054852,0.9806567287467488,0.087377251559801,0.0407703475480521,0.17033900033339436,0.7804760641538309,-0.12832999177230509,0.0337642212021991,0.24505579938583483,-1.288351298970511,0.13327392837998095,-0.716941351284654,-0.14213037000426573,-0.15640842678617953,-0.27972187843265656,1.199467563696691,-1.296446168086921,-0.21677130119079782,-0.9638373130206404,0.6616024895490051,0.2407214475888422,-0.15089678275291754,0.4652997418505813,0.8194703118467572,1.902606455123027,1.4883396899840307,-1.3997723818030017,0.17936588541092924,-0.4479851588213579,-0.8628224722373062,1.1145598089906406,-1.0563224233648572,0.35939208743274165,1.8630426173164472,1.821369038040419,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.958333333333333,1.0,0.0,0.0,1.0,2.4331097482635253,0.005177931286984447,0.6106358293201164,0.9806917727166142,0.08928581198437835,0.035590440722506424,0.17030857651203685,0.7911671804224544,-0.13309578999323723,0.024894088212929155,0.22864118605040723,-1.3032209905864383,0.10383598140106039,-0.710055111544737,-0.126464460830371,-0.1435263429701168,-0.29124811412670476,1.2004662541334852,-1.2998579256582872,-0.22381178212574868,-0.9544582802151874,0.6532533249209931,0.24382376742984205,-0.13486647492262613,0.4799748936646731,0.8297909956205918,1.8568591646301225,1.5916578943380721,-1.3643365799340001,0.05824010561474413,-0.37583330736768783,-0.8266547149453041,1.1327921372057048,-0.9516883544453791,0.3840075989508063,1.9827451772780138,1.6904182921543975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.966666666666667,1.0,0.0,0.0,1.0,2.439730788273552,0.006359406879907572,0.6103641475793843,0.9807256565059755,0.09112680463968732,0.03036739183495999,0.17014968016523196,0.7999062701822032,-0.13783467640831698,0.01557298577289444,0.21199591345335994,-1.3087917662480832,0.07361667792188976,-0.7031115013576441,-0.11118271726043036,-0.12988079521387833,-0.30246082143155656,1.2004382321236033,-1.3027100565430492,-0.23054887977321956,-0.9449574440672119,0.6457410169749155,0.2471215742380223,-0.11785102979828398,0.4934733800531546,0.8337280005962677,1.8113268712164794,1.670281121097913,-1.3246823450336898,-0.06713268613386614,-0.3131277076385297,-0.7902180166100065,1.1439562435928696,-0.8558382613251458,0.4060225507358156,2.0981938058246876,1.5410216839505886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.975,1.0,0.0,0.0,1.0,2.446422474461709,0.0075312795401599585,0.6100755663856752,0.9807576831427228,0.0928934220279796,0.025139047014527963,0.16986231899902174,0.8065126652682801,-0.14242285852793024,0.005885070427164296,0.1951733116769972,-1.3054417563727962,0.04270139511985327,-0.6961596448681325,-0.09627567964342967,-0.11568832428515158,-0.3133261532105996,1.199347376031254,-1.305076720785596,-0.23698208240258212,-0.9353923428219729,0.6389893538989073,0.25059080994210564,-0.09989657815888134,0.5056585883971829,0.8322283418378262,1.7677067807956615,1.721911843742915,-1.281142484904454,-0.19702825855942407,-0.25867742864749577,-0.7539175968897749,1.1484038117399598,-0.769540545908276,0.42484594122800534,2.206895708033689,1.377188090552951,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.983333333333333,1.0,0.0,0.0,1.0,2.4531677312690325,0.008688049729354112,0.6097689978734976,0.9807878484436929,0.09457944613767265,0.01994156051228914,0.16944692053226454,0.8107789670956792,-0.14671111040611262,-0.00406014114523548,0.17825133850335134,-1.2936011810406916,0.011209642549490292,-0.6892410289936803,-0.08172093758050267,-0.10118226448482974,-0.3238131961799641,1.1971544278142796,-1.3070213470205074,-0.2431141730547158,-0.9258173805382126,0.6329153412097775,0.25420233992515573,-0.08106943466438916,0.5164265148957038,0.8261049200088699,1.7274599011092717,1.7447204497762072,-1.2341398853893426,-0.3319393591000219,-0.2110549812951268,-0.7181746808495693,1.146536100932667,-0.6936377086948542,0.4398243292496318,2.306520726249964,1.2027210974591918,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.991666666666666,1.0,0.0,0.0,1.0,2.459947431816998,0.009824808475490472,0.6094435324192495,0.9808167299292765,0.09617951054984118,0.014809314526487642,0.16890449444737207,0.8124822004787003,-0.15052829748474472,-0.014133633938932147,0.16133915253052628,-1.2737579823515683,-0.020721725577369177,-0.6823912295346514,-0.06748468129160848,-0.08660965012221479,-0.33389515130042197,1.193815053379587,-1.3085943038071814,-0.2489516604167416,-0.9162834078064285,0.6274287254206597,0.2579212154295995,-0.06145456605471527,0.5257039400215028,0.8160398759515775,1.6917862717304577,1.7373893774424352,-1.1841749474081864,-0.47256520652892764,-0.1685870190554528,-0.6834327966656656,1.138779002275907,-0.628955444583581,0.4502354416893184,2.394882911337278,1.0213343922644458,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0,1.0,0.0,0.0,1.0,2.466740121159479,0.010937290711700168,0.6090985946696073,0.9808454283856779,0.09768917528874041,0.009774535574518772,0.16823652724853028,0.8113844670384016,-0.15368885224389572,-0.0241866130538387,0.1445579812526454,-1.2464564026801344,-0.05295300887618215,-0.6756403643944874,-0.05352449971832837,-0.07222577486078915,-0.3435494453034339,1.1892783410387975,-1.3098311306714316,-0.25450471966581023,-0.9068377305002808,0.6224327504667179,0.26170626395331104,-0.04115471947543453,0.5334487547667779,0.8026212141602906,1.6615438419078794,1.6992289753950494,-1.1317772800089287,-0.6197815625829906,-0.1293875352513485,-0.6501282963917954,1.1255775824625935,-0.5762867058059395,0.45531346377765125,2.469933906394579,0.8366832282987713,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.008333333333333,1.0,0.0,0.0,1.0,2.4735219099598917,0.01202195890586094,0.6087340975521902,0.9808754596367676,0.0991050168221713,0.004867209841116102,0.16744503155189133,0.8072485826538327,-0.15600101048525547,-0.03405384830624644,0.12804362405522862,-1.2122526342355395,-0.08533371215491217,-0.6690142092986465,-0.03979228392647716,-0.058289167198963966,-0.35275810596723745,1.1834853606698705,-1.3107507627280373,-0.2597871320232715,-0.8975237814320519,0.6178239469905608,0.265509773159227,-0.02028900094813895,0.539648660493149,0.7863172297550447,1.6372580733122002,1.6301072158630239,-1.0775003924365012,-0.7746083616541544,-0.09138493623878752,-0.6186776206077704,1.1074075686529583,-0.5364304511749385,0.4542666583444621,2.5297988482985683,0.6522661715594347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.016666666666666,1.0,0.0,0.0,1.0,2.480266479651432,0.013076035398204872,0.608350544674858,0.9809086547157858,0.10042465676517007,0.00011506168232909229,0.1665325378960063,0.7998490548530843,-0.1572790669904811,-0.04356133150161566,0.11193538998870994,-1.1716982566275644,-0.11772138809657887,-0.6625350772319033,-0.026236865163125036,-0.04505732126307209,-0.3615077851773756,1.176368201677895,-1.311354212942078,-0.2648160133426064,-0.8883809376893982,0.6134922429471356,0.26927737492571874,0.0010085946628749338,0.5443198576261018,0.7675058041451766,1.619181746883788,1.5303088656608272,-1.021879648390469,-0.9381479169005313,-0.052385679746200786,-0.5894544086475217,1.0847526425691423,-0.5101451217874042,0.4462984323675656,2.57277936137851,0.4714254212024538,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.025,1.0,0.0,0.0,1.0,2.486945210684044,0.014097489169690813,0.6079490597754266,0.9809470773899552,0.10164673189431708,-0.004456393283046248,0.16550200546889515,0.7889844397470801,-0.1573556339851381,-0.05253515204342917,0.09636585663299524,-1.125315282227394,-0.149997956306543,-0.6562224458962269,-0.012805921478414025,-0.03278401943795018,-0.36978943344041193,1.1678495620548617,-1.311623857390474,-0.2696113721673969,-0.8794445707225662,0.609321528294104,0.2729480803653531,0.022590655074836218,0.5475057508465232,0.7464977623968649,1.6074049105178438,1.4003016700358428,-0.9653968415736824,-1.1115149770499944,-0.010151185126310303,-0.5627684796007026,1.058084125200922,-0.49811651829574366,0.4306278817572762,2.597362691176987,0.29731208371840845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.033333333333333,1.0,0.0,0.0,1.0,2.4935274523331095,0.015084980327570238,0.6075313544219224,0.9809929558059236,0.10277080262496681,-0.008823662890019861,0.16435670281491996,0.7744907688718186,-0.15609369342111848,-0.0608101798651188,0.08145180558468362,-1.0735650333551927,-0.1820806895464993,-0.6500934478586222,0.0005532166788390276,-0.02171896009580804,-0.37759773253693696,1.157842952060395,-1.31152339936085,-0.2741954880026181,-0.8707462022693828,0.6051903009755398,0.27645450628834,0.044297972849158054,0.5492750590214086,0.7235546420901628,1.602002508664991,1.2404384586494586,-0.9084534966131352,-1.2957605048312537,0.03751848986950801,-0.5388457074441688,1.0278495882164784,-0.5009480165054692,0.40651205981963145,2.6022416218217286,0.13280888505644128,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.041666666666666,1.0,0.0,0.0,1.0,2.499980939203148,0.016037764285669383,0.6070996347753616,0.981048633141613,0.10379720890827314,-0.012964969825272666,0.16310005638034444,0.7562563356846217,-0.15339802739937686,-0.06823877956071323,0.06728707682578683,-1.016820690978,-0.21393358893175954,-0.6441632018613909,0.013894120332669154,-0.01211004512712587,-0.38493032505063085,1.1462535536410074,-1.3109985492259821,-0.27859213395813304,-0.8623137442522916,0.6009723946856795,0.279723281362347,0.06596134877186503,0.5497192322641306,0.698908459041343,1.6031988126071492,1.0506480140369017,-0.8513492694159419,-1.4917909788901618,0.09269992403429406,-0.5178117135729299,0.9944653566592043,-0.5191475348080532,0.3732660019315537,2.5863431351762878,-0.01956242473833969,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.05,1.0,0.0,0.0,1.0,2.5062723729675818,0.01695556509000679,0.6066564560925531,0.9811165397015807,0.1047268893948484,-0.01685983730129185,0.1617354631732834,0.7342406353216832,-0.14922602881092512,-0.07469901079987376,0.053938303267372256,-0.9553455194290931,-0.2455798274073673,-0.6384449735412665,0.02727319688895818,-0.00420815986185968,-0.39178688702720266,1.1329797690788923,-1.309978400626945,-0.2828256832288336,-0.8541717796583961,0.5965378420620723,0.28267560632053257,0.08740369176876285,0.548949018609103,0.6727831955638353,1.611519820447029,0.8301790256788905,-0.7942644631432239,-1.7002807891473193,0.15726407828701383,-0.4996800570754345,0.9583142987499538,-0.5531012503882127,0.33027975587610503,2.5488793584861296,-0.15776052090139103,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.058333333333334,1.0,0.0,0.0,1.0,2.5123682166124333,0.01783843023655917,0.6062045372769275,0.9811991871495293,0.10556118317911688,-0.020488592565281977,0.16026605790892381,0.7085012481885635,-0.14359891855021206,-0.08010244314520018,0.04144339122909896,-0.8892771401562422,-0.2771165864621583,-0.6329501486019936,0.0407527840067863,0.0017262719675223027,-0.3981680661030179,1.1179155404885521,-1.308377481254532,-0.2869201349093903,-0.8463418392731257,0.5917540405125427,0.28522794396028206,0.10844267141330052,0.5470898902491074,0.6454189438869307,1.6279097067896642,0.5774512299437652,-0.7372425732462717,-1.921569059925976,0.23279109243206975,-0.4843431768007034,0.9197470322167245,-0.6030186055033782,0.27703387641432986,2.4894383066085695,-0.28039015074302176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.066666666666666,1.0,0.0,0.0,1.0,2.5182357829101285,0.0186865772160193,0.6057465446301952,0.9812991846494664,0.10630162906433616,-0.023831808079362252,0.15869441952476077,0.6792313846527188,-0.13661495014153927,-0.0844026725435307,0.029810743503436293,-0.8186146457063848,-0.3087329960121988,-0.627687991143151,0.054405025335452585,0.005416027303869738,-0.40407426324797385,1.100953618080126,-1.3060985490864105,-0.29089806950884534,-0.838842662454784,0.5864875319703493,0.28729283759410473,0.128894330212239,0.5442758494300526,0.6170994557920273,1.6538047392405384,0.2900258718948157,-0.6801676897730091,-2.1555292703668094,0.3204630687974719,-0.47156180120355273,0.87907948090165,-0.6688342080084841,0.21311776938012783,2.4081268618960197,-0.3869350198387056,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.075,1.0,0.0,0.0,1.0,2.5238447141324785,0.01950023257456302,0.6052848402835892,0.9814192766092187,0.1069497606152619,-0.026869679820452134,0.15702220387777083,0.6468064377078884,-0.12846595779062744,-0.08760661712111226,0.019014751994172963,-0.7432001387925928,-0.34072981484737275,-0.6226651576721265,0.06831619632746194,0.006560036499102564,-0.4095041942659014,1.0819900526491053,-1.3030364301079074,-0.2947794982627828,-0.8316905145914315,0.5806068037124013,0.2887799067832842,0.1485781191115675,0.5406409732517956,0.5881822506063616,1.6911853922036428,-0.0353647420448407,-0.6227334390875849,-2.4014051018960236,0.4209000904582405,-0.4609462926075625,0.8365733334384462,-0.7500641532889052,0.13825841613425927,2.305758964833057,-0.4780667455743881,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.083333333333334,1.0,0.0,0.0,1.0,2.529168915227653,0.020279446093471237,0.6048211647059482,0.9815624025391301,0.1075068636017976,-0.02958130072288638,0.15524970482360295,0.6143764949474173,-0.12071791789781869,-0.08993654693460355,0.005365757797412607,-0.6758499538120034,-0.37345449321412905,-0.617884953633045,0.08259144853884663,0.004826614936455726,-0.4144531538994336,1.0609301997151923,-1.2990835475787732,-0.2985805077189714,-0.8248997735641432,0.5739864627488676,0.2895971445296757,0.16732364629278995,0.5363080703371461,0.5690039562407057,1.7286678675235436,-0.3445711166445121,-0.554202847429166,-2.651475666558616,0.5510327120415148,-0.4473193630072603,0.7825030136707434,-0.8007489811007984,0.064125316008673,2.197706826060023,-0.5413264979211463,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.091666666666667,1.0,0.0,0.0,1.0,2.5342358052820195,0.021017524176367673,0.6043534645059148,0.9817314174689877,0.10796086997935263,-0.03205615946510113,0.15336321967205982,0.5869706115954848,-0.11544064539741132,-0.0920651340287198,-0.015441615677242476,-0.6351330945456052,-0.4069665036715765,-0.6131817584014481,0.09712732745285434,0.0008171845550273623,-0.41874090838972083,1.037798791539795,-1.2938525515738821,-0.3022348209795705,-0.8186487976969191,0.5672609873607213,0.2898486620500954,0.1852065662125679,0.5316188649531098,0.5724118081639062,1.745767145803393,-0.549795186528707,-0.4615848808344003,-2.8894637373832888,0.7301884940707914,-0.42481476693847053,0.7011397301589195,-0.7497896253966463,0.007802411730706282,2.10897080886491,-0.5614207348977263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.1,1.0,0.0,0.0,1.0,2.539109910391411,0.02170926743260947,0.6038764360084865,0.98192675632781,0.10830148822666277,-0.034430698842666405,0.15134450711168296,0.5656242286233035,-0.1123515370945819,-0.09452600292552531,-0.040536329088594086,-0.6163500649473506,-0.4408985597621375,-0.6083447568303132,0.11168756763556985,-0.004336638172356057,-0.4221462352466736,1.0127724707588042,-1.28691373934426,-0.30566075383461255,-0.8132141113948279,0.5614899689922568,0.2897271847251875,0.20247315977387179,0.5269510580888507,0.5921069909915744,1.7446739129014253,-0.6604928103800471,-0.35180380882128826,-3.106272537279642,0.9446842655077115,-0.3968313002647883,0.5932109893978343,-0.6019529852307159,-0.03406249235539671,2.0435390603837256,-0.5527444771022116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.108333333333333,1.0,0.0,0.0,1.0,2.543834062127068,0.022357795150495664,0.6033864383614169,0.9821470812392922,0.10853344215091504,-0.03675250812013268,0.1491873181446343,0.5484988259544632,-0.11033254102495281,-0.09725808283950844,-0.06611759362083572,-0.6057005271472515,-0.4748650978314592,-0.6033133085515885,0.12620522600121142,-0.010191028951306757,-0.42460430520340897,0.9860275825851343,-1.2781078138154203,-0.30884867598398363,-0.8087619478736219,0.557228437606876,0.28928095384417213,0.21926555055229666,0.5224064570014063,0.6170399069946142,1.7404113864119017,-0.7357526417846978,-0.23623668331489434,-3.3031460630878606,1.1731528918513368,-0.36802374480698674,0.4683157815873007,-0.4002158742903261,-0.0721632160889163,1.9925464993684312,-0.538188999967697,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.116666666666667,1.0,0.0,0.0,1.0,2.548438010569294,0.022964930951257043,0.6028821678972034,0.9823911964850653,0.10865918337326873,-0.03904052058812856,0.14688960715402474,0.5344463654768705,-0.10913093951276424,-0.10008948141487096,-0.09194924610848176,-0.5983436144987713,-0.5087204447036715,-0.598060758380403,0.1406944240757682,-0.01659918220210102,-0.42608351330192185,0.9577200363740065,-1.2673611911467377,-0.311794482914729,-0.8054088483683729,0.5548197044207513,0.2885244644570389,0.23568226809667897,0.5179812414227224,0.6445966165208894,1.7397465954772946,-0.8006840157704458,-0.11754047947492574,-3.4819191678603745,1.4079875935934627,-0.3386743930792202,0.33069979642750935,-0.16277861467721477,-0.10914644568557286,1.952048258772708,-0.5264272136269565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.125,1.0,0.0,0.0,1.0,2.5529450348199516,0.023530823978877374,0.6023629053099779,0.9826581256061353,0.10867897299335419,-0.04130253261963217,0.14445064835075844,0.5229093484239907,-0.10869833187010225,-0.10298682294707154,-0.11813557424657133,-0.5923313309942082,-0.5424591771353975,-0.5925700316095737,0.15520100259249967,-0.023535762547480854,-0.42656331319465773,0.9279955964541281,-1.254641353922196,-0.31449324920197064,-0.8032502845998301,0.5545154606955891,0.28746184641607925,0.25179968819850845,0.5136326701076237,0.6740048246530828,1.7453123354541278,-0.8654851977576528,0.003258276073944133,-3.643434306867761,1.6453196646879586,-0.30871045983397627,0.18234755601826524,0.10217409810615363,-0.14585859506816012,1.9201707186324257,-0.5208678432679448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.133333333333333,1.0,0.0,0.0,1.0,2.557375739752828,0.024054701388956243,0.6018278605301772,0.9829469976615093,0.10859186687415757,-0.043541651315693,0.1418701196098728,0.5136879568225423,-0.10903514597724101,-0.10598706592766902,-0.14477019134430888,-0.5868164195059381,-0.5760992596198803,-0.5868273446361849,0.16978296300000367,-0.0310239354980619,-0.42602920870068944,0.8969961312595438,-1.2399391967352718,-0.31693965724529527,-0.8023697224347351,0.5565226060558539,0.28609348787256955,0.2676851134072194,0.50930011070159,0.704987071370109,1.758138912115102,-0.9341761776356505,0.12553255685675335,-3.7879652082497683,1.8827615579224233,-0.2781165809257158,0.02458052304167513,0.390327694899959,-0.18259357636104645,1.8963070720029729,-0.5233644914784485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.141666666666666,1.0,0.0,1.0,1.0,2.561750199365524,0.024535353152733166,0.6012759584317258,0.983256964071031,0.10839626662856128,-0.04575880899455749,0.1391478472222023,0.5067849471981504,-0.11016144005494231,-0.10915920275419197,-0.17191841021997234,-0.5813847685351131,-0.6096481109683852,-0.5808202470867385,0.18450331779441803,-0.03910536550807503,-0.42447110391371184,0.8648628429832986,-1.2232619946234888,-0.31912852555073257,-0.8028406092158021,0.5610209222772551,0.28441862014339514,0.28340480606522467,0.5049099285829829,0.73742482875925,1.7786743339152162,-1.0082207169731585,0.24880339079769054,-3.915503109358336,2.1184945894853335,-0.24692184307641307,-0.1413645023454979,0.6987654706520541,-0.21941447897790178,1.8806214644636765,-0.535488724667077,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.15,1.0,0.0,1.0,1.0,2.5660891494665052,0.024971356156535143,0.6007057712285786,0.9835871534440954,0.10809016323238779,-0.04795375985511926,0.13628376685497953,0.5023115003679014,-0.11210605462018845,-0.11258771200936799,-0.1996307267537989,-0.5757923316697987,-0.6430961500967999,-0.5745369308235307,0.19942753523192394,-0.04782761411428121,-0.42188248552072793,0.8317377461035715,-1.2046309535771829,-0.3210550212965688,-0.8047257974738268,0.5681686972333881,0.2824365798896045,0.299028804481614,0.5003752986238054,0.7712539064568746,1.807136330228672,-1.0879664597504743,0.3726693043393703,-4.025930015728026,2.350880571767604,-0.21517507001135083,-0.31412894380591805,1.024935498375692,-0.2562707867969971,1.8737274621470579,-0.5589000114096476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.158333333333333,1.0,0.0,1.0,1.0,2.5704145832360723,0.02536116330675306,0.6001155027238553,0.9839366495536164,0.10767123412814475,-0.05012546561876694,0.1332779528024985,0.500425871925806,-0.11489657849905904,-0.11636431295221326,-0.22795093656655788,-0.5698587102858083,-0.6764172467756592,-0.5679660153124573,0.21462225663156256,-0.0572381398372496,-0.418259948841389,0.7977640093878315,-1.1840806517606954,-0.3227147767175884,-0.8080760916125674,0.5781031805835166,0.2801474403634452,0.31463359710100897,0.4955949283928221,0.8064212910637392,1.8435836596000295,-1.1731679832897386,0.49677144486817815,-4.119138216947853,2.5783126279194146,-0.18294260275952268,-0.4921694126554166,1.3662071195788772,-0.29306120489973275,1.8764659311675547,-0.5953898827646409,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.166666666666666,1.0,0.0,1.0,1.0,2.57474991906167,0.025703135746519112,0.5995029992546599,0.9843044808398211,0.10713688443141155,-0.052272231109494985,0.13013066836042508,0.48425426830124774,-0.11362268333537553,-0.11512842666030906,-0.2549973337303223,-0.5496679903766908,-0.7056214571260315,-0.5610965759724684,0.2301539295585911,-0.06738041383577685,-0.41360296143959163,0.763085442487774,-1.1616590764451926,-0.3241040646758942,-0.8129286210180837,0.5909388158930361,0.277552226474609,0.3303032366677399,0.49045213391106135,0.8327821348561426,1.8275335671370119,-1.2265874775650636,0.6058878358702657,-4.25310394177745,2.821736362850764,-0.021770296806468137,-0.6459828251527111,2.5088925656577676,-0.3534878347123138,1.6709525968733352,-0.3800661255982485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.175,1.0,0.0,1.0,1.0,2.578818320514635,0.025983038974262945,0.5989331605771221,0.9846899646328021,0.10648368803942926,-0.0542803386668572,0.12688791340118294,0.49117471523253536,-0.11910100428061912,-0.11920400716840128,-0.287657510512752,-0.5442247736955337,-0.7367539269316212,-0.5540863130648549,0.24508114941717943,-0.077681264463334,-0.40816181824355124,0.7268789436915407,-1.1370517123798494,-0.3230776149976962,-0.8188424720317793,0.6199180566778127,0.2742559764515733,0.3424828070488979,0.4892604929661846,0.874688457689281,1.881283619001577,-1.3107246062100688,0.7340950097741539,-4.305385556088108,3.0410739500364725,0.1409342199510133,-0.7131408994189803,3.580180459835094,-0.3899298880376345,1.334878629192432,0.12815351174522815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.183333333333334,1.0,0.0,1.0,0.0,2.5833019942584077,0.02622208542611317,0.5982804144196986,0.985091771038156,0.10568509460954235,-0.05638798675850807,0.1234716905194378,0.5333750317062033,-0.1342703799113605,-0.13311323353079588,-0.3247295881791403,-0.5609824072201848,-0.7727744412046903,-0.5465184350109804,0.2615086565419507,-0.089225823939278,-0.4013680446100224,0.6913290165529722,-1.1109745106112514,-0.321755161010044,-0.8248143026750667,0.650608490223621,0.27105339500731507,0.3525512138209471,0.4925880257734818,0.935462227634285,2.04590354821182,-1.4506660450606788,0.887600923941293,-4.232509055520624,3.2081428325022054,0.1715999519242184,-0.6985211632173449,3.7267095572180042,-0.3868528456355169,1.0745320856823526,0.6575845376242551,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.191666666666666,1.0,0.0,1.0,0.0,2.5881399481821514,0.026412804651095335,0.597563062746217,0.9855067578046817,0.1047583984659479,-0.058538667934348594,0.1198971752324913,0.5690809188396196,-0.14725880406212333,-0.1451375671441125,-0.3584012606700586,-0.5665231463496898,-0.8071735928992383,-0.5384952759376168,0.2791795418873764,-0.10185903188101197,-0.39336846951119636,0.6563371260995303,-1.0835826651714793,-0.32021761579895924,-0.830484491418735,0.6820298826314461,0.2678084290243147,0.36039167514360376,0.5002202352599222,0.9870280527877906,2.181571814366653,-1.5717918886734616,1.0268791525323306,-4.171840897462862,3.3596854093140216,0.1955171827735358,-0.6528831407025559,3.7841522281014606,-0.3976853113707479,0.8039078616740658,1.1598315661583514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2,1.0,0.0,1.0,0.0,2.5932774194492305,0.02655070887839926,0.5967914180241242,0.9859341076939787,0.10370173709870349,-0.06069365395456132,0.11617299762909683,0.5992739993314516,-0.1582992294430068,-0.15592839351058824,-0.3914789085122302,-0.5637000252211495,-0.8405628542699528,-0.5300679674645172,0.29786818678139493,-0.11542235541716903,-0.3842533920678169,0.6217983349285912,-1.054979753789351,-0.3184965412971517,-0.8356956883534427,0.713677694025312,0.26442530648446927,0.36594967818218155,0.511918551876121,1.0331958655033757,2.2925135819311273,-1.6746965665669573,1.156210806925052,-4.122421844511801,3.4999211810769593,0.21590887857228958,-0.5916880620431897,3.7900559175891413,-0.41920309255822463,0.5302317278652346,1.6310903736730387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.208333333333334,1.0,0.0,1.0,0.0,2.598670665817578,0.026632790135042432,0.5959730095403545,0.9863730939973215,0.10251317025614012,-0.0628222972781614,0.11230551334201594,0.6251062871858306,-0.16767696257184928,-0.16571050607642063,-0.42411953631464017,-0.5538985664295215,-0.8731056456737569,-0.5212753448458939,0.31738810158622854,-0.1297706413237946,-0.3740982893957788,0.587630095357667,-1.0252506454868633,-0.3166191344894211,-0.8403459591194549,0.7451974812579318,0.26082171081501093,0.36922887060802434,0.5274050748211395,1.0750747270790328,2.38282248263902,-1.7612107387512506,1.2769260022906659,-4.081940496786334,3.630594551695463,0.23325300427798235,-0.5199455613288118,3.758340591134821,-0.45011200240353544,0.2596123329106381,2.0660857858569304,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.216666666666667,1.0,0.0,1.0,0.0,2.604284648217958,0.026656845385216166,0.5951147691317364,0.9868229830347803,0.10119148438990198,-0.06489722423586179,0.10830066448567764,0.6475164879553594,-0.17561852161752595,-0.17452556173047923,-0.4562745184611458,-0.537691210894404,-0.9047600708375663,-0.5121500553465334,0.3375818948253786,-0.14477586772968987,-0.3629712920296391,0.5537659933154856,-0.9944698445944267,-0.314608991225852,-0.8443614477089229,0.776316703877559,0.2569234397777437,0.37027655039735885,0.5463533149737365,1.1132825645317102,2.455691798965649,-1.8335087682276985,1.389755715961033,-4.048653308311523,3.752607433798787,0.2479848306966026,-0.4403597620582822,3.6970395316974414,-0.4895291872842422,-0.003585192065518328,2.459625590103296,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.225,1.0,0.0,1.0,0.0,2.6100914324558113,0.02662123752402868,0.5942237175913371,0.9872830621255664,0.09973610056255261,-0.0668924420614366,0.1041646133775867,0.66729140578167,-0.18230401100114382,-0.18236126676788517,-0.48786816039453407,-0.5153214899353918,-0.9354242342006823,-0.502720635437032,0.35831629823565603,-0.16032912079425624,-0.3509356941297616,0.5201525402191416,-0.9627071882568835,-0.31248605397781104,-0.8476852884870929,0.8068148067862225,0.25266289102694023,0.36916911740693237,0.5683988346561945,1.1482478154399822,2.5138135452888055,-1.893869155731623,1.4952125999444577,-4.021093979945086,3.8662300696850505,0.2605249738315074,-0.3546282553964075,3.611438604312105,-0.5366892403416212,-0.25665426195757957,2.8081569799355144,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.233333333333333,1.0,0.0,1.0,0.0,2.616069076958979,0.02652481754409498,0.5933071069902905,0.9877526680846013,0.09814701705874733,-0.06878256360986693,0.09990389721314856,0.6850995072985605,-0.18787450933809854,-0.18919714459597375,-0.5188169043188261,-0.4869007278471804,-0.9649938789273682,-0.493012591755867,0.3794787872468587,-0.17634035365855025,-0.33805108203056483,0.4867477603164008,-0.9300326767663425,-0.3102669083286602,-0.8502719186321963,0.8365073472827608,0.24797861910538332,0.3659989793647325,0.5931559313059951,1.1802896974810306,2.5594843743312126,-1.9444353282496192,1.5937059351216598,-3.9979366006158004,3.9712063970438582,0.27124529161371425,-0.2639065660815354,3.5052747175588284,-0.5908516268715647,-0.4983383207726588,3.110122634093697,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.241666666666667,1.0,0.0,1.0,0.0,2.6222006813325547,0.026366915369792313,0.5923723811024979,0.9882312032695153,0.0964248005192845,-0.0705424980362387,0.09552540343543449,0.7014899791623057,-0.19243204908288658,-0.19501503873995113,-0.5490322881139935,-0.4524931418734915,-0.9933832166159434,-0.48304914047901487,0.40097437114117623,-0.19273637626508322,-0.3243739285444006,0.4535202635422116,-0.8965204149728192,-0.30796529911758247,-0.8520837312551185,0.8652360520788697,0.24281536391241415,0.36086347872738805,0.6202342118910894,1.209646587033828,2.5945832950617986,-1.9870316522812936,1.6855875301857437,-3.9779957275923774,4.066884641977711,0.2804468983803843,-0.16902711996127806,3.3812386163866903,-0.6512624147860008,-0.7286083720085568,3.365835498906309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.25,1.0,0.0,1.0,0.0,2.628473291646444,0.026147355865101283,0.5914271040263787,0.9887181377241757,0.09457060371685701,-0.0721473600718232,0.09103627565100024,0.7169233687271472,-0.19604457960603872,-0.19980314118458348,-0.5784132212636652,-0.41214685149122204,-1.0205231959926877,-0.4728518153053032,0.42272184216455533,-0.20945754786323847,-0.3099579565274691,0.42044783152319454,-0.862251266066714,-0.3055927933556538,-0.8530890372982176,0.8928613242225389,0.23712424552561664,0.35385550649792324,0.6492531896211002,1.2364789627984762,2.6206286172801843,-2.023116479002154,1.7711633481027256,-3.960158193995267,4.1522718471641555,0.2883537021808824,-0.07060016719815154,3.241291820744445,-0.7171073591594435,-0.9482648844530406,3.576941738816495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.258333333333333,1.0,0.0,1.0,0.0,2.634877489509436,0.02586653412508301,0.5904788805193181,0.9892129912084425,0.09258625119036713,-0.07357241196189263,0.08644387957089103,0.7317197903515824,-0.19874009418391486,-0.2035398428846954,-0.6068543443050234,-0.3659219680448844,-1.0463682728040085,-0.46244115776570693,0.44465151476251263,-0.22645498424845245,-0.2948545394093552,0.3875176269756238,-0.82731588418675,-0.30315940408123443,-0.853260400708421,0.9192575824246104,0.2308635745930901,0.34505906398650404,0.679849907538031,1.2608886693043986,2.6386621369717544,-2.053691979400492,1.850718874623395,-3.9435272402351496,4.226231509742218,0.29510969422597677,0.03087562461494553,3.086724230557185,-0.7875144578797549,-1.1588583913363237,3.746219621594431,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.266666666666666,1.0,0.0,1.0,0.0,2.6414054260178164,0.025525387706215766,0.5895353862130992,0.989715317928102,0.09047421493030149,-0.07479320646691343,0.08175562463767891,0.7460660692987424,-0.2005100056916768,-0.20618744692190405,-0.6342380059608398,-0.3138942597994606,-1.070891344772947,-0.45183700415022987,0.4666995444474179,-0.24368574751991334,-0.2791126419504125,0.3547223775192754,-0.791814074237677,-0.30067429845188753,-0.8525744435546352,0.9443067280651587,0.22399900456095406,0.3345411999756512,0.7116901833143408,1.282915113348927,2.649291718171544,-2.079361874339795,1.9245164064912301,-3.927435622155082,4.287586223434143,0.3007784034777816,0.13495215894980372,2.9182724985046127,-0.8615379545097751,-1.3624310245231097,3.877138792942365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.275,1.0,0.0,1.0,0.0,2.6480505419381726,0.025125511864416413,0.5886043599881955,0.9902246629897528,0.08823776606586281,-0.07578556013309312,0.07697897325861111,0.7600763466263154,-0.20132233908647068,-0.20769513979671522,-0.6604282741229468,-0.25615046587920026,-1.0940711794747473,-0.4410592392098915,0.48880637673203836,-0.261111015487449,-0.2627792659678347,0.32206036660637244,-0.7558561137961809,-0.29814643068993807,-0.8510111980592576,0.9678954573996873,0.21650460868459384,0.3223518802444522,0.7444688874204037,1.3025373159025444,2.652862849625337,-2.1004702844693557,1.9927974251830711,-3.9112894901807596,4.335077205878299,0.30536519747693225,0.24121501309408933,2.7363227754726616,-0.9380988171498678,-1.5611024028684062,3.973249059717072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.283333333333333,1.0,0.0,1.0,0.0,2.654806649745643,0.02466917346979539,0.5876936805413885,0.9907405242679163,0.08588098526470596,-0.07652566457849987,0.07212137412617738,0.773760345883903,-0.20112454695425103,-0.20798658188581684,-0.685285773616139,-0.1928013446166526,-1.1158979805672435,-0.43012804888518746,0.5109139252745069,-0.2786935855944026,-0.24589935153069467,0.28953421934959606,-0.7195627874730387,-0.29558487849393866,-0.8485541933364004,0.9899121076563697,0.20836402427512293,0.3085228265945111,0.777911000976292,1.3197024328064522,2.649422795825428,-2.11712546368664,2.055812837437094,-3.8946410482892757,4.36747138359407,0.30883744534380697,0.34922019937289717,2.540924868827943,-1.0159801124393064,-1.7570624854770656,4.0381144887870795,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.291666666666666,1.0,0.0,1.0,0.0,2.661667133921042,0.024159331530683666,0.5868114510777898,0.9912623065225366,0.08340880269571917,-0.07699017690627867,0.06719020733490882,0.7870424287957849,-0.1998514880774647,-0.2069603174884936,-0.7086650890668638,-0.12397846939682904,-1.1363700201401727,-0.4190641986631173,0.5329634233291288,-0.29639643988222636,-0.22851571867721646,0.25714968246821784,-0.683064924069613,-0.29299913993420795,-0.8451908614030427,1.0102442052134863,0.1995716068106054,0.2930675054865011,0.811770795566855,1.3343292806202667,2.638808052694419,-2.1293146520386763,2.113824156078035,-3.8771577992810546,4.38359011569827,0.3111379724028518,0.45846752757046083,2.331883823058516,-1.0938162011567627,-1.9524255329153695,4.075093445248557,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3,1.0,0.0,1.0,0.0,2.6686243779645116,0.023599650424461893,0.5859660938016134,0.9917892712862337,0.08082702172687412,-0.07715630684948291,0.06219275065865315,0.7997899432461508,-0.19743512891061885,-0.2044921287223339,-0.7304198350727084,-0.0498345512341324,-1.1554864987314655,-0.40788922754151635,0.5548940594860805,-0.31418216312838054,-0.21066894892939408,0.2249149226949118,-0.6465029522114009,-0.2903992456205578,-0.8409130678768927,1.0287768380406783,0.19013375425584356,0.2759824010459216,0.8458292250637679,1.3463203345703079,2.620730869240746,-2.136977659269829,2.1671108547937172,-3.858550903098876,4.382299199466053,0.3122106239603051,0.5683988629215286,2.1088555047785995,-1.170069854687682,-2.1490778601062988,4.087144075033733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.308333333333334,1.0,0.0,1.0,0.0,2.6756694688020057,0.022994497486141383,0.585166456948867,0.9923204828561243,0.07814230890499645,-0.0770019195187788,0.057136181655209076,0.8118250902782758,-0.19381258830209785,-0.20043665064039157,-0.7504099984516678,0.02945435214554737,-1.1732438303628114,-0.3966255264202788,0.5766422711498079,-0.33201273420339017,-0.1923972044306545,0.19284050074990325,-0.6100266040785122,-0.28779562953486953,-0.8357175470210172,1.0453917969597963,0.1800704425658107,0.25724954115139614,0.8798898634840839,1.355577014985646,2.594829463836983,-2.140061553814067,2.215980460791896,-3.8385461978419073,4.362518303894762,0.31202428541545757,0.6783939701655162,1.8714042096060801,-1.2430327613550503,-2.3486124223251186,4.0767558439292895,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.316666666666666,1.0,0.0,1.0,0.0,2.682791851256382,0.022348902263535284,0.5844219171122158,0.9928547546226787,0.0753621519960579,-0.07650564823656279,0.05202757017094695,0.8229273886880183,-0.1889327523577474,-0.19462920828723523,-0.7685085361191328,0.11368830541829315,-1.189633377711354,-0.3852962772917556,0.5981412172166969,-0.3498498556919483,-0.17373594124952915,0.16093915273088003,-0.5737943138131548,-0.2851988408636335,-0.8296065017074674,1.0599669082007797,0.16941654156659272,0.23683886067383628,0.9137751557959227,1.3620133682508828,2.5607007462766296,-2.138574776746136,2.260775876369678,-3.8168928794871495,4.323257198063697,0.31059326901181294,0.7877671653749929,1.619033617591672,-1.310851692768365,-2.5523149640803937,4.045949896614934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.325,1.0,0.0,1.0,0.0,2.6899791007701555,0.021668495604858846,0.5837424809333597,0.9933905947234443,0.07249479017698314,-0.07564700595698022,0.046873896810224316,0.8328416351434929,-0.1827627884996213,-0.18688932285440957,-0.7846075707980571,0.20264510453404527,-1.204636407688647,-0.37392530361609744,0.6193206169210851,-0.3676556471491591,-0.15471760649115987,0.12922561942511743,-0.5379723174441172,-0.2826190750513393,-0.8225880942647673,1.0723756905863242,0.15822291435300462,0.2147109584167229,0.9473223617609995,1.3655681625405147,2.517936388509008,-2.132631064325441,2.3018788738949487,-3.793370689105892,4.263658341164767,0.307998527833091,0.8957806419319514,1.3512142981606878,-1.3715662646311177,-2.7611366867037512,3.9962660535169237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.333333333333334,1.0,0.0,1.0,0.0,2.69721673726278,0.020959419275780072,0.5831388816802762,0.9939261536192503,0.06954911295533339,-0.07440648937835259,0.04168208700840945,0.8414519796819793,-0.17519998318135865,-0.17473304064913645,-0.7988979973392825,0.30685693484542825,-1.2186809507954701,-0.36253680791608034,0.640106823691847,-0.385393706764039,-0.13537129335128,0.0977163079124485,-0.5027333414604087,-0.2800655320664153,-0.8146768243419349,1.0824871465034578,0.14655710382274076,0.19081991589544042,0.9803795900212048,1.3665080601762924,2.46463016023295,-2.137992737576515,2.339473880331133,-3.7721961974679536,4.169405099557096,0.3074609868150635,1.0088655617860076,1.0365810687188937,-1.4282969882075143,-2.9846093739236657,3.907296349303,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.341666666666667,1.0,0.0,1.0,0.0,2.7044853091865906,0.020224445649832667,0.5826607131806651,0.9944659952569206,0.06652926844646449,-0.07267621454928919,0.03646105534222931,0.8481679612128746,-0.16606284418828393,-0.1556903950512105,-0.8112711317366565,0.4366038983562981,-1.2327073448060055,-0.3511501692798259,0.6603977862583009,-0.403288859442101,-0.11572637515230766,0.06635568280065153,-0.46848223245149895,-0.27749472527108826,-0.8057736682350005,1.089652041731639,0.13441796454954605,0.16496746885132849,1.0124439675827162,1.3650484271353214,2.3989478261084884,-2.171510592420598,2.3744362590426196,-3.7580050748321088,4.024822262137792,0.31167197152486614,1.131588052185848,0.644705415704272,-1.4837868309057924,-3.2338915519111677,3.7615482207817297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.35,1.0,0.0,1.0,0.0,2.711755920454681,0.01946910431105778,0.5823547923172975,0.9950132379121646,0.06344284453640582,-0.07035097262608257,0.0312154209888796,0.851648606154231,-0.15533237921055354,-0.1322300547453005,-0.8210189938525743,0.5788867770313341,-1.2468136108796155,-0.3397860007971583,0.6800892874603218,-0.42158554997104897,-0.09579735570056969,0.03508288999858002,-0.43565297042477885,-0.27487099920766755,-0.7958170234721708,1.0932322367651957,0.12182732330764422,0.13692172336358763,1.043072060367567,1.360798529043492,2.321972731690254,-2.2170365159490535,2.408614825953988,-3.7471687341077122,3.8446287509686496,0.3165428526216363,1.252287585330052,0.21126413375614383,-1.5294598173649079,-3.501350486168406,3.5882288821444286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.358333333333333,1.0,0.0,1.0,0.0,2.7189950277256565,0.018704407044208143,0.5822243564936805,0.9955617938162779,0.06030492220673922,-0.06743032034210682,0.025945769400320683,0.8511430412710884,-0.1432580320608931,-0.10737941452726678,-0.8278976861525429,0.7174943867492938,-1.2599926675768045,-0.3284701937957677,0.6990973317864718,-0.4402394680412519,-0.07558279471974119,0.003902870565522992,-0.40440508660202146,-0.27221901106072766,-0.7849022084794997,1.0931731106275748,0.10892696759346425,0.10661162741518838,1.0722477822851233,1.3536473286942585,2.234621054229977,-2.251004332452972,2.443204559664806,-3.7351645571387873,3.6528985263912985,0.31832221519801474,1.3601501824028772,-0.22005445571669835,-1.5548657815392173,-3.7723543850268184,3.4169025966116884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.366666666666667,1.0,0.0,1.0,0.0,2.7261709869006556,0.017940688201078643,0.582265083051091,0.996102737555782,0.05713004045320182,-0.06394398149735062,0.020655796817661238,0.8467717419477677,-0.13020130455772136,-0.08175907512278696,-0.8321670976721076,0.84773732870609,-1.271149051857953,-0.31722521198558734,0.7173329716974881,-0.45910228884526516,-0.05507727970615625,-0.027169852620399764,-0.3747713283182572,-0.2695656289543673,-0.7731478537654561,1.0895646625032507,0.09591289361532393,0.07404915027980732,1.1000204369777618,1.3439421516113326,2.1370873471820517,-2.266083745137525,2.4784036613571128,-3.7210022297034793,3.4604102927262295,0.31737788550561197,1.454225366433195,-0.6384059408498244,-1.5556880360480516,-4.0386102800615,3.2505842487479164,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.375,1.0,0.0,1.0,0.0,2.7332559608600633,0.017186732327389743,0.5824716347660748,0.9966262819231182,0.05393131731808059,-0.059931294746038,0.01535275554036586,0.8388321556944465,-0.11651839852345071,-0.055605449470513324,-0.8340918239288019,0.9681512184268481,-1.279498841331861,-0.3060711579355788,0.734715454239506,-0.47800753046021066,-0.03427606703045598,-0.05811383326286833,-0.34673158172325097,-0.2669293796356341,-0.7606651190389464,1.082533011613411,0.08299883365933006,0.03930145608083006,1.126424186430922,1.3319583904188659,2.030830985415235,-2.262188158295039,2.5141360082681765,-3.7037497977640057,3.271418917090576,0.314744708343041,1.5357151703322525,-1.0410859144180051,-1.5311106309215867,-4.294499710301574,3.08682924925876,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.383333333333333,1.0,0.0,1.0,0.0,2.7402256585325,0.01644971405322757,0.5828384293962787,0.9971226062728359,0.05072036458846887,-0.055434852105724824,0.010046384821518142,0.8276454378604066,-0.10253803405235182,-0.029123837748086134,-0.8339496829276536,1.0782218958657734,-1.284550993072127,-0.29502590547860624,0.751180154787742,-0.49680542481684914,-0.013175012901686638,-0.08889901591646653,-0.32024767970008094,-0.2643198838153166,-0.7475526009265853,1.072213230596284,0.07039438309996415,0.002474155108114424,1.1514675911320744,1.317989243694585,1.917848259035928,-2.2416433136656946,2.5503490923626266,-3.682289629807674,3.087367335795125,0.31143448235805393,1.6062679554670112,-1.427394784035938,-1.482376025796852,-4.53580825865196,2.9226453195119584,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.391666666666666,1.0,0.0,1.0,0.0,2.747059503445391,0.0157353358788878,0.5833597655690052,0.9975822740661855,0.04750719053781816,-0.050498798294813144,0.004748124652074809,0.8135248430719331,-0.08855443071973933,-0.002537197215603748,-0.8320252513949724,1.1777078655395186,-1.2860346763336816,-0.28410467054066907,0.7666795918901048,-0.5153682523546389,0.008229751175587805,-0.11948532709299622,-0.2952754594599989,-0.26173880492966656,-0.7338939864478295,1.0587430985461455,0.05829256656271586,-0.036295348230035926,1.1751349417561212,1.3023665143101948,1.8001536030203646,-2.207176996126089,2.587038642119276,-3.6553756314308314,2.908452896986177,0.30828012663117077,1.6676312388003,-1.7970988229579588,-1.4120015083609068,-4.759186604530056,2.755554206206816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4,1.0,0.0,1.0,0.0,2.7537399461706253,0.015047953427790424,0.5840295706888347,0.9979965128165095,0.04430033484247924,-0.04516813150608917,-0.0005297521858280364,0.7967356686944034,-0.07482648021521768,0.02390683535718298,-0.8285890113158093,1.2664593625764433,-1.283872852462752,-0.27331979690676966,0.7811827148380814,-0.5335917080856173,0.029942297800301294,-0.14982194310698038,-0.27177346475031133,-0.2591818817047971,-0.7197587469465803,1.0422615835469846,0.04686102462728237,-0.07684562163405317,1.1973934945688547,1.2854457832721378,1.6796143393881557,-2.1614315394175554,2.6242422858887666,-3.6216968992799283,2.7340884877279836,0.30587782657501283,1.7214667059974653,-2.150041359042034,-1.323306122972015,-4.962084464009514,2.583894885091418,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.408333333333333,1.0,0.0,1.0,0.0,2.760251972868231,0.014390728435451302,0.5848412323299703,0.9983574143245144,0.04110695668003211,-0.039488517612352066,-0.005774803717050567,0.7775118963847707,-0.06157791255532483,0.04994317043882674,-0.8238993639660008,1.344340614203428,-1.2781360403506974,-0.2626805741528001,0.7946731642132407,-0.5513921113449315,0.051967122607067255,-0.17984694208099503,-0.24970731799786583,-0.25664084115341634,-0.7052028746812051,1.0229090758954449,0.03623746451318227,-0.11899675596352782,1.2181998565076448,1.267599843800491,1.557885328376012,-2.1066669604053523,2.6620127118129324,-3.579879282886137,2.563205178388883,0.3046050395901456,1.769322538206708,-2.485990858377054,-1.219961182703812,-5.142564896871801,2.406733030195798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.416666666666666,1.0,0.0,1.0,0.0,2.766582671301695,0.013765760034065433,0.5857874353435872,0.9986580869102515,0.03793291748123372,-0.03350626356151157,-0.010974950305640493,0.7560653576632409,-0.04900137996157565,0.07529253949935431,-0.8182021349145462,1.4112064517462373,-1.2690089129546696,-0.25219313284342815,0.807147470311015,-0.5687028240923732,0.07430917633051683,-0.20948659782174933,-0.22905337844382995,-0.25410513104496135,-0.6902700379764685,1.0008284025740337,0.026528338248885508,-0.16255503658191653,1.2375057117387847,1.2492126864777604,1.4364186794423572,-2.044714663291707,2.7003965765811655,-3.5284393747300538,2.394300469478972,0.30465179924117014,1.8125868568964787,-2.804563496992998,-1.1056428372157154,-5.299209431663426,2.223770868050874,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.425,1.0,0.0,1.0,0.0,2.772720882273832,0.013174181042568265,0.5868600084466704,0.998892773955991,0.03478283340533426,-0.027268342728538158,-0.016118875510603606,0.7325959247782142,-0.03726354893997512,0.09966494599409532,-0.811733935511751,1.466897444380641,-1.2567591910033125,-0.2418603627115041,0.81861347553728,-0.5854706890664599,0.09697373221675334,-0.23865426499316258,-0.2098023101732163,-0.2515633111660635,-0.6749930937329305,0.9761663509455616,0.01781008389292035,-0.20731691315791825,1.2552627043084927,1.2306784696021629,1.3164931998926144,-1.976997497290216,2.739414652935692,-3.4657382257904557,2.2254334270125953,0.30606533147160386,1.8524459883139688,-3.1051691461514763,-0.9837685980276961,-5.431045294776273,2.0352474269503373,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.433333333333334,1.0,0.0,1.0,0.0,2.7786569274600925,0.012616213789424655,0.5880497864124404,0.9990569463130891,0.03166009330896413,-0.020822421354135336,-0.021196304611160854,0.7072998128838116,-0.026510177046162313,0.12276392086195594,-0.8047262104424686,1.5112444068071242,-1.2417103987740346,-0.23168182501672543,0.8290890236425585,-0.6016527823805434,0.11996608721277836,-0.2672489015849236,-0.19196282132695336,-0.2490040421871013,-0.6593959381712357,0.9490755834715091,0.010132194948423906,-0.2530724581615211,1.271426502187957,1.2124026509675712,1.199244381487241,-1.9045749331901196,2.7790419332152174,-3.3899468687099503,2.0542035545847632,0.30879751882901263,1.8898443719309266,-3.3869684878375073,-0.8573215958771,-5.537495052096907,1.8418433965042258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.441666666666666,1.0,0.0,1.0,0.0,2.784382393453884,0.012091189103879652,0.5893464954099942,0.9991473723647676,0.02856684857783238,-0.014216854211302386,-0.02619817920557788,0.6803753304664604,-0.01687035191876768,0.1442916740735427,-0.7974082367903186,1.5440786991734026,-1.2242202168636283,-0.22165365186204458,0.8386008818954007,-0.6172136046196286,0.1432910977703403,-0.29515337947166176,-0.17556558426347024,-0.24641668585224663,-0.6434956875340817,0.9197168761482698,0.0035213906283020164,-0.2996084973595334,1.2859600942502298,1.1948029230393042,1.0856889750463083,-1.8281978425315226,2.819188385410543,-3.299033625887721,1.8777392767054075,0.31274764078896733,1.9254457592094987,-3.6488359816998828,-0.728756636334522,-5.618345045093601,1.6445902319392758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.45,1.0,0.0,1.0,0.0,2.7898899547941833,0.011597538794386629,0.5907386688571842,0.9991621665353585,0.02550398711212879,-0.00750062890081059,-0.03111675272369461,0.6520267243095837,-0.008459374706013024,0.16395496987106503,-0.7900081327623454,1.565245912734737,-1.2046649629539505,-0.21176844296607036,0.8471838398933303,-0.6321227464227355,0.16695256030295408,-0.32223279534971894,-0.16066716671519657,-0.24379158150728517,-0.627305175517744,0.8882616504431777,-0.002013748990484795,-0.34671154224641443,1.2988363393869449,1.1783081078006097,0.9767426944321334,-1.7483633095743456,2.859681210230606,-3.19077876636082,1.6927158641460083,0.3177958434979511,1.9595968491309756,-3.8893241441215687,-0.5999738651263268,-5.673723821981324,1.4447789863177585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.458333333333334,1.0,0.0,1.0,0.0,2.795173230577956,0.01113277525415442,0.5922136000168322,0.9991008147801524,0.022471105701503378,-0.0007232484581417186,-0.03594563148352164,0.6224686632395193,-0.0013802111630448408,0.1814709144473959,-0.7827516996502771,1.5746191428221545,-1.1834278216465612,-0.2020151833987011,0.8548799268026029,-0.6463529931125344,0.19095245127418373,-0.3483330255776754,-0.1473536531943701,-0.2411200884606141,-0.6108357400485654,0.854894807079577,-0.006478173790470096,-0.3941705610592221,1.3100397440221925,1.1633534957596943,0.8732332650230346,-1.6653585948137062,2.9002467608061324,-3.0628111725512652,1.4954111588996588,0.32382661488655096,1.9922948959098785,-4.106617225693103,-0.472338749775501,-5.7040738117757295,1.2438671993501593,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.466666666666667,1.0,0.0,1.0,0.0,2.800226703608515,0.010693468154702604,0.5937573258115256,0.9989641748423936,0.019466492732665916,0.006065434441860286,-0.040679768278303115,0.5919270743440226,0.004277537652806494,0.19657609434948445,-0.775859124098266,1.5721178355277243,-1.1608962110583374,-0.19237921803674213,0.8617377276437143,-0.6598787230029639,0.21529000631638961,-0.37327964822557336,-0.13574364740020226,-0.23839447125917598,-0.5941002605859127,0.8198180300149593,-0.009886061486743146,-0.44177943910934325,1.3195674593761142,1.1503733576422859,0.7758969404254268,-1.579296892896147,2.9405005325248017,-2.9127102553863637,1.2818597388245812,0.3307387972010267,2.023163429524024,-4.29850928778198,-0.3467463576165689,-5.7101278976685,1.0433694444116481,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.475,1.0,1.0,1.0,0.0,2.8050456294144,0.010275250550935132,0.5953547044267632,0.998754446792155,0.016487135671108377,0.012815490896301018,-0.045315478187327965,0.5606488213104679,0.008439270383601219,0.20903172257167876,-0.7695396574898127,1.5577142198745548,-1.1374510177325796,-0.182842294104663,0.86781154247636,-0.6726746079941368,0.23996079348293042,-0.3968781965007815,-0.12598932421396042,-0.23560777517393033,-0.5771163495564984,0.783252985616544,-0.012257279750746244,-0.4893393593536971,1.3274292347623866,1.139785892545034,0.6853845299761785,-1.4901218517703296,2.9799230607098828,-2.7380925782479895,1.0480283930621501,0.33845127334967806,2.05143048450511,-4.462323936771456,-0.22368266926851,-5.692836118217548,0.8447634804138637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.483333333333333,1.0,1.0,1.0,0.0,2.8096261741044772,0.00987282186816972,0.5969894545307406,0.9984751160845543,0.013528757896517073,0.019477130287796737,-0.049850342681532885,0.5289142725603359,0.011048818893661112,0.21863114285249766,-0.7639864512688849,1.5314369525686555,-1.1134558174279714,-0.1733827864943249,0.8731608031433172,-0.6847140871991361,0.2649553906615543,-0.4189145245297065,-0.11827650751583309,-0.23275361670334802,-0.5599097525108275,0.7454459644021018,-0.013614105974551646,-0.5366600410796357,1.3336468507163453,1.1319752074930411,0.602255972868575,-1.397580461225758,3.017833217557574,-2.536728776083448,0.7900640050824879,0.34690313475918,2.0759173120202745,-4.594831978800114,-0.10329546220543113,-5.653268017494722,0.6493956905639298,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.491666666666667,1.0,1.0,1.0,0.0,2.813965607119712,0.009479996302672437,0.5986443180077705,0.9981308672295968,0.010585882489183195,0.026000995634044777,-0.05428313920047262,0.4970469346199875,0.012074251887608467,0.22521125887244803,-0.7593700314863927,1.4933778572473062,-1.0892515578210031,-0.16397604064644564,0.8778491420241696,-0.6959676156812328,0.29025801377555666,-0.4391570094355056,-0.11282159079591896,-0.22982605626127733,-0.5425177276894938,0.7066724526365421,-0.01397887078750343,-0.5835604929786091,1.3382524962717854,1.1272691937391621,0.526958142478553,-1.3011821835404769,3.05336393565436,-2.3067184342655978,0.5046362737389934,0.35604396372893976,2.095034462833103,-4.692194186518788,0.01451745616680919,-5.592517280166245,0.4583907439368762,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5,1.0,1.0,1.0,0.0,2.818062697240707,0.009089778409901748,0.6003012376619028,0.9977274716440929,0.007651941891899643,0.03233842431268279,-0.058613705094824595,0.3559473755602151,-0.008616987309848063,0.24472658494665975,-0.7774945891915925,1.3792761214118954,-1.1019581191726586,-0.1545949665986722,0.8819434388512931,-0.7064004569248107,0.315844789589127,-0.4573598317674665,-0.10986590295351653,-0.22681955064119902,-0.5249925114636091,0.667242727960122,-0.013372148371771492,-0.6298686624157398,1.3412866964486265,1.2190663108697792,0.33915767139416353,-1.3638836681282673,3.0586929638143268,-1.2119611028282495,-0.6449031384628537,0.3999003236453358,1.943721953195705,-4.6852089700911215,0.16485361982983318,-5.7923789825436955,0.4111535815741929,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.508333333333333,1.0,1.0,1.0,0.0,2.8200875682423097,0.008568711702333153,0.6023242952353671,0.9972736561219344,0.004493746881146844,0.037919221058290424,-0.06314422949480482,0.22301717254456188,-0.02743174762378926,0.24651896593178863,-0.7759921140585759,1.2882497041494805,-1.1047981446854198,-0.14365826879861598,0.883501769880739,-0.7186990101500372,0.34123622983912877,-0.4593563611493098,-0.12356997643696652,-0.2231610508671884,-0.5101223618028987,0.6285856364683567,-0.01123131045700621,-0.6801001426876707,1.3451050559646887,1.2794969419304147,0.29537637975865394,-1.7602622343573415,3.023081793296986,-0.15783939703544192,-1.816043320324889,0.4206088925873891,1.7640174385336727,-4.63663089090085,0.293658200515011,-5.975118550845129,0.3385780789381876,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.516666666666666,0.0,1.0,1.0,0.0,2.8219899961430683,0.008112884065068047,0.6041127685356498,0.9967694296727155,0.0015327318041956726,0.043493844204225945,-0.06750289119353814,0.2164466091208136,-0.021469421621558696,0.22486184169990578,-0.7414441075035618,1.2721039573366764,-1.0633485703289354,-0.13327001756649862,0.8868663785139373,-0.7357381608307664,0.36622948614407674,-0.45999048838472384,-0.140133291625598,-0.2198094024314092,-0.49559222082138127,0.5899655464451078,-0.008477845029854643,-0.729453971596492,1.3469296644309297,1.229148581573879,0.48745375070137875,-2.227079537008154,2.972078539038685,-0.03795106565766093,-1.998012547006397,0.3945940390633662,1.7509643682357545,-4.616977619364446,0.3752797831520208,-5.814365787252513,0.08332786165058614,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.525,0.0,1.0,1.0,0.0,2.823924462514717,0.007695721757907368,0.6057452677154771,0.9962257022339018,-0.001334481558655032,0.04891655790196802,-0.07169197814654403,0.22127034089408198,-0.016242595672955794,0.20988238040965426,-0.719855782028623,1.2244102316088397,-1.023232519761822,-0.123172459105718,0.8916259990590953,-0.7558170024335065,0.3907708721564402,-0.4599888789102708,-0.1568701855537398,-0.21658448354946563,-0.4809396223323028,0.5516360094789493,-0.00497664740447253,-0.7770062391418793,1.346493853658865,1.1995114649104572,0.6387021427446626,-2.5343745754659586,2.909171431727946,0.0332215897705157,-1.967187522632009,0.3799054521858253,1.7664344297368229,-4.551577381344067,0.4635107295478138,-5.579982917404028,-0.17699482601037708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.533333333333333,0.0,1.0,1.0,0.0,2.8259252455261477,0.007302461378061825,0.6072379484318449,0.9956532593938444,-0.004129202909214954,0.05407761062710223,-0.07571755919609464,0.22945438790867168,-0.011777673859256502,0.19596215492373906,-0.7003343971648167,1.15362675562823,-0.9845419840366201,-0.113278159817991,0.8975114142263484,-0.7779777370885324,0.41471567667287584,-0.4594367952218819,-0.1729197503361315,-0.21347764489497878,-0.4661516469924342,0.5141059234227067,-0.0007526662040577458,-0.8224536868865591,1.34397975066409,1.1779403790365515,0.7647626831799403,-2.7477949599237994,2.8286791295198523,0.10333221795612357,-1.8661157751531938,0.3648421785222816,1.7747028282393251,-4.419718540157364,0.5477158077815873,-5.318731243955281,-0.4120914108313789,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.541666666666666,0.0,1.0,1.0,0.0,2.8280067219767497,0.006923478495560187,0.6085858891653191,0.9950630288574054,-0.006861533260087,0.058896585110012105,-0.079584421998453,0.23987529289977205,-0.007814293909539874,0.18138721362845717,-0.6814711488224927,1.0649609690739208,-0.9471450897311359,-0.10354011945510881,0.904372043778761,-0.8016135850989031,0.4379155243151044,-0.45826667527766873,-0.18797211513962636,-0.21050378057409427,-0.4513612418616474,0.4779740338096599,0.00415194939188726,-0.8656517598744673,1.339625663478342,1.161254821514458,0.8757036702376486,-2.8962056516264356,2.730195950091112,0.1854675432201891,-1.7408076047380145,0.34774004818899973,1.763073817445292,-4.211939973167222,0.6268594764278245,-5.0433316301026965,-0.6185785851847347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.55,0.0,1.0,1.0,0.0,2.830181912179933,0.00655039237829806,0.6097785735182206,0.9944661152603961,-0.009539498717737079,0.06330656177532447,-0.08329719562685897,0.25265718579512053,-0.004194786238807396,0.16572492224383498,-0.6629860496407702,0.9608627487450005,-0.9110952768894511,-0.09392391279275003,0.9121064753969759,-0.8262478312823063,0.4602189425077277,-0.4563456695015454,-0.2019332104150984,-0.20768197742516212,-0.436767083368346,0.44390692386991965,0.009694991736405995,-0.9065092140549373,1.3336701075776778,1.148298490370573,0.9761168276387089,-2.991192039605135,2.613286692160487,0.2853957814715713,-1.6100740583508943,0.3282405137797828,1.724681106138709,-3.919701899509902,0.7010578950747547,-4.758602289093481,-0.796659071715915,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.558333333333334,0.0,1.0,1.0,0.0,2.832466159567237,0.006175098946002743,0.6108038737079651,0.9938736702553941,-0.012170604187699744,0.06724758002004193,-0.08686061793602044,0.26809593655441677,-0.0007945602805633362,0.1488536461714658,-0.6447706539877198,0.8426626854626674,-0.8764571079253657,-0.08440181128226593,0.9206406575727395,-0.8514667857589887,0.48147030251777917,-0.4535100789198092,-0.21480668277880793,-0.20503310534443123,-0.42261655675933557,0.4126456688178282,0.015836247643133173,-0.9449617980260253,1.3263480122830769,1.1383533563030375,1.0688786337775302,-3.039212879412976,2.477567028508484,0.40564910503684604,-1.4825148789013909,0.306142762613672,1.653900127228115,-3.5338376029436414,0.7705615491990875,-4.467454517914167,-0.9465150049072157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.566666666666666,0.0,1.0,1.0,0.0,2.834876945292099,0.005789597614908741,0.6116489381554826,0.9932966956464605,-0.014762195701322603,0.07066391949352654,-0.09027935798238401,0.2863995874880761,0.0024889672599024693,0.1306847660061637,-0.6267614721254142,0.7111577550623852,-0.8432439293455326,-0.07495135685436607,0.929921119293268,-0.8769013792725225,0.5015117263162024,-0.44958485108426466,-0.22664179173012158,-0.20257959804826758,-0.40920208124787744,0.3850096304875256,0.022537684223057453,-0.9809667893535068,1.3178948574958909,1.1308289389089374,1.1562884556045416,-3.0452266713378773,2.3229821395734565,0.5468494311236793,-1.3618289118353144,0.281254253404829,1.5456628295824837,-3.0453003772828846,0.8356342689413336,-4.172454555234853,-1.067717110995674,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.575,0.0,1.0,1.0,0.0,2.837432925884997,0.00538592578864575,0.612300147208509,0.9927458438927482,-0.017321658914955154,0.07350235929122947,-0.09355775085332181,0.30765555501666764,0.00572793734019806,0.11106447610416156,-0.6089379977955199,0.5667193782125821,-0.8114154719737912,-0.0655546623004503,0.9399121318328152,-0.90222056361462,0.5201866715106701,-0.44439592173441456,-0.2375038313093965,-0.20034553445435074,-0.3968555095996275,0.36189066252978014,0.029763485458822066,-1.0145027072799395,1.3085527270998156,1.1252366546882948,1.240387168143462,-3.013499605198333,2.1499496571826215,0.7084237819464834,-1.2486986719806092,0.2533753705276365,1.3960136054504557,-2.446509753643317,0.8965670908983578,-3.87622598584092,-1.158981250321589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.583333333333334,0.0,1.0,1.0,0.0,2.8401530018299743,0.00495598949917817,0.6127426115474409,0.992231247223689,-0.01985674417845155,0.0757103632157871,-0.09669954961267722,0.32967708699839976,0.008583325762016043,0.09368799255898685,-0.5938335360164395,0.4311148229181926,-0.7797137248966741,-0.05619741260956116,0.9505942387623257,-0.9271263726924948,0.5373442206025795,-0.43777778805182327,-0.24745343626313174,-0.1983566752061403,-0.3859351878237032,0.3442344679268037,0.03748046907136342,-1.0455705557841888,1.2985785033238644,1.1239321598317007,1.3141649066943817,-2.9762848771387906,1.9758280143889828,0.8681832299776382,-1.1565024098780396,0.22954246086118513,1.240001674314477,-1.8490435475407996,0.9533695270519396,-3.5560222415148246,-1.2703255298510818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.591666666666667,0.0,1.0,1.0,0.0,2.843029414624708,0.0044939395984608,0.6130303151961672,0.9917487944370658,-0.022377645870572886,0.0774169943737882,-0.09970044547742601,0.3491556701000291,0.010799673324591447,0.0841235511092254,-0.5837794597007224,0.3362061846168473,-0.7468345362946962,-0.046822459636588626,0.9618148802777216,-0.9518253115669332,0.5531171384171532,-0.42992620123478725,-0.2567788714740305,-0.196519826773331,-0.37618881502771956,0.3310732700707668,0.04565297757635439,-1.07376974463852,1.287380634935631,1.1290925173992619,1.365115213106145,-2.976602170070306,1.8265552861686585,0.9950612228171962,-1.1062746527194707,0.21844456752465435,1.140061898180852,-1.4377116963685932,1.0044019312372154,-3.18790146720354,-1.4689003249746246,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6,0.0,1.0,1.0,0.0,2.846043342422377,0.0040018594888370255,0.6132480738831186,0.9912859291410703,-0.024884544205218507,0.07883510426796835,-0.10255726480105255,0.3664333319316321,0.013101101826406628,0.08117561729942463,-0.5756107744069536,0.2757915601943041,-0.714000732295186,-0.03737920398624013,0.9733461589807615,-0.9767364088603332,0.5677868087053904,-0.42119343433820333,-0.2658913471417896,-0.19471593241406274,-0.36693415618735564,0.32027260632066046,0.05422050125865034,-1.0987022469042478,1.274096831240954,1.1368087025935505,1.3945992440264998,-3.0049789142829897,1.6994864998947157,1.0947273512058442,-1.0929791457706761,0.21452641089308222,1.100708001308186,-1.2082304786731402,1.046767878543253,-2.7971706777425442,-1.7286708222970004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.608333333333333,0.0,1.0,1.0,0.0,2.849194156058338,0.0034865716173781754,0.6134270828896576,0.9908387763472625,-0.027366393231490056,0.08003943237490421,-0.10527720131105957,0.38335135826770056,0.01602081432323582,0.08077737345069186,-0.5663933770202619,0.2275729006117877,-0.6825271841860889,-0.02787564792669612,0.9850582010114965,-1.0019082934716497,0.5814419134153984,-0.4116807453813565,-0.27499519057020844,-0.19294438659177962,-0.3578436816725831,0.3109360954262145,0.06309910888540861,-1.120389255934229,1.2585694545640143,1.143794590264473,1.4108157463923798,-3.032174018927334,1.5796171933836933,1.186107572327052,-1.0967253733861493,0.20983736599705538,1.0893590417525423,-1.0533488881961206,1.0796172229894163,-2.412224840034365,-1.9931559938581245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.616666666666667,0.0,1.0,1.0,0.0,2.852484874721698,0.002951939670131643,0.6135795279518286,0.9904068343928601,-0.029817201129102917,0.08105570734206187,-0.10786662705670165,0.4005019718469507,0.019368096419844286,0.08141477049966803,-0.556407798864857,0.1832800233324325,-0.6522547152893773,-0.01831596081516558,0.9968597547539678,-1.027272642509122,0.594113761928452,-0.40142497479941913,-0.28417010336489207,-0.19121864298077848,-0.3487781721581466,0.3027167915173918,0.07221412164180728,-1.1389059942381539,1.240877564676652,1.1506298798838661,1.4171764349761196,-3.0488020387315595,1.462259389712608,1.274527466461235,-1.1067965869559893,0.20366096499036923,1.0899764891654273,-0.9264849260221586,1.1042904661393826,-2.0379274168117822,-2.242902430597935,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.625,0.0,1.0,1.0,0.0,2.8559201477335394,0.002399225083983569,0.6137102622953495,0.9899910054263763,-0.03223482086064834,0.0818904591498065,-0.11032986090919454,0.41818745967248266,0.022944265528709276,0.08238475453698307,-0.545947432711898,0.1390233970372677,-0.6227475387695864,-0.008698483261965019,1.0086778082610985,-1.0527216607838423,0.6058129032439419,-0.39043862094033593,-0.29344180035280826,-0.18955003717527347,-0.33967740685315934,0.29549467999251183,0.08150394998773165,-1.154354712881092,1.221187747387382,1.157696692574095,1.4155192474923406,-3.05119454279585,1.3450781020621427,1.3624435351203346,-1.1180597540469572,0.19621733753989845,1.0947897586390054,-0.805232274028792,1.1221215824223263,-1.6773233971105261,-2.469280401553071,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.633333333333333,0.0,1.0,1.0,0.0,2.859505421898852,0.0018277086539199919,0.6138195033950563,0.9895932839396665,-0.034618750227464766,0.08253756708200534,-0.11266864931270303,0.4365150284066602,0.02662345740943152,0.0833450569372399,-0.5351896544453253,0.0930183704670477,-0.5936341682762853,0.0009789840610693369,1.0204517422121735,-1.078125884889053,0.6165317302961544,-0.37871758254741356,-0.302804432599008,-0.18794835402178017,-0.33053167618082985,0.2892962536169119,0.09091614801551272,-1.166861384189996,1.199722891317434,1.1650841253036124,1.4068632362826605,-3.0383815737833952,1.2270249927679666,1.45072048473059,-1.1277592535394854,0.18779652634293098,1.1001032788576781,-0.6791251074012938,1.1340102508268148,-1.3325368264283632,-2.6688026031418,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.641666666666666,0.0,1.0,1.0,0.0,2.863245730743748,0.0012360603748205964,0.6139067241497213,0.9892157540411805,-0.03696968373699718,0.08298903742261103,-0.11488365466867766,0.4553418267473539,0.030388385866233714,0.08435060163941982,-0.5243950063756477,0.04591603778558165,-0.5649658751987705,0.010719585493095185,1.0321255288658095,-1.1033613536802322,0.6262633197900747,-0.3662599461948261,-0.3122377879117997,-0.18642009506955795,-0.32134235220553137,0.28417592820249027,0.10040412083484523,-1.1765636599882314,1.1767077040016853,1.1729384809526309,1.3913049159714985,-3.0123132611182335,1.1093339873233488,1.5380298459504849,-1.134810615799693,0.17873578345516894,1.1068623117950838,-0.5515085957680566,1.1403471807329726,-1.004150777278805,-2.8442498705114216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.65,0.0,1.0,1.0,0.0,2.8671443672052277,0.000623973520094748,0.6139738730629877,0.9888595255924492,-0.039288730348972414,0.0832443064742185,-0.11697700523026457,0.4744951481688074,0.03424185949119615,0.08542780057498615,-0.5135334466217507,-0.0018372252047194337,-0.5368438763358676,0.020527958743613184,1.0436401574783651,-1.1283311059076901,0.6350206300848769,-0.35308375178157214,-0.32171794286233624,-0.18496942429752736,-0.3120839709842451,0.2801044436874443,0.10992193436106226,-1.183597230477976,1.1523187268089103,1.1810924149427973,1.3688325657587308,-2.9744989573913427,0.9928743809498353,1.6231807274567611,-1.1380364825646405,0.1690203202812307,1.1161537849247816,-0.425673804306973,1.1412166242626072,-0.6926177291432545,-2.9979213428181684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.658333333333333,0.0,1.0,1.0,0.0,2.8712037427698758,-9.003739145953689e-06,0.6140216582939947,0.9885259484707125,-0.04157605465673926,0.08329897205210335,-0.11895025066984831,0.49389423947450806,0.03814944436826405,0.08643265738250079,-0.5024299723275454,-0.05085714835951484,-0.5091588428203563,0.03040445907547514,1.0549394049617884,-1.1529363363034213,0.6428112261392386,-0.33920693407054675,-0.33120506262121036,-0.18360308973153744,-0.3027397891234517,0.27708136479737405,0.11942439790588869,-1.1881072888072857,1.1267423482880492,1.1891829599059678,1.339702341220761,-2.925042358268417,0.8773425927888945,1.7059613236360338,-1.1357088794229897,0.15850736003146015,1.1272090996283846,-0.2992171562528301,1.1368477226964364,-0.3987762387102656,-3.129304925793157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.666666666666666,0.0,1.0,1.0,0.0,2.8754253747536813,-0.0006633715470534666,0.6140503731208424,0.9882163646472979,-0.04383186536903649,0.0831472251224595,-0.12080448326122878,0.5147056795846621,0.0423474896469751,0.08823940484129755,-0.48902942075414,-0.11502376305255324,-0.4831326811782331,0.04034767474204598,1.0659685298320445,-1.1770818118788304,0.6496430066313584,-0.3246510630543049,-0.34064642418605273,-0.1823276349636697,-0.2932971526571054,0.27511749108323047,0.12886939640600287,-1.1902435011231471,1.1001636447123577,1.1944778317998406,1.300063715133013,-2.8331293857653295,0.7478884679792386,1.7878203633462775,-1.0910982830055072,0.1428881431014456,1.1354219417039713,-0.1327132406406939,1.1248505411587495,-0.1222042793198197,-3.217652240679265,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.675,0.0,1.0,1.0,0.0,2.879833801464459,-0.0013393947857371176,0.6140721194208865,0.9879408771804852,-0.046054467184542335,0.08266778201518954,-0.12254732581702725,0.5384544671566611,0.04690903432226931,0.09141733626209533,-0.4719203685332812,-0.2110953859701701,-0.45991598485674035,0.05031242293880581,1.0766071335473386,-1.2001551593995101,0.6552760339388926,-0.30940992801477546,-0.3493900340046355,-0.18122162067984668,-0.28381609009505215,0.2748694774533625,0.13817190692520118,-1.1901440267959493,1.0731148109433948,1.1947152535756722,1.2473359089749447,-2.6648353510910727,0.5882289135205809,1.8704469013250902,-0.960977923600882,0.11811400490958135,1.1322112033963172,0.12777844348490497,1.1040339266112387,0.13559092023089914,-3.2342840679568408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.683333333333334,0.0,1.0,1.0,0.0,2.88445683376851,-0.0020419249625423055,0.614095152921855,0.9877109794142608,-0.04825040059966385,0.08171493044448767,-0.12418369510110278,0.5641316904990286,0.05122565548420037,0.09429530717292763,-0.45411639422435346,-0.32883775990162006,-0.4378978868571124,0.06025959563497385,1.0867574616482936,-1.221495734397015,0.6594468218567014,-0.2934769480322201,-0.3566627229127341,-0.18035906821517667,-0.2744269659338334,0.2772471318079789,0.1472699618495235,-1.1879836524526322,1.0462589102464104,1.1930284456010627,1.1879856895817653,-2.45046053932386,0.41319153937166453,1.9511863262503104,-0.7722758956980591,0.08923506962314698,1.1165094555643917,0.46206876460900936,1.0795999413654644,0.36981811647169405,-3.189483130499182,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.691666666666666,0.0,1.0,1.0,0.0,2.8892956695115717,-0.0027786847737326795,0.6141116568927335,0.9875287311750747,-0.05043168033797312,0.08025521762614468,-0.12570899238260694,0.5897304463447535,0.05491714974885736,0.09546293982810101,-0.4377791322975504,-0.4502236936864231,-0.4154295234256382,0.07019623036549019,1.096406895040368,-1.2409961683882411,0.662162559595087,-0.2768901559106036,-0.36226129893293646,-0.1797343695194609,-0.26520759916897896,0.2825706235301793,0.15616523928129225,-1.183980391521421,1.0199567587684084,1.191800804998431,1.1269986580045277,-2.232577615550264,0.2440574490177494,2.025075658416219,-0.5685741554329748,0.061290307241257946,1.0975057053040949,0.8125787992050049,1.0550639012829521,0.5784065863218801,-3.110271495149459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7,0.0,1.0,1.0,0.0,2.8943406249631263,-0.0035537409789452214,0.6141146450621726,0.9873923308838457,-0.05260344713766936,0.07829406922399561,-0.12711923924181465,0.6143835134293057,0.05803923888752589,0.09474871294081447,-0.42224328942574363,-0.5697998915506282,-0.39197857779404693,0.0801229423849477,1.1055407726150357,-1.2587053613228527,0.6635144460069973,-0.25972568705861643,-0.366138958836617,-0.17933756309448903,-0.2561352041787652,0.29079011179472897,0.16485436020423938,-1.1783435426806008,0.9944210519939194,1.189931411435695,1.0638259853898013,-2.0218984180746657,0.08631990826367009,2.0892476093363976,-0.36075048804935617,0.034413937490580526,1.0834282525823935,1.1513002492469648,1.029963413615363,0.761972267439468,-3.006597689596151,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.708333333333334,0.0,1.0,1.0,0.0,2.8995790615714827,-0.004370226668435847,0.6140967020463348,0.987299355525225,-0.054766249279921485,0.07584241216548193,-0.12840782311185772,0.6378302815804169,0.060611905554605966,0.0921128236492322,-0.40697827753379,-0.6863652984988666,-0.36693727763382616,0.0900284205560851,1.114137328130198,-1.2746944753561522,0.6636012247328148,-0.24206936242166366,-0.3682738070670924,-0.1791608038946179,-0.24715046162593907,0.3017589610176287,0.17333129617488163,-1.1712808537307633,0.9698467972751392,1.1863943401154375,0.9975015203997462,-1.820087157672372,-0.0592192617899312,2.1424699032840913,-0.15040586279526869,0.008593784977997676,1.078299843591104,1.468015376045898,1.004227426657096,0.9212384901762727,-2.8807497069165566,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.716666666666667,0.0,1.0,1.0,0.0,2.9049975225954214,-0.0052305138930131695,0.6140515774298321,0.987246724312065,-0.05691909729211508,0.07291523342652192,-0.12956654827958186,0.6596525456596674,0.06286310939439987,0.08814376934200344,-0.39218500385704314,-0.7959240499365217,-0.3410183842296983,0.09989618138687166,1.1221657979550315,-1.289040147284059,0.6625274583104984,-0.2240178553372149,-0.36864572321653816,-0.17919433334485574,-0.23816354011891344,0.31525703472882727,0.18159148398185765,-1.1629895678443296,0.9464085568786434,1.1813347466634858,0.9259864388494821,-1.6305841546034427,-0.18878727489059166,2.181077933125033,0.06071979357278545,-0.016132509884485002,1.0898049823299822,1.739637679437609,0.9773902463326678,1.0602504382937994,-2.744387848180496,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.725,0.0,1.0,1.0,0.0,2.910579745459128,-0.006131016671575811,0.6139823963645181,0.9872276333207108,-0.05906017082821382,0.06955619461838393,-0.13059644719585606,0.6795400775533056,0.06502464501159094,0.08343225311126241,-0.377725178693607,-0.895173933769032,-0.31504114871579947,0.10971733300047654,1.129570435444356,-1.3018708779328763,0.6604547701513049,-0.20571806353624644,-0.36726181050754597,-0.1794296790593593,-0.2289870452537727,0.3307529223415889,0.18962113361375943,-1.1536100130925333,0.9241069998054643,1.1746492371959825,0.8474963026695548,-1.4554938148070784,-0.2999931344201556,2.2025438736068663,0.2707128752727561,-0.040129695616738514,1.1233917871416872,1.9485858395520883,0.9487275975715032,1.1829324854880552,-2.607954248360309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.733333333333333,0.0,1.0,1.0,0.0,2.916310241270957,-0.007067860177220901,0.6138921865758559,0.9872356726036996,-0.061184185932946,0.06580695294681001,-0.1314977835348825,0.6975727412111075,0.06713585988439744,0.07804430327394533,-0.3631275662536424,-0.9842739180986123,-0.28879173005245445,0.11947366867347137,1.1362907363328574,-1.3132983775308436,0.6575275727368292,-0.18730879077710047,-0.3641338419619922,-0.1798631616051347,-0.219440343666552,0.34773346538802874,0.19740361060804937,-1.1432740264195287,0.902942652739305,1.1656110330747027,0.7616729033502168,-1.2932950770688567,-0.39450246947610346,2.2078443746686998,0.4786349103582488,-0.0636303621797224,1.177466393115022,2.09802165678617,0.9182152701023744,1.29043018980866,-2.472002276553067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.741666666666667,0.0,1.0,1.0,0.0,2.9221746364700207,-0.008036769575148886,0.6137840306987626,0.9872646391670257,-0.06328527037639356,0.061709485017043646,-0.13227035292549302,0.7138446323964395,0.06924404647900462,0.07205518617812835,-0.348319065654101,-1.0631354925575631,-0.26213498588043427,0.12914418355172158,1.1422649838335264,-1.3234257958840239,0.6538797289933699,-0.1689206572917681,-0.35928456200157516,-0.180490185095688,-0.20936260536852233,0.3657199499546917,0.204924721448799,-1.132102843262389,0.8829069618629132,1.1539318254049435,0.668491468883956,-1.1430897175781807,-0.47358465921834014,2.1980969770691097,0.6828985662167952,-0.08649898223329622,1.249342005304136,2.1925617940817035,0.8861602780067873,1.383925552995886,-2.3376141076728563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.75,0.0,1.0,1.0,0.0,2.92815956838102,-0.009033150769328792,0.6136608049962035,0.9873086541556823,-0.06535719977711554,0.057306221448093234,-0.13291371204751837,0.7284388647380139,0.07138939479863614,0.06551840616605939,-0.3332568064941099,-1.1316829190046702,-0.23497435773476555,0.13870586576355376,1.1474322608142566,-1.3323498728238132,0.6496344950831902,-0.15067384115928198,-0.3527521991917123,-0.18130481130902298,-0.19861797691148306,0.3842761619560571,0.21217294857482916,-1.120208600536264,0.863982417611424,1.1393903285463176,0.5681283078457522,-1.0041674850556603,-0.5385511730786452,2.174671192714979,0.8814763096418343,-0.10856197352902996,1.3358523276375178,2.2375880401734216,0.8528837690151242,1.4644074755798764,-2.2057859191990836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.758333333333333,0.0,1.0,1.0,0.0,2.9342524875682994,-0.010052160278166553,0.6135249434760723,0.98736230767049,-0.06739349612733671,0.05263984804864383,-0.13342727033503818,0.7414206421787458,0.07360336802787444,0.058468496599497,-0.3179061663001735,-1.189897634536243,-0.20723060921407283,0.14813402236082687,1.151733788964289,-1.3401619206349515,0.6449038761087258,-0.13267613741318512,-0.34459329017421125,-0.18229955132117184,-0.18709839990789703,0.40301308395758206,0.2191394509323844,-1.1076960520027244,0.8461438632095951,1.1218020771830357,0.4608894553561038,-0.8759040501549542,-0.5907760331482037,2.139155597397822,1.072044540323931,-0.1296170530263524,1.4336211746770844,2.2388248769120325,0.8187049946507124,1.5326758581527677,-2.0773590842965683,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.766666666666666,0.0,1.0,1.0,0.0,2.9404414548165443,-0.011088777889453118,0.6133782691829316,0.9874207887803476,-0.06938751821270878,0.047753052654606755,-0.13381032905989906,0.7528346071609534,0.07590785867737505,0.05092822847554847,-0.3022370688751673,-1.2378210789936865,-0.17883452335905475,0.15740256704993769,1.1551137517368584,-1.3469482736597291,0.6397882278640534,-0.11502124786931828,-0.33488479018631345,-0.18346509552612886,-0.17472429066686498,0.421589909904591,0.2258180318190077,-1.0946640029003845,0.8293597662064812,1.1010149809757086,0.34715299604498817,-0.7577145629266857,-0.6316617499298438,2.0933269794048255,1.2520509079811892,-0.14942868759867445,1.5392814230631835,2.201947460607524,0.7839332963192497,1.589380305961181,-1.9530495576633244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.775,0.0,1.0,1.0,0.0,2.946714925125489,-0.01213786437009604,0.6132219069590101,0.9874799907368473,-0.07133252825685858,0.04268829411141168,-0.13406210446257574,0.762701693486225,0.07831529241221863,0.04291720445941383,-0.28621914572668244,-1.2755486216099676,-0.14972529908751409,0.16648427204375535,1.1575196722317054,-1.3527904966837296,0.6343761802765617,-0.0977873544231047,-0.32372577504119143,-0.18479002944781642,-0.16144370952351064,0.4397122083010408,0.23220500587103857,-1.0812063802367047,0.8135930372485397,1.0769047429110563,0.22731878828958774,-0.6490248584387492,-0.6626054083635613,2.0391153554271906,1.4187645748713285,-0.16772840096487107,1.6496170869115412,2.1323143832557867,0.7488550935109112,1.6350632971153622,-1.8335021137292062,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.783333333333333,0.0,1.0,1.0,0.0,2.9530615196225445,-0.013194198997578345,0.6130562774601622,0.9875365900420549,-0.07322173350437515,0.03748758669707798,-0.13418174955838308,0.7710224491892328,0.08082746881167675,0.03445795483120431,-0.2698259209010647,-1.303219806656543,-0.11985456363027044,0.17535097943178862,1.1589023982083515,-1.3577653546337083,0.6287448043913274,-0.08103599194553177,-0.311238713938458,-0.18626056887554338,-0.14723067255167263,0.4571284829588541,0.23829895004418955,-1.0674129479484618,0.7988013976443278,1.0493854384148944,0.10176684657881907,-0.5492381158841031,-0.684954343076869,1.9785937816780519,1.5692858041295832,-0.18420894365889617,1.7616431032356124,2.0348318866229933,0.7137329932260289,1.6701966637928667,-1.7193260269054766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.791666666666666,0.0,1.0,1.0,0.0,2.9594698705406968,-0.014252554159876571,0.6128811219614286,0.9875880888711474,-0.07504837483746933,0.03219234468028889,-0.13416840573782512,0.7777793325928392,0.08343439601587617,0.025580719960668172,-0.25303852123046067,-1.3210141346580422,-0.08919037951169043,0.18397402935067025,1.1592157863413524,-1.361944465281798,0.6229602745586139,-0.06481079139513717,-0.2975710116390317,-0.18786017850879802,-0.13208299113625044,0.4736260730780907,0.24410055575813905,-1.0533697691734902,0.7849376034667818,1.0184194727486158,-0.029174360712991287,-0.4577059964439023,-0.6999746798328599,1.9139628042576515,1.7005662278117573,-0.19852067775904647,1.8726329900074643,1.913923804869444,0.6788066386822444,1.6952084300575132,-1.6111152301892462,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8,0.0,1.0,1.0,0.0,2.965928429123093,-0.015307747550362773,0.6126955873069728,0.9876328354793766,-0.07680579111702822,0.026843197310196153,-0.13402125015138128,0.7829325542776546,0.08611395244153203,0.016329388481372567,-0.2358414777014053,-1.329159545788934,-0.057717947702658805,0.19232463731093222,1.158416158863135,-1.3653937879077733,0.6170785597274464,-0.049136611874570905,-0.2828959434749287,-0.18956924683819415,-0.1160201227182149,0.4890272130400115,0.24961239402222696,-1.0391594741141699,0.7719494771411737,0.9840138101475071,-0.16525702827033584,-0.37369974200960776,-0.7088487724449033,1.8474972072325861,1.8094997144293468,-0.2102772849368001,1.9801090556043388,1.7735756109313638,0.6442859684328328,1.7105040531080906,-1.509463209535855,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.808333333333334,0.0,1.0,1.0,0.0,2.972425242550765,-0.016354685465769875,0.6124983635252472,0.9876700213697368,-0.07848747661732568,0.02147975363991708,-0.1337395419664889,0.7864237297344527,0.08882778107746733,0.006761208486975298,-0.21823755075826123,-1.3279280143178513,-0.02544379190102311,0.20037425951979537,1.1564615025368468,-1.3681727943152915,0.6111461283511989,-0.034019171274594064,-0.26741268306520927,-0.19136479992441136,-0.09908117354284479,0.5031856665936134,0.2548386552320196,-1.0248613682883554,0.7597798833078508,0.9462471042049186,-0.30634463780880417,-0.2963807200781243,-0.7126379870883537,1.781522630247116,1.8929471230882189,-0.2190404616773195,2.081820099979999,1.6174061224551939,0.6103732373283499,1.7164759474202462,-1.4149595085194022,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.816666666666666,0.0,1.0,1.0,0.0,2.9789477893485654,-0.01738849302687396,0.6122877819974504,0.9876996381027506,-0.0800872558387694,0.016140464104250643,-0.13332269785177847,0.7881741203599961,0.09152033744131854,-0.0030501234811248987,-0.2002475058059371,-1.3176425585788614,0.007603695427028587,0.2080954223810142,1.153310414899655,-1.370333466575742,0.6052012599426405,-0.01944456803711897,-0.2513468247567917,-0.1932199211994828,-0.08132312105188158,0.5159839817475981,0.2597852813110328,-1.0105515416571658,0.7483668186658503,0.9052703179598864,-0.45242969351923623,-0.2247751143520782,-0.7122824199530986,1.7183525080093822,1.9478389124834212,-0.2243235841738611,2.1757185465612765,1.4487435900058698,0.5772649655209205,1.713514337837212,-1.3281879916863515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.825,0.0,1.0,1.0,0.0,2.98548271378393,-0.01840455565425314,0.6120620158798669,0.9877224290804435,-0.08159933869710038,0.010862324983640698,-0.13277033144352293,0.7880817940332695,0.09411874490926635,-0.013011757681749662,-0.18190835603475186,-1.2986840516609384,0.04137667537153862,0.21546209815246015,1.1489210076448595,-1.3719190462211595,0.5992747546853139,-0.005379962807771026,-0.23494870119048558,-0.19510352632730904,-0.06281919776682351,0.5273313930937112,0.2644597379907016,-0.9963027959910685,0.737643416779745,0.8613007129657718,-0.6036510307932419,-0.15775088151422256,-0.7086087569120214,1.6602040248638856,1.9713100114284394,-0.22559767209438253,2.2599364915208695,1.2706984793769904,0.5451520587951653,1.7020164731829968,-1.2497277175161758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.833333333333334,0.0,1.0,1.0,0.0,2.9920156025400924,-0.019398630960158925,0.611819234585571,0.9877398074742877,-0.08301847838012469,0.0056806823905101314,-0.13208230322689182,0.7860256286679863,0.09653169939263957,-0.023014114041126865,-0.16328317590287034,-1.2714813485697283,0.07580939764773284,0.22245043426377706,1.1432495643864342,-1.3729626479343124,0.5933911139941068,0.00822549904394579,-0.21849165789965105,-0.19697988240105585,-0.04365751285986709,0.5371622897372146,0.2688711489576189,-0.9821846004374492,0.727538023373914,0.8146318834267463,-0.7603039175760085,-0.09400956095628299,-0.7023128706239778,1.6091417291272332,1.9607669934765881,-0.22228469739565548,2.3327670358556682,1.0862151035943701,0.5142356894550926,1.682387911180132,-1.1801481863148355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.841666666666667,0.0,1.0,1.0,0.0,2.9985307621535364,-0.02036693353971114,0.6115577750422646,0.9877537623242864,-0.08434008696471622,0.0006290303449316649,-0.13125874853073632,0.7818679172480751,0.09865307529858486,-0.03293123067648215,-0.14445593493473669,-1.2365050017652157,0.11082435699394844,0.22903929620957258,1.1362492756852594,-1.3734858722370975,0.5875695401749143,0.021439066011016195,-0.2022692512992091,-0.1988082712839033,-0.023939747169229045,0.5454349781536174,0.27303033281495315,-0.9682629974713997,0.7179742803411644,0.765614652474968,-0.9228285872975928,-0.03209336400391116,-0.6939738641654403,1.5670058753553358,1.9139890387094205,-0.21377069839258966,2.392657317961011,0.8980962359802791,0.48472022524816416,1.65504495234168,-1.1200062753316442,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.85,0.0,1.0,1.0,0.0,3.0050110426366774,-0.021306206522087572,0.6112762932496395,0.987766754187289,-0.08556033450783222,-0.004261133754300172,-0.13030008142885638,0.7754615223341601,0.10036740199986774,-0.04262436563054803,-0.1255280986000823,-1.1942501980065146,0.1463405660825576,0.2352106784716932,1.1278690879314743,-1.3734975373343776,0.5818248829246828,0.034342263633201385,-0.18659184058782738,-0.20054272737426568,-0.00377989089385024,0.5521305603368859,0.2769498193784216,-0.9546005178984212,0.7088712521183866,0.7146357790567226,-1.091785264250058,0.02958776758308801,-0.6840639072664634,1.5353661694139047,1.8291762088934267,-0.19941823441412432,2.4382083432801,0.709001618141023,0.4568066634738377,1.6204109869404348,-1.0698384249855808,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.858333333333333,0.0,1.0,1.0,0.0,3.01143774564366,-0.022213766875464745,0.6109738785791556,0.9877816085088107,-0.08667621039656088,-0.008960366278598347,-0.12920696683697233,0.7666609773501617,0.10155839149330327,-0.05194789507474038,-0.10661137339793131,-1.145211938156537,0.18228439350851905,0.24094989252718463,1.118052854614425,-1.3729927427773794,0.5761684750538065,0.047028502167914606,-0.17178298115098534,-0.2021319085241387,0.016697058552105952,0.5572516717893011,0.2806437772061838,-0.9412561476890591,0.700143639924738,0.6620868283527381,-1.2678068390426445,0.09270262865851198,-0.6729640660813785,1.515508497847994,1.704938274140252,-0.1785852957846623,2.468184940466352,0.5214152018719931,0.4306786154901243,1.5789073322293357,-1.0301461431921743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.866666666666667,0.0,1.0,1.0,0.0,3.017790661544648,-0.02308751339035639,0.6106501108245761,0.987801415261636,-0.08768553088939175,-0.013441214771839793,-0.1279802540442407,0.7553379748439873,0.10212027529072995,-0.06075778758518371,-0.08781745646035943,-1.0898527416933559,0.218602544642107,0.24624545894423883,1.1067389739474303,-1.3719524935234024,0.5706088151566598,0.05960073859733462,-0.15817620268548985,-0.20351914897067672,0.03735652478058896,0.5608208137014191,0.284127796303257,-0.9282853956945989,0.6917021497318504,0.6083255100557527,-1.451529626492416,0.15891714450541716,-0.6609847902083543,1.5084652230297422,1.5402085457365784,-0.15064977305893845,2.4815367940561393,0.33757997180593025,0.4064821792148676,1.530938271399127,-1.0013725620957903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.875,0.0,1.0,1.0,0.0,3.024048281149735,-0.023925888738625216,0.6103050416259993,0.9878294432005422,-0.08858688019832774,-0.017678007331502828,-0.1266208666043465,0.7414013549765351,0.10197138131824733,-0.06892254022337316,-0.06924552764555048,-1.0285643809754688,0.2552765367767338,0.25108865102811384,1.0938606941728848,-1.370344123702289,0.5651520618836673,0.07216958921841031,-0.14611283872204237,-0.204642738075121,0.05805600511970827,0.5628780046527333,0.28741848019309824,-0.915740509832407,0.6834540972231415,0.5536322883439482,-1.6435035826238265,0.2297845761612205,-0.6483900978137669,1.5150922329602428,1.3340819514785447,-0.11503868498595693,2.477432573284123,0.15939930603054986,0.3843012854971717,1.4768708840247657,-0.98386804343503,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.883333333333333,0.0,1.0,1.0,0.0,3.0301882264007873,-0.024727790707330912,0.6099390861765611,0.9878690758149836,-0.08937947767865102,-0.02164647367851527,-0.1251296455506878,0.7248215810960116,0.10106913472964635,-0.07633618137498598,-0.050968462414474475,-0.9616258940573736,0.29233792784535717,0.2554726637499713,1.0793472475703665,-1.368122750587382,0.5598023135264304,0.08485227581333867,-0.13594150349418077,-0.20543646038710933,0.07864706766865767,0.5634774688019283,0.2905328177282099,-0.9036708809608528,0.6753043490079332,0.49816541407645465,-1.844085117232499,0.3066091773871138,-0.6354242958006173,1.536184857155681,1.0855975495208299,-0.0712611418800857,2.4553103764738102,-0.011696429614576065,0.364130603311289,1.4170108082014976,-0.977842736115031,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.891666666666666,0.0,1.0,1.0,0.0,3.036187941461702,-0.025492431908796367,0.6095528169576153,0.9879237738156841,-0.09006296948508354,-0.0253231876247293,-0.1235071448372266,0.7056596012980165,0.09942558045060226,-0.08293278795193165,-0.03301869887305278,-0.88916028343406,0.3298835727134277,0.2593914079293881,1.0631259422190098,-1.3652339707458372,0.554561656953657,0.097772670171005,-0.12801954623002854,-0.20583042377312244,0.09897784472760511,0.562683064159157,0.2934873235816197,-0.8921236630290487,0.667156718287891,0.4419171943755107,-2.0533167347246817,0.390285166357458,-0.6223399860971202,1.5726119446631717,0.7935087338005412,-0.018944206954807363,2.414948563656749,-0.1749200106511628,0.3458480928085561,1.3515749034295,-0.9833036245406745,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9,0.0,1.0,1.0,0.0,3.0420256811929054,-0.026219150834342547,0.6091466569425089,0.9879970660510485,-0.09063714758935254,-0.028684829938133975,-0.12175337975936118,0.6840996008573763,0.09712253031156633,-0.08870192882570338,-0.015374332026070914,-0.8110918093130846,0.3680901251896147,0.2628379503228965,1.0451253019916218,-1.3616179978147578,0.5494299804248117,0.1110624748910582,-0.12271635793083842,-0.20575219716968945,0.11889621039627016,0.5605621352910756,0.2962969526083525,-0.8811446325703611,0.6589159552655887,0.3846736305376386,-2.2707989154455754,0.4811115527848564,-0.6094260455347578,1.6254355141550254,0.45610367656651496,0.04212856310391477,2.3565601888426944,-0.33033589687120113,0.3291888579382385,1.2806607833256556,-0.9999739882691605,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.908333333333333,0.0,1.0,1.0,0.0,3.0476818237119834,-0.02690717912787684,0.6087204738781921,0.9880925673811152,-0.09110160085030534,-0.03170727686811936,-0.11986753189396483,0.6604838722023038,0.09432529487058078,-0.09370437054229128,0.0020544588954067022,-0.7271049993581731,0.4072265925847315,0.2658026351050154,1.0252792936282502,-1.3572154448660896,0.5444045561947444,0.12486326207358875,-0.12041781828725329,-0.20512828105472386,0.13825384787498335,0.5571774658779703,0.298973804547257,-0.8707793166402877,0.6504904851500717,0.3259793850108217,-2.4955629325394613,0.5785823938640844,-0.5970339182043327,1.6959743070499573,0.07114979322402598,0.11197539338720697,2.2809097407188563,-0.47910495133111297,0.3137215513111924,1.2042118733827523,-1.0271963044124521,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.916666666666666,0.0,1.0,1.0,0.0,3.0531405072061926,-0.02755537055607678,0.6082730803019307,0.9882140181873089,-0.09145530214875991,-0.034364523132268975,-0.1178476199035184,0.6370566274612616,0.09191923904867191,-0.09793968593946478,0.022015781990178646,-0.6517964838051797,0.4474122897224417,0.26827094007307684,1.0035325864492974,-1.351974957917023,0.5394794151214062,0.13932871334189081,-0.12153052804377132,-0.203885940613236,0.15691137274158443,0.5525770527688904,0.3015256451302057,-0.8610744346806486,0.6417960168587145,0.2576599331611029,-2.7218862443062286,0.7045300886000039,-0.5941940230453979,1.7675673284265243,-0.2952577898440356,0.18182324083377943,2.200621579849579,-0.6014127634930921,0.29637367667931014,1.1145012982306435,-1.0224604784719005,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.925,0.0,1.0,1.0,0.0,3.058421577259334,-0.028157931245069774,0.6078048075206298,0.9883624184879815,-0.09168949867721518,-0.036755240757081455,-0.11567980735585774,0.6171599216932183,0.0908346407996187,-0.10162587331149735,0.04743584877320271,-0.6065336731001921,0.4882947651106301,0.2700969673243671,0.9799145228898131,-1.3454732767227562,0.5345013224773211,0.15432271754736415,-0.12533878145132055,-0.2020978937074942,0.17493087420580966,0.5471539198197521,0.30391336582524553,-0.8522042950031103,0.63344947717554,0.170240529212472,-2.9376093243220947,0.886681822154638,-0.6116198901748304,1.8113166188314351,-0.537746340134983,0.23956232153060641,2.135328603250748,-0.6690773111813431,0.2745771933475438,0.999613761275393,-0.9217769936457221,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.933333333333334,0.0,1.0,1.0,0.0,3.0635669393064826,-0.028711562774176098,0.6073163848020527,0.9885350978223997,-0.09179949550951759,-0.03903246015756757,-0.11334760717197331,0.6012359121687414,0.09062965431316392,-0.10525515040009589,0.07586593363848144,-0.5859579256487885,0.5293796248640695,0.27110828222661804,0.9545724310439292,-1.337196927547779,0.529285750285159,0.16951732365574806,-0.13049296704602104,-0.19989323525439257,0.19250018279576356,0.5414257642492013,0.3061019316859981,-0.8444142053260587,0.6264330669646191,0.06938815732867476,-3.1352697659654205,1.1097806760280138,-0.6429129191780225,1.8279159373599996,-0.6669595171149156,0.2886062919576571,2.086468904589442,-0.6948947312048892,0.2514541883286858,0.8606991817046383,-0.7330371829338977,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.941666666666666,0.0,1.0,1.0,0.0,3.0686023487832963,-0.029219383848502773,0.6068065093327094,0.9887296176465632,-0.09179070236069023,-0.04124861191226527,-0.11084566822403678,0.5879388798208449,0.0906804906857303,-0.10901727193132321,0.10451760704911703,-0.5741455658489699,0.5704053722356762,0.27125343661317836,0.9276600267903894,-1.3269769321222893,0.5237861071576874,0.1847879831700308,-0.1364547734032358,-0.19728778884153325,0.20970535594896703,0.5355723409663373,0.30810426896405696,-0.8378593086413664,0.6212321907933084,-0.0363444278090963,-3.315213573159852,1.346645084071545,-0.6780255187763906,1.835597468901416,-0.7521591884889178,0.33702413295454925,2.046008325844235,-0.7072808679924592,0.22966985692172592,0.7055897079525386,-0.49776229182618037,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.95,0.0,1.0,1.0,0.0,3.0735457307480556,-0.029682906249228157,0.6062744033877416,0.9889442171575853,-0.09166520037671631,-0.0434229966305898,-0.10817240754548395,0.5766115377415522,0.09100247427281799,-0.11287469321720031,0.13341030242085825,-0.5655492495650412,0.6112718282666295,0.2705025417631331,0.899318871491265,-1.3147528428132533,0.5179853249722192,0.200110614804105,-0.14302895352083633,-0.19427616637181674,0.22660032155983414,0.5296377497826603,0.3099297626346935,-0.8326543768601831,0.6181370287675161,-0.14532720133668242,-3.478475927893805,1.5879980171281183,-0.7147570573437623,1.8429084518516166,-0.8221548947816021,0.3863406252891738,2.0113306076043815,-0.717680164079153,0.20871928470733603,0.5377713844284671,-0.23244392955984017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.958333333333334,0.0,1.0,1.0,0.0,3.078412240115409,-0.030102033113763235,0.6057191991289194,0.9891774785023252,-0.09142267105097535,-0.0455624230715555,-0.10532747431519224,0.5670428357049321,0.09167754131731667,-0.11684765326234364,0.16271982336175128,-0.5580335091287947,0.6519591442454117,0.2688313165909003,0.8696854279921593,-1.3005102985034873,0.5118734895352913,0.21550312403422442,-0.15015735498292918,-0.19084877842004702,0.24322753274237338,0.5236110048983514,0.3115829237091792,-0.8288964522342253,0.6173581253006444,-0.2570119832656115,-3.6254499746165214,1.8297105987839268,-0.7525553146683928,1.8534047454568543,-0.8883297005375368,0.4368436443329299,1.981663919234163,-0.731017184860594,0.18817695483568042,0.35898116255258516,0.05586491557402207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.966666666666667,0.0,1.0,1.0,0.0,3.08321667038131,-0.030475873963181743,0.6051397733805419,0.989428082034338,-0.09106163917529293,-0.04766874678841682,-0.10231099125825735,0.5592446816016534,0.09275835602371343,-0.12098735714327633,0.19254633141577196,-0.5507357056982979,0.692447995306011,0.26621900870870624,0.8388947052476563,-1.2842576661668546,0.5054427363944126,0.23100069389505257,-0.15783444852979528,-0.1869954389662679,0.2596280535470702,0.5174541300349838,0.3130660452152882,-0.8266713574843066,0.6190681106937498,-0.3709742464436516,-3.7562383060143945,2.069597402391441,-0.7912446331754797,1.8685377148593514,-0.9549093084802024,0.4885475342819867,1.9571453395541079,-0.7499791871238215,0.16787913068737614,0.17050454955010785,0.3634492568589942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.975,0.0,1.0,1.0,1.0,3.087974550633463,-0.030803241742929328,0.6045347450172672,0.9896946807238182,-0.09058011761659733,-0.04974173319820875,-0.09912336363360068,0.5533289012638553,0.09426953063452231,-0.12535694679440457,0.22293361263940858,-0.5432803350134101,0.7327015740651507,0.2626484124835061,0.8070814562252527,-1.26601700846363,0.49868607898236667,0.24664541928188027,-0.16607251012426588,-0.18270631951534724,0.27584662173494184,0.5111113517796211,0.3143809092206355,-0.8260547097417235,0.623415612914961,-0.48677561986408824,-3.8708789589907178,2.30622413664479,-0.8307297336050878,1.8888563439900974,-1.0231394991932907,0.5413911998050702,1.938359205705097,-0.7765352461199004,0.14781976772275773,-0.026386377505727143,0.6876226803657004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.983333333333333,0.0,1.0,1.0,1.0,3.0927025744793766,-0.031082885892646392,0.603902509671931,0.989975841560887,-0.08997589928519205,-0.05178016172657001,-0.0957652626230767,0.5494402064681602,0.09621415065877217,-0.13002231854642965,0.2538950863106648,-0.5354798993799507,0.7726651825768887,0.25810608171097144,0.7743800559311443,-1.2458205972227747,0.4915972408343278,0.2624816329615542,-0.17488677351635012,-0.17797225230285008,0.2919340403088218,0.5045118759329854,0.3155297080106675,-0.8271111304427354,0.6305284886998448,-0.6039534032311966,-3.9694722321721554,2.5384540353568052,-0.8709173660678371,1.9144723356107163,-1.0929587710673834,0.5952931527593236,1.9260825780515511,-0.8124338324257641,0.12808304441295548,-0.23029767885795138,1.0258421267160345,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.991666666666667,0.0,1.0,1.0,1.0,3.0974186391718357,-0.03131359471813802,0.6032412849651413,0.9902700194783673,-0.08924669291118924,-0.053782251910137295,-0.09223765882913842,0.5477153227998361,0.09857520761795205,-0.135046390454504,0.28542628478346316,-0.5272192609476977,0.812269064080242,0.25258252242965284,0.7409235856890501,-1.2237094412076832,0.4841707895479027,0.2785532915420589,-0.1842884896420556,-0.17278476696935852,0.30794799803580103,0.49757078790585835,0.3165156266275181,-0.829893004389356,0.6405129816935615,-0.7220216355364861,-4.052261022023489,2.7652951178258123,-0.9116910086785635,1.9452204599520895,-1.163659385906037,0.6501785184572034,1.921127826323168,-0.8593287185264942,0.10881755024158668,-0.43969399657773023,1.3753824866801367,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.0,0.0,1.0,1.0,1.0,3.1021416178604735,-0.03149424439461809,0.6025491647213553,0.9905755462942635,-0.0883902015669788,-0.0557458254526544,-0.08854186747220674,0.5397335677256333,0.09941593848526921,-0.13566098566998966,0.3172753067008527,-0.5099347267679722,0.844983453525861,0.24607238778536333,0.7068423722307529,-1.1997323452590112,0.4764023906896851,0.2949019739607557,-0.19428109661478407,-0.16713594366189669,0.32395283741420794,0.4901897306242105,0.31734333384802726,-0.8344393637190309,0.6534515301445137,-0.8309033719285724,-4.152863671376859,3.00680477945805,-0.9478290023072067,1.941671219438067,-1.2022454755060015,0.7322314390945117,1.5631262267416468,-0.48040114391392663,0.0012622438800613534,-0.5758893769311246,2.5108211957660043,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.008333333333333,0.0,1.0,1.0,1.0,3.106738542564338,-0.03161609433691238,0.6018901355538434,0.9908899763507857,-0.08739701970426646,-0.057602915463208164,-0.08473912818150604,0.5520016524848921,0.10508269215851258,-0.1451021748286236,0.3530313344145384,-0.5186297817092818,0.877102517024311,0.23873413289750997,0.6717091911661025,-1.1735960282167157,0.46837363950944927,0.31091447853269333,-0.2043259142338223,-0.16058090965111665,0.3340001018148285,0.48956410217395957,0.3165366640255191,-0.8394911606715414,0.6823600016229949,-0.9538238050639386,-4.167855997852201,3.2303912856914785,-0.9945418818081553,1.9968117454594536,-1.2356053278293289,0.7940441679594906,1.0533182833108612,0.24369393399675476,-0.10456799339021994,-0.6215080821231123,3.600506702369919,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.016666666666666,0.0,1.0,0.0,1.0,3.11170046859975,-0.03168961662894664,0.6010840551576899,0.9912019314793902,-0.0862618996722179,-0.059638428117454394,-0.08075192622164858,0.5883311437007337,0.11583420157698242,-0.16616601842612433,0.3903744322219624,-0.5550009431985851,0.9116925215242129,0.23017532436763102,0.6373781055998828,-1.1458924904974865,0.4598266926595492,0.32818216971841324,-0.21487451874527289,-0.15390187419590518,0.3415081421360556,0.4942512961908231,0.31560053395819027,-0.8447978317544161,0.7134599751840124,-1.0906245877990806,-4.081129003967059,3.41632199157476,-1.0501273329856065,2.1263899708971237,-1.2776722076179015,0.8114052229739049,0.7494294529559375,0.8520312460009627,-0.11721629107290243,-0.6284244976467246,3.800429331659072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.025,0.0,1.0,0.0,1.0,3.1169641845114593,-0.03170850455986217,0.6001659619825137,0.9915073183779172,-0.08499883781182106,-0.061794147406939545,-0.07661539349354163,0.6179134876184751,0.12447019013235418,-0.18367182657881193,0.42438793343199,-0.5788225586228387,0.9409673689880359,0.22055705643419196,0.6036903744333182,-1.1166573283571364,0.4508715172930225,0.3463543113809787,-0.22562045102745398,-0.14705748926821824,0.34649059269742744,0.5037646229406423,0.31458305917430407,-0.8499649022989868,0.7457004904839795,-1.211205394937821,-4.013170545830116,3.597987970740175,-1.0950793678607162,2.2201905418635826,-1.2922159508354698,0.8342590099468217,0.4462189000644423,1.4079745262342613,-0.12534468736681847,-0.5995953481728278,3.9010972730006643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.033333333333333,0.0,1.0,0.0,1.0,3.1224716881241306,-0.03167087544328975,0.5991565517563932,0.9918044067493402,-0.0836093759052926,-0.06402500623200962,-0.07234839037943107,0.6415058933645339,0.13115329207228343,-0.19877246828465397,0.45703495158980234,-0.5924159290552685,0.967410077781018,0.209988567785334,0.5704919298360476,-1.0859260243184836,0.44157536986187057,0.3651853454161396,-0.23641145125919738,-0.13999755736345815,0.34894512380379633,0.5177175382947274,0.31351145583540996,-0.8547910875572966,0.7784782630673568,-1.3199168934820888,-3.9625218704593035,3.7753194118403144,-1.1328693588183891,2.288449482062278,-1.2932674405867957,0.8633293358937277,0.1448637918901563,1.9166721513740348,-0.13025426014898422,-0.5504988161639401,3.9384585613068324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.041666666666666,0.0,1.0,0.0,1.0,3.128174125482263,-0.03157610315776047,0.5980714992252151,0.9920921938450062,-0.08209480243877655,-0.06629156433642092,-0.06796286355324302,0.6601641611306339,0.13615707675795732,-0.21186419156789377,0.4885334682260674,-0.5967286111400693,0.9920879833655954,0.19855844154282382,0.5376483432589965,-1.0537353381597978,0.431990361312716,0.3844951360820167,-0.24717490837056724,-0.13266866700332278,0.34890498922893004,0.5357091587968762,0.31241215483848767,-0.8591398825683858,0.81134146650576,-1.4187162104271689,-3.9269560736998432,3.948119147418616,-1.1649510567953159,2.337715133236068,-1.2886250062856142,0.8985795128058022,-0.15040031775375273,2.3748148161063987,-0.13221695786549859,-0.487150455205021,3.92695373963704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.05,0.0,1.0,0.0,1.0,3.1340318477453843,-0.03142411032491123,0.5969249327446883,0.9923702025610556,-0.0804566858076936,-0.0685559593050006,-0.06346797004626907,0.6749820611265778,0.13973199361346292,-0.22309014045270212,0.5189400520281344,-0.5920155810894194,1.0154389459550082,0.18634329761154786,0.5050426619410502,-1.0201240385281733,0.422159518915282,0.4041472643034074,-0.25788853469729095,-0.1250212321500281,0.3464384518412338,0.5572977852298341,0.311307839870985,-0.8629102618107136,0.8439274920613075,-1.5088316612948567,-3.9043051302980314,4.115871295776028,-1.1922564586214146,2.372705286845115,-1.2835230152090389,0.9393009897567492,-0.43586918472033,2.777916894345296,-0.13174048542854977,-0.41306871734753337,3.8757685331262715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.058333333333334,0.0,1.0,0.0,1.0,3.1400144443240796,-0.03121523830809671,0.5957303884802371,0.9926384170157129,-0.07869690332720125,-0.07078059352670993,-0.05887170841448291,0.6870505493293685,0.14209182259232833,-0.2325408578963185,0.5482726487704133,-0.5783128821847153,1.0376456310699742,0.17341124718790954,0.4725765910873626,-0.9851374832301973,0.41211942033569243,0.42404022419610193,-0.2685669586240512,-0.11701365050737696,0.34164050281692454,0.5820077737026311,0.31021648008134517,-0.8660243611908447,0.8759376087245312,-1.591189041278201,-3.8922572450208994,4.277479039167376,-1.2154675232608247,2.3972617043799596,-1.281805252478646,0.9843933727235424,-0.7089565047939883,3.122925971596149,-0.12938126034718223,-0.3306040593128734,3.791705565493859,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.066666666666666,0.0,1.0,0.0,1.0,3.146100445317243,-0.03095024848315483,0.5945009976208216,0.9928972449420875,-0.0768176795844753,-0.07292780713782905,-0.054181547009157845,0.697409667489017,0.14340595616911306,-0.24030953053999154,0.576527013457965,-0.5556111200305615,1.0587864420859794,0.15982348025691118,0.44017170785736853,-0.9488327212087171,0.4019017268609349,0.4441016260430734,-0.27925195557193505,-0.10861467593796907,0.3346225100946673,0.6093465514231032,0.3091514855318653,-0.8684203294659282,0.9071225848195384,-1.6665593166169845,-3.8884043210592347,4.431272853001564,-1.2351003510522718,2.414555619496176,-1.2861964133958692,1.0325277538194213,-0.9682719125019579,3.4088596473585087,-0.1256440082704613,-0.24137538307241968,3.680069183789305,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.075,0.0,1.0,0.0,1.0,3.1522766799092183,-0.030630373163222025,0.5932494599230569,0.9931474762755407,-0.07482166617472365,-0.07495990006057156,-0.04940467611506093,0.7069811861829176,0.14379174547363144,-0.24649483624242674,0.6036800774902731,-0.5239217222362741,1.0788969696554191,0.14563525857762646,0.40776985240304203,-0.9112829356801713,0.39153441448482124,0.46428281785437153,-0.2900035655139824,-0.0998048546103866,0.3255026376085586,0.6388221011586063,0.3081224132768375,-0.8700472842420517,0.9372720951210196,-1.7356130753204875,-3.8904121758804746,4.575165324748747,-1.2515366500505065,2.42704900461742,-1.2983574526462494,1.0822434779995103,-1.2135531442347391,3.6367513747970803,-0.12093676776573803,-0.1464877682189325,3.544942246947429,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.083333333333334,0.0,1.0,0.0,1.0,3.1585369010809345,-0.030257360349148055,0.5919880160674924,0.9933902311138507,-0.0727120165686669,-0.07683931135726944,-0.04454808194678936,0.716519338445644,0.14331170716233882,-0.25118920895590435,0.6296871026149039,-0.4832972362830868,1.0979922486040905,0.1308965956682364,0.3753315049260273,-0.872579965796238,0.38104278269342645,0.48455244278669707,-0.30089124644937254,-0.09057728463797723,0.31439662435742166,0.6699590743363879,0.30713587273576964,-0.870861792269577,0.9662049556019956,-1.7989372682893956,-3.8961638321054526,4.706819974377878,-1.2650338835605013,2.4364605866193556,-1.3189718019137786,1.1320065555873648,-1.4454726678531449,3.8092568287124307,-0.115555091131061,-0.04668740266805527,3.389321647352186,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.091666666666667,0.0,1.0,0.0,1.0,3.1648803442857667,-0.02983354368167416,0.5907284387515074,0.9936268925722113,-0.0704925036378089,-0.07852879329926729,-0.03961860563038532,0.7266103971164197,0.14197824638916726,-0.25446841976788187,0.654478569104235,-0.4338314441106754,1.1160668402241238,0.1156529707728032,0.3428337885346178,-0.8328359361072066,0.37045051642547955,0.5048904942980275,-0.311986428879212,-0.08093807868393052,0.30141142647767283,0.7023097149704801,0.3061964950913198,-0.8708254076198526,0.993760789243556,-1.8570394141987658,-3.903766646900916,4.823738112630305,-1.2757304754233456,2.4438317916340013,-1.347895008853851,1.1802277873077127,-1.6652855838437597,3.9300293566747913,-0.10969171056660953,0.05752874017582288,3.2152861959321255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1,0.0,1.0,0.0,1.0,3.1713103672705043,-0.02936190302894869,0.5894820868766412,0.9938590285870851,-0.06816761037910693,-0.07999159034473184,-0.03462302219909117,0.7376367906768799,0.13976071121670303,-0.2563722421980695,0.6779676447417198,-0.3756601784180277,1.1331044553438678,0.09994593876492362,0.3102687274776787,-0.7921843305857329,0.35978060810303736,0.5252829726472638,-0.3233561632636034,-0.07090682151618202,0.28664186462669233,0.7354595636143011,0.3053076775596595,-0.8699029799333133,1.019793058867531,-1.9103756729876376,-3.9116424378110515,4.923401664903282,-1.2836755363139862,2.4495307509962694,-1.384305444212034,1.225299009689,-1.8746866828296116,4.00335617327789,-0.10346290344024123,0.16578029445515785,3.024073832947183,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.108333333333333,0.0,1.0,0.0,1.0,3.177832417187467,-0.02884607005783265,0.5882600187587623,0.9940883090735054,-0.06574258303829934,-0.0811916176831606,-0.02956801917052214,0.7497910306564585,0.1365962586340516,-0.2568950675630509,0.7000514934130248,-0.3089544754190399,1.1490747834595747,0.08381337622300924,0.27763974790443363,-0.7507792416921519,0.3490559241535798,0.545716006814632,-0.3350581862827459,-0.06051642852244719,0.27016664843051263,0.769032317858445,0.3044721133673158,-0.8680624027122666,1.0441620197926758,-1.9593605703694004,-3.918499120001902,5.003333648388846,-1.2888448586511903,2.4533567493399056,-1.426891469120899,1.2656117091285464,-2.0755651126254326,4.033720313433163,-0.09693857996281974,0.27771610157244275,2.8162262799628968,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.116666666666667,0.0,1.0,0.0,1.0,3.1844529167733584,-0.02829037229033164,0.5870731350960515,0.9943164112941966,-0.06322349824508788,-0.08209358536870073,-0.024460309538526192,0.7631173377091183,0.1324032598277407,-0.25598312287286434,0.7206163134174836,-0.23391534039391426,1.1639252984163846,0.06728992925876695,0.24496040881098033,-0.7087954364459188,0.33829986045885085,0.5661722518029288,-0.3471376877489517,-0.04981329303070625,0.2520491127496018,0.8026882355048538,0.30369203456027916,-0.8652743782404393,1.0667301635335793,-2.0043772389700245,-3.9232142944064243,5.061081832837315,-1.2911602719777704,2.454688876633826,-1.4740242559369066,1.2995614012151875,-2.269728294423642,4.025383956297053,-0.09018209546456046,0.3929648294445487,2.591766670088429,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.125,0.0,1.0,0.0,1.0,3.191177945800381,-0.02769981172521083,0.5859323648446818,0.9945449236895382,-0.060617260435523915,-0.08266313879869114,-0.0193066823981395,0.7775127109430889,0.1270938077940148,-0.253526966515778,0.7395481753221029,-0.15077450296394027,1.1775863873982297,0.050407088906842173,0.2122528429976599,-0.66642787781153,0.3275365862872836,0.5866274880918624,-0.3596252572150277,-0.0388570718355274,0.23233784352345194,0.8361220504633958,0.30296907844290644,-0.8615129888881908,1.0873581309608162,-2.0458036482591213,-3.924829105630012,5.094267269927742,-1.2905237890798171,2.452554202668107,-1.5239014883117852,1.3255851126584246,-2.4588440578244333,3.9822656971701798,-0.0832896136581962,0.5110679833841858,2.3502887502278957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.133333333333333,0.0,1.0,0.0,1.0,3.1980121556054635,-0.02708002881408057,0.5848488765506348,0.9947752448982925,-0.05793157707662289,-0.08286698703381047,-0.014114070122373241,0.7927480210829241,0.12058537453890708,-0.24936033579246045,0.7567395048277683,-0.05979332061381478,1.1899699875801584,0.033193201787781595,0.17954659038381346,-0.6238909819471231,0.3167911306408539,0.6070481551807306,-0.37253604588748146,-0.027720207819732508,0.2110683784525279,0.8690593304576901,0.30230387433264255,-0.8567565785173695,1.1059016427040442,-2.0840242414198835,-3.9225169903604313,5.100626289825878,-1.2868404638114483,2.445725192354311,-1.57468065122368,1.3421976247977505,-2.6443493210060467,3.9078091202659304,-0.0764241312775571,0.631446095342636,2.0910634499881464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.141666666666666,0.0,1.0,0.0,1.0,3.2049578180595524,-0.02643723844268772,0.5838343141774662,0.9950084799798227,-0.05517489617945258,-0.08267303319584006,-0.008889610930362212,0.8084796881865371,0.11281201295742174,-0.24325981537652988,0.7720973766328917,0.03873676968788984,1.2009720376853432,0.01567335154984412,0.14687755982498604,-0.5814174396477654,0.30608924522375947,0.6273895746311009,-0.38586993473542236,-0.016487111422231557,0.18826535484001783,0.901252202467828,0.3016953429216138,-0.8509888872991469,1.1222091884606187,-2.119445779573021,-3.915591510229799,5.078087182559705,-1.2800450498990834,2.4327953778185063,-1.624597122836684,1.34803760246552,-2.8274197508550074,3.804937778245905,-0.06984684610962244,0.7533725424543225,1.8131184393281785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.15,0.0,1.0,0.0,1.0,3.212013952205667,-0.025778138557551348,0.5829010515763172,0.9952453350983208,-0.052356310534568164,-0.08205050307923553,-0.003640694592081666,0.824255589460682,0.10373473379346684,-0.23494648685071873,0.785550828780073,0.1444954568741336,1.2104780869434781,-0.0021308945384354194,0.11428673187998348,-0.539256195571128,0.2954570464758692,0.6475947448110391,-0.3996126646014262,-0.005252914445307175,0.16394471593827778,0.9324749600951219,0.3011397602308155,-0.8442003694764642,1.1361202833595139,-2.15251431572515,-3.903559832742313,5.024898226225865,-1.270127930843179,2.4122452776615555,-1.6720820298034356,1.3419217176510971,-3.0089765296966644,3.6760553855369382,-0.0639412368702641,0.8759566230517368,1.5152974718882684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.158333333333333,0.0,1.0,0.0,1.0,3.2191754941378874,-0.02510979506375387,0.5820624574095196,0.9954860121634117,-0.049485435223461195,-0.08097005987254408,0.001625020732425768,0.8395181615765016,0.09335103108168433,-0.22409059757247546,0.7970565934529874,0.2571386766582089,1.21837208252187,-0.02020188704557505,0.08181822927928083,-0.4976691358773343,0.28492044637637315,0.6675936625921268,-0.4137379685654796,0.005878250538620059,0.1381157460117401,0.962519792226777,0.30062965564044275,-0.8363896102482846,1.1474641463254232,-2.1837342090686325,-3.886217238109647,4.939806530959964,-1.2571590984139414,2.382507730931629,-1.7158889482983297,1.322901637015319,-3.18971161984002,3.523061308538291,-0.059227372383491295,0.9981389505849148,1.1963042841116156,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.166666666666666,0.0,1.0,0.0,1.0,3.2264325065717836,-0.024439509170706142,0.581333157073166,0.9957301051291245,-0.0465722680793681,-0.07940388321640453,0.006899631587856854,0.853620745087194,0.08156804920195188,-0.20861904548969334,0.8068458688474567,0.38411617838003376,1.225138539356734,-0.0385264646895793,0.04951644457815603,-0.4569260867217953,0.2745043948356368,0.6873032069932329,-0.4282108137397317,0.01679544617161481,0.11078285560761078,0.9911926485707601,0.3001526373577573,-0.8275647203000489,1.1560586880947075,-2.2146175557419503,-3.867499053414647,4.812458794507371,-1.2416065196194448,2.3404442347267196,-1.7658885704255345,1.2909972966118937,-3.375688725480916,3.3311275013177832,-0.058643455753703,1.123222113455291,0.8329827907557785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.175,0.0,1.0,0.0,1.0,3.233765174056651,-0.023774316210709894,0.5807573947036159,0.9959815559916572,-0.043626199488209894,-0.07726065430408612,0.012177279645574553,0.8654726930217195,0.06834677727526346,-0.18687016924511177,0.8148977859039876,0.5306353603432663,1.2313593292659952,-0.05711217964127422,0.01735991172237005,-0.41746148930221144,0.26422700438271574,0.7066010665042388,-0.4431694447392385,0.027394872148818288,0.08185426725372483,1.0180385839154067,0.29965226471121437,-0.8176692416906964,1.1613471928380195,-2.2470036109609555,-3.851083718531008,4.635270883639565,-1.2239232751740659,2.2835017779228206,-1.8304625964222132,1.2460210814039314,-3.5722506421913374,3.0910704326602634,-0.06445421450081756,1.2518188606364533,0.4084424585934787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.183333333333334,0.0,1.0,0.0,1.0,3.2411432474446986,-0.023122735348784243,0.5803711742680335,0.9962412351038319,-0.0406587687194631,-0.07446912301028216,0.017453243925310166,0.8737506444534866,0.05401359229822375,-0.16117133303264541,0.82069350303691,0.6836393494396722,1.2362151450673076,-0.07597652487226189,-0.014668284064027436,-0.3796715719944692,0.2541056735827357,0.7253615699586132,-0.4587185236801019,0.03756246419501367,0.05124534490442183,1.0427104891150978,0.29907840044941036,-0.8067010726227747,1.1628660624045988,-2.280769940413527,-3.8331806030125675,4.4256635114545215,-1.2039898731607719,2.2129024932731034,-1.893859924019633,1.1865053307866562,-3.771441271883372,2.830995832576142,-0.07367542995518117,1.3738017041638306,-0.04356411565613616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.191666666666666,0.0,1.0,0.0,1.0,3.2485338263499286,-0.02249364427362687,0.5801747057226474,0.9965019800593475,-0.03768269732354983,-0.07104668085426932,0.02271975352651414,0.8777987938376866,0.03904635949121787,-0.13395496665517362,0.8240751933520614,0.8297316991010375,1.2384263145264733,-0.09512501198149967,-0.04652643166117275,-0.3437004307779694,0.24416050649670287,0.7434827747254572,-0.4747337768062324,0.04716996099526256,0.018996912722335293,1.0652218477916757,0.298424340878628,-0.7947725466212993,1.1606211242437505,-2.3149801329976167,-3.8103420296954393,4.205583029634128,-1.1819193333158606,2.1300415713998277,-1.9384033354450991,1.1118655352626237,-3.962273573002924,2.575797362294261,-0.08361202910347143,1.4815814273790862,-0.488661606438634,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2,0.0,1.0,0.0,1.0,3.2559043957476534,-0.021894156785931936,0.5801629959796816,0.9967545530000609,-0.0347089398729377,-0.06703383194446996,0.027966335871370828,0.8775825835929442,0.02382976255436446,-0.10566236479587617,0.8252823328313987,0.9653637559538623,1.2373522867904416,-0.11455952708888884,-0.07817398455895143,-0.3095785215005671,0.23440701802747138,0.760862262815277,-0.4910252459375202,0.05609355644939073,-0.014792547978960234,1.0856404451533355,0.2976848666310192,-0.7820080488331232,1.1547217022972882,-2.3493103592557296,-3.7829686062885943,3.985122942015249,-1.1582152558646237,2.0354322275969228,-1.9601256639855014,1.0234047251846548,-4.139127592998222,2.3281472879114906,-0.09443558563902776,1.5750458991054428,-0.9193279301860979,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.208333333333334,0.0,1.0,0.0,1.0,3.263224332314372,-0.02132980898537081,0.5803309310700105,0.9969893181585888,-0.03174678694591649,-0.06247777000629778,0.03318085671741035,0.8732293054836596,0.008682482738451507,-0.07647950412698673,0.8245578363971751,1.0895130755218287,1.2327397933973943,-0.13428018463576183,-0.10957590843264932,-0.27728171507771526,0.22485691889895915,0.7774066451854059,-0.5074025378726574,0.0642267064150068,-0.049988547160968407,1.1040243025902006,0.2968504144513109,-0.7685217816362085,1.1452989920739822,-2.38365114987124,-3.751569050964597,3.7691704892854605,-1.1333108848838365,1.93056004264063,-1.9604725997830952,0.9235925026336906,-4.298461297215767,2.086446946868179,-0.10659229425342809,1.6556096226503647,-1.3339742317594316,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.216666666666667,0.0,1.0,0.0,1.0,3.2704650314211006,-0.020804820247022092,0.5806735416839077,0.9971968737022935,-0.028804140556675614,-0.05742770629674822,0.03835068600375425,0.8649088071421996,-0.006116992918317708,-0.04662713101549293,0.8221342927494497,1.2018584796943075,1.2245952498153212,-0.1542870462534095,-0.14070013540836138,-0.2467590133458094,0.21551850327940744,0.7930382635259542,-0.5236997892672385,0.0714867648266189,-0.08643356959922302,1.1204145609344718,0.29590832839346204,-0.7544145551222838,1.132488798434631,-2.418050328193173,-3.7163263066070544,3.5602365877711386,-1.107619763851196,1.8174390664187356,-1.9426729616168514,0.8153858106322313,-4.437897620935447,1.848844024917926,-0.12034536766308501,1.7249410797983256,-1.7321893918476272,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.225,0.0,1.0,0.0,1.0,3.2776001791071896,-0.02032225773193722,0.5811857022676876,0.9973683677925769,-0.025887581359752606,-0.05193364078887153,0.043463421599281384,0.8528368520930297,-0.02032232491294493,-0.016386194725584627,0.8182494677779488,1.3022542835983708,1.213072693172802,-0.17458102343898138,-0.17151468020943356,-0.21794443861486296,0.20639658950143921,0.8076972962923848,-0.5397804205662716,0.07781646992554399,-0.12395350750989252,1.134838369672166,0.2948446583235928,-0.7397727636395698,1.1164291688765218,-2.452628697339522,-3.6770602252410156,3.3596629949728634,-1.0815656679104901,1.6982065001967617,-1.9101150153269453,0.7017505267221019,-4.555704408031776,1.6139565739921258,-0.1357563171660403,1.7847918626493553,-2.1136510370869743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.233333333333333,0.0,1.0,0.0,1.0,3.2846059645252916,-0.019884120348265394,0.5818617899343216,0.9974957075211797,-0.023002380658545343,-0.04604608808310234,0.04850733699081217,0.8372703819594135,-0.03371515095828852,0.013912937710601717,0.813148645891557,1.3905839791328582,1.1984118933471724,-0.1951641912090682,-0.20198447249571164,-0.19076463009626168,0.1974924088142326,0.8213417051959002,-0.5555350395226876,0.08318260693865394,-0.1623619763997526,1.1473138371676739,0.29364572310736137,-0.7246680240781279,1.0972612811498481,-2.4875208787148764,-3.633200956329836,3.167949579013653,-1.05558558786995,1.5749378519220825,-1.8658010040875395,0.5853916862672185,-4.650621184506315,1.3810062222297992,-0.1527258642988305,1.8369265427757342,-2.4778937437117188,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.241666666666667,0.0,1.0,0.0,1.0,3.2914612117890774,-0.019491370835860153,0.5826953944358668,0.9975717225589368,-0.020152469626694022,-0.039816074767806554,0.053471642249460764,0.8184993658130215,-0.04610222111194849,0.04390608480437749,0.8070870980378114,1.4667205269275903,1.1809006395234185,-0.21603970475089598,-0.2320680294815975,-0.1651452789646354,0.18880349637027338,0.8339462604910862,-0.5708771039677306,0.08757299802999763,-0.20146386058499777,1.1578551400426627,0.2922992272519456,-0.7091573212599742,1.0751309398146598,-2.522835628547881,-3.5837775766127584,2.9848337881215286,-1.0301295231651382,1.4495681721399434,-1.8121872603721623,0.468602296051209,-4.721807294300697,1.1498156691786132,-0.17104756756384898,1.8830539927473589,-2.824270243336384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.25,0.0,1.0,0.0,1.0,3.2981473905440843,-0.019143933533473007,0.5836790855742919,0.997590302717973,-0.01734038325113461,-0.03329519477403185,0.05834662855662355,0.796833900555712,-0.05731240526623691,0.07320992887511668,0.8003307420495174,1.530521405915808,1.1608535401428448,-0.2372114516848662,-0.26171409877259094,-0.1410174002942362,0.18032358342814697,0.8455011747315659,-0.5857381605288903,0.09099264520617409,-0.24105876463809756,1.166477431653984,0.29079493031463055,-0.6932837908656719,1.050190110427575,-2.558630197699801,-3.5274244215433717,2.8092956664262765,-1.0056606397117136,1.3238604142473709,-1.751182950263166,0.3531976329282746,-4.768851264695878,0.9207773774695749,-0.19045765616894417,1.924744919955974,-3.1519503737310783,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.258333333333333,0.0,1.0,0.0,1.0,3.3046484791916977,-0.018840672848636865,0.5848042332850449,0.9975465145715707,-0.014567197362672164,-0.026535641487912803,0.06312374989686292,0.7725884300187863,-0.06719350373129603,0.1014344210714323,0.7931542632669897,1.581838194680754,1.1386027284972733,-0.258683541379226,-0.29085843650732035,-0.11832368452419746,0.1720424857084115,0.8560106007285424,-0.6000634864721167,0.09345962524546887,-0.28094471499659573,1.1732014296671556,0.2891249329824632,-0.677078239260708,1.0225984335858085,-2.594896223325252,-3.4624045171620557,2.6395448262967403,-0.9826554220571726,1.1993985375144178,-1.6842247218321171,0.2405103533846248,-4.791808287099831,0.6948061322240839,-0.21067555181108477,1.9633418907746547,-3.4599191465442214,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.266666666666666,0.0,1.0,0.0,1.0,3.3109506762817102,-0.01857936685130209,0.5860608735660812,0.9974366962486966,-0.011832476763869617,-0.019590175204473162,0.06779568252805088,0.7460654950157857,-0.07560920671762192,0.12819226408135626,0.7858364720322707,1.620534547638382,1.1144970587907004,-0.2804597220736204,-0.31942084072529187,-0.09702498652262387,0.16394599306052743,0.8654911503568062,-0.6138085725594256,0.09500115109591784,-0.3209222360897614,1.1780575338577188,0.28728367111777914,-0.6605614260194277,0.9925247913185047,-2.6315563881818074,-3.3866422173695145,2.472999014302179,-0.9616024483140645,1.0775969653088735,-1.6123922263527057,0.1314261760715077,-4.791242146078823,0.4732702541167466,-0.23143280270933597,1.9998702618425024,-3.7469645290082165,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.275,0.0,1.0,0.0,1.0,3.3170419766944836,-0.018356689670928947,0.5874376119407522,0.9972585262067871,-0.009134251166057521,-0.012511998883370066,0.07235639112086979,0.717541311194047,-0.08243669442734614,0.15310520818776066,0.7786529863132845,1.6465101234423438,1.088906725407381,-0.30254281451558945,-0.3473024734634789,-0.07710703428582781,0.15601577823651042,0.873970550150357,-0.6269366902446618,0.09565006151332733,-0.3607987507645761,1.181089267235768,0.2852677196039743,-0.6437470682299996,0.9601490247690049,-2.6684716036727765,-3.297754415318279,2.3062484280000533,-0.9429983366996203,0.9597222643428482,-1.5365446563614893,0.02644377464396025,-4.768252620069225,0.25789628692407085,-0.25248986600926226,2.03495707748917,-4.011653605619019,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.283333333333333,0.0,1.0,0.0,1.0,3.322911647330853,-0.01816821505822426,0.588921555273153,0.9970110598961857,-0.006469033613927932,-0.005354523656734763,0.07680121900383761,0.6872552018056737,-0.08756540854873188,0.17580737757228967,0.7718665790570014,1.6597285508672681,1.062230305457658,-0.3249342488015,-0.37438341431392985,-0.058587512722622984,0.14822935411553376,0.881486521429187,-0.6394176501654504,0.09544188067331717,-0.40039311309091513,1.1823558053064533,0.28307550668429143,-0.6266454747279415,0.925663897891521,-2.705458020905102,-3.1930712690737972,2.135000158934638,-0.9273396324294447,0.8469233582459301,-1.4574622788047487,-0.07425367348945444,-4.724473275357804,0.050646259890236855,-0.2736414543449839,2.0687632350057883,-4.25229803582172,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.291666666666666,0.0,1.0,0.0,1.0,3.328549652375248,-0.018008451491122384,0.5904982635298485,0.9966947276253824,-0.003831893108716742,0.0018289851303268558,0.0811270082858596,0.6554047564287073,-0.0908974951750467,0.19594645499689223,0.7657158832081181,1.6602466998740995,1.034901099871918,-0.3476337815306745,-0.4005203279480422,-0.04152369830358384,0.14056011769601967,0.8880859394544558,-0.651227728224741,0.09441250028850309,-0.4395399720205395,1.181933371567272,0.28070702869822456,-0.6092676809799031,0.8892773908386429,-2.742311585798064,-3.0696440146395387,1.9540109716443135,-0.9151098348874093,0.7402653198335818,-1.3759753375640815,-0.17072460339972506,-4.662028123276714,-0.1464284844950825,-0.2947123576846078,2.100933168951533,-4.466909832898476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3,0.0,1.0,0.0,1.0,3.333946092969013,-0.017870916227146007,0.592151717159061,0.9963112879301828,-0.0012165881310918182,0.00898587613632234,0.0853322427281299,0.6221487172964809,-0.09235030771815572,0.21318438350614136,0.7604038288594711,1.648240494057844,1.0073891657849936,-0.3706394418981344,-0.4255441478912555,-0.026020663195217758,0.13297752353407694,0.8938242767597467,-0.6623505724581851,0.09259647061665509,-0.4780935818121937,1.1799153305648686,0.27816363405621464,-0.5916299219120826,0.8512154006765464,-2.7788344019492084,-2.924251925205421,1.7570496402818239,-0.90676155612741,0.6407589867980468,-1.2930558352262733,-0.26320020491927554,-4.583438033219744,-0.3313482751019814,-0.31554715034201597,2.130566719868492,-4.6531472268068335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.308333333333334,1.0,1.0,0.0,1.0,3.339090743711233,-0.017748250818688825,0.5938643058706198,0.9958637340301209,0.0013842417099632352,0.01606466439438862,0.08941718992416291,0.5876200430244246,-0.09186111709348259,0.22720040963013716,0.7560884143776377,1.6240189214958352,0.9801944291801383,-0.39394768822982795,-0.44925786003479923,-0.01223953763222011,0.12544742509389617,0.8987652559010899,-0.6727786588118455,0.09002583020651517,-0.5159306059075353,1.1764109003155723,0.2754479095258576,-0.5737582356487616,0.811724937058529,-2.814850767485617,-2.7534464172576767,1.536989984255474,-0.9026951858422194,0.5493739027535915,-1.209834448978575,-0.3520277205167299,-4.491468462945684,-0.5023675609016198,-0.3359993868958189,2.1562199910737867,-4.808247534691361,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.316666666666666,1.0,1.0,0.0,1.0,3.343972791748306,-0.017632372290754858,0.5956168641056341,0.9953561575908795,0.003978845999113282,0.023015595742260683,0.09338399684595763,0.5519519944610599,-0.08939372903230053,0.23770065195732165,0.7528800748164699,1.5880131651911769,0.9538250860054027,-0.41755362135622803,-0.4714349215122168,-0.00040416345762652654,0.11793260377003995,0.9029805084723066,-0.6825144799411613,0.08672934194137626,-0.5529513895279551,1.171542537883175,0.27256364427461766,-0.5556929220608529,0.7710779417650238,-2.8501911913248414,-2.5537060366804587,1.2862168968400718,-0.903237433006876,0.46701611891391215,-1.1274880237068352,-0.43763402590784956,-4.388910540415676,-0.6581196040264903,-0.35592859496148876,2.1759445212812945,-4.928939199638978,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.325,1.0,1.0,0.0,1.0,3.3485809106976725,-0.01751464119233493,0.5973888077473187,0.9947935849104758,0.006576142539704722,0.029791090226681083,0.09723666435353666,0.5153191204070131,-0.08494602598733157,0.2444388811368089,0.750850798050522,1.540725283128359,0.9287559514790199,-0.44145087475190864,-0.4918196273128069,0.009197410648447753,0.1103934678771149,0.9065488578829884,-0.6915701258736261,0.08273192977471767,-0.5890791149144632,1.165442240248464,0.2695157662764995,-0.5374924936274067,0.7295759503978794,-2.8846141426884797,-2.3217998300421017,0.9975750395321588,-0.9086248193155583,0.39445027674631206,-1.0469393317560427,-0.5205169680309655,-4.278294927930153,-0.7977166630980115,-0.37521448835509896,2.187371965962137,-5.011319751218471,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.333333333333334,1.0,1.0,0.0,1.0,3.3529038116586944,-0.01738601228647598,0.5991584532887176,0.99418181439351,0.009185579067477615,0.036345872065026694,0.10098080421904716,0.34760310232919506,-0.040297474366536926,0.2610218953000863,0.7775640603193086,1.424684964222382,0.9677985397649463,-0.46563052373436936,-0.5101315853462518,0.016222087201242786,0.10278885678144731,0.9095546797514118,-0.699963468803762,0.07805405914086017,-0.6242563049934576,1.1582472601648748,0.26631006946869934,-0.5192367226281506,0.6875559459113826,-2.891960589368243,-1.2861277957137662,-0.11551260969741454,-1.0557854070736317,0.2303158628758828,-1.099751168383487,-0.659519301152631,-4.483774198468907,-0.790855591477353,-0.44821509511683844,1.9653844197584558,-4.958410002796194,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.341666666666667,1.0,1.0,0.0,1.0,3.354697708575535,-0.017052875493576432,0.6013018143774289,0.9934904692886144,0.0121177527328922,0.04217474183854069,0.10512439677181266,0.1859940947481586,0.000858624143464097,0.25804619229416187,0.781293985224198,1.3317787793417513,0.9967742820407424,-0.489650217908046,-0.513255090574703,0.007272200486824178,0.09279704442588771,0.9103874555975865,-0.7098993120133509,0.07173994142217383,-0.663808684888945,1.1522613137238416,0.26204551469121884,-0.5047360866314324,0.6469357836846095,-2.858707353784055,-0.25982151756320127,-1.3212633282193111,-1.1798492554535611,0.2180655016863975,-1.5007927731734427,-0.7715142207563034,-4.685605468936784,-0.7951259670331767,-0.4907944244780471,1.7087193205153206,-4.856085567778082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.35,1.0,0.0,0.0,1.0,3.356292559701902,-0.01678676300911185,0.6031912566659455,0.9927631221663573,0.014836786963353532,0.047955129237584784,0.10909426532757684,0.17399585852452482,-0.003956030019507145,0.23371832988194188,0.7428850441492855,1.3072924586678811,0.9554759217739844,-0.5132756462974369,-0.5144619439723052,-0.005798968269079065,0.08312470252388796,0.9131891047795184,-0.7249766816899861,0.06519548879492178,-0.7023497294757374,1.1449951607143218,0.2581301623940652,-0.49075806728622856,0.6066211864484146,-2.801148617524535,-0.0834533790801828,-1.6270871990810085,-1.1536780103536213,0.4286520901725921,-2.0021125012074092,-0.8056323665027831,-4.50519960576123,-0.9658642980743704,-0.4576720668920309,1.684210614718663,-4.80960471069323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.358333333333333,1.0,0.0,0.0,1.0,3.3579129683253335,-0.016558925140833493,0.6049081240765407,0.9920095186423084,0.017456775392582096,0.05354728901340978,0.11289403820987298,0.17899211022809672,-0.009612308945667558,0.2168314468889008,0.7183084398320756,1.2511996437930513,0.9170467941865089,-0.5363360282001216,-0.5146459802260394,-0.019845919497859296,0.07356907758666069,0.917531657100463,-0.743267853700141,0.058312735313794106,-0.7388953449849655,1.136163575422602,0.254417646909685,-0.4766659097194547,0.5667757051730556,-2.722731926296005,0.026985892186959237,-1.6757901153303516,-1.144442524842827,0.596799181205927,-2.3238993995542168,-0.8446771451226713,-4.2516068869601575,-1.1385058192963626,-0.43315692979935094,1.7017378945577488,-4.7233795331098065,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.366666666666667,1.0,0.0,0.0,1.0,3.3596163718310166,-0.01635049210177277,0.6064695283404989,0.9912399683823825,0.02000723981926441,0.0588410202231278,0.11653656019747638,0.18933876756489323,-0.014776101213783109,0.201233100938017,0.6962764918478879,1.1717668324813637,0.881827701217591,-0.5586545117357037,-0.5140121791025225,-0.033728803524584926,0.06405066044317417,0.9231357577996172,-0.763708338349223,0.05111753637621059,-0.7732098442584067,1.1260200637260491,0.2509108802307427,-0.4623957690435994,0.5278981942299178,-2.624330833643065,0.12464996754479207,-1.6286743180797216,-1.1426097315711456,0.7390447657893007,-2.542916383897844,-0.8800211156083091,-3.981737377341381,-1.275647181668682,-0.4071642000145187,1.7153945119773273,-4.57034243316125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.375,1.0,0.0,0.0,1.0,3.3614242409425867,-0.016148856325572405,0.6078695601212983,0.9904651263371107,0.022503338598697024,0.06375587622811943,0.12003175236828167,0.20260708709754063,-0.019499454371035035,0.1849597681651813,0.6750886318719723,1.0744172616029606,0.8492454518255564,-0.580074875427506,-0.5125684807669595,-0.046990491465854656,0.05452558206047493,0.929849069863618,-0.7856497934317718,0.04364571672032229,-0.8052576346073218,1.1149027890614573,0.247631576909443,-0.44807600118649926,0.4906033312870348,-2.5075496758405014,0.2266016292810158,-1.5433207590161093,-1.145305737432196,0.8660045555717777,-2.693313342463939,-0.9111651081130179,-3.711378739256388,-1.371874611615027,-0.37841029951968475,1.7086844443487292,-4.338979531106778,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.383333333333333,1.0,0.0,0.0,1.0,3.3633507248334267,-0.01594342223759749,0.6090963146484389,0.9896957986793586,0.02495676550639599,0.06822543878632935,0.1233883117868211,0.21841813971321808,-0.02391993378711795,0.16751149975870952,0.6543481473075328,0.9616747720128095,0.8191176980071072,-0.6004470063330454,-0.5102354852811722,-0.05945081617485341,0.04496223148597091,0.9375691670591468,-0.8085968940569553,0.035931451240993624,-0.8350661565793465,1.1031554868657987,0.24460404190541463,-0.4339176949711206,0.4555818687114715,-2.3727962884309184,0.340617618667165,-1.4437885024226011,-1.151388638099527,0.982191943027777,-2.7883506253989276,-0.9382902635149797,-3.4458413569075375,-1.4270350568228407,-0.34664265786797377,1.673324667949131,-4.019945519567255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.391666666666666,1.0,0.0,0.0,1.0,3.3654100397818154,-0.01572431539653412,0.6101363598076871,0.9889427610309819,0.02737810353829919,0.07219006888565317,0.1266145680487932,0.2368672533173588,-0.028178687389718973,0.1487577899915756,0.6339011233871157,0.8348281180361488,0.791411093798771,-0.619621480234688,-0.5068915204558401,-0.071053633172898,0.03533577142548281,0.9462189355807477,-0.8321223038550872,0.028007545661739294,-0.8626883238891141,1.0911188714477433,0.24185419927831012,-0.4201872567206804,0.42360423929424723,-2.220227808497508,0.4703267023603397,-1.3409951992252978,-1.1601517480903631,1.0902252958577896,-2.8347746916971994,-0.9615291895031929,-3.1875926972571222,-1.4413297099811917,-0.31164838824610464,1.6031722797191772,-3.6036093271492464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4,1.0,0.0,0.0,1.0,3.367617737611747,-0.015481991668758561,0.6109757261851492,0.9882165324838066,0.02977751452716202,0.07559407121218754,0.12971862232111642,0.2580853398532666,-0.03239499549379285,0.12860795165597244,0.61366997168113,0.6946064084336601,0.7660939205337205,-0.6374508031413372,-0.5023967069084999,-0.08180073616194171,0.02562636901779819,0.9557395886567767,-0.8558431389185753,0.019905964749273742,-0.8881927015336318,1.0791333250327788,0.23940990210131288,-0.407198156975801,0.39552171325898405,-2.0502540150235493,0.6170566516845355,-1.2397785822002467,-1.1710452000670615,1.1921798472511602,-2.8374880104181166,-0.9809822995707919,-2.9384086487695127,-1.414378159161429,-0.2731725778511346,1.493059693472124,-3.0807346739249564,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.408333333333333,1.0,0.0,0.0,1.0,3.369990342400847,-0.015207052278284575,0.6115997314884581,0.9875271819808036,0.0321650913272811,0.0783839082724074,0.1327080807217975,0.2822199691347136,-0.03657051800595977,0.10673794322740174,0.5935504164332857,0.5404272826236804,0.742691177513923,-0.6537923804850805,-0.4966072429277645,-0.09171660954290212,0.01581835142436512,0.9660885997016003,-0.8794137706953892,0.011657840668892763,-0.911661801368606,1.0675459021283862,0.2373013229807912,-0.395302928496145,0.37225866139549796,-1.8625322736817185,0.7816231104301508,-1.1413574600904877,-1.183541758539531,1.290180964033023,-2.7996524136484435,-0.9970655645418234,-2.7005213536287775,-1.342088921008875,-0.23100734555678903,1.337710510269402,-2.439259131923807,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.416666666666666,1.0,1.0,0.0,1.0,3.3725452037665344,-0.014888198428059756,0.6119897192626846,0.9868852191669197,0.03455132347867526,0.08049920656534984,0.13558631194701107,0.1586553943583255,-0.023149301017590586,0.047388346518259836,0.2988799526538293,0.32744140299729635,0.49421525960860757,-0.6684930077026991,-0.4893696550679974,-0.10082336049678317,0.005900673042139342,0.9772426047239937,-0.9025040124793827,0.0032882053402433545,-0.9332013907607781,1.0567651763492976,0.2355597796753664,-0.3849029818046443,0.3548673943935873,-1.1587326997055336,0.46941512437498667,-0.7002123677604608,-0.6550077429405242,0.7341653453953145,-1.5193564378107194,-0.43768325105726336,-1.2931571700456157,-0.8623358415252147,-0.048734266183085295,0.7680331732714518,-1.4301066247430205,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.425,1.0,1.0,0.0,1.0,3.372737102357077,-0.014892032973497322,0.6119473187964342,0.986671436192955,0.03458500998844518,0.0812703598002109,0.13666924636351188,0.017887815122627607,-0.006416827848274521,0.0031577611225589385,-0.0008609445608257927,0.13395557351905704,0.1612720186406377,-0.6731045921468394,-0.4887836575215147,-0.10338681567224313,0.004901555708689717,0.9783246887915222,-0.9047363779922345,0.0043631198179383745,-0.9332144208693662,1.053173638102966,0.23648908521107312,-0.3825023756082875,0.3484235509831143,-0.3428376008928802,0.0701083804953706,-0.259393136719088,-0.060867802555057623,0.07065827459840968,-0.15742700233215556,0.11630391623459077,-0.24884271044699702,0.16128568339944582,0.0794220630278969,0.22715727987751677,-0.5808993941677976,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.433333333333334,1.0,1.0,0.0,1.0,3.3728654384111834,-0.014911236968246842,0.6119868587207633,0.9866118833040793,0.03450084197513395,0.081553128569592,0.13695171049982793,0.01177450702677976,-0.003910662856816427,0.004707512066128534,-0.018244320031078246,0.04025477977034468,0.027140596648653825,-0.6742069677175805,-0.4882011820597412,-0.1051465794421013,0.004886209666221715,0.9784202426339672,-0.9051277958515853,0.005226603944153201,-0.9373487692682281,1.0594532710726217,0.23688348072583135,-0.381117027140019,0.345185737824124,-0.05144928653409098,0.08221485240540449,-0.19812199734648817,0.01398286865555095,0.004049293758108252,-0.013262280437114082,0.08496378426237584,-0.5038980268571014,0.8360168761215547,0.031649553294073596,0.10898127827671633,-0.2330900547510406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.441666666666666,1.0,1.0,0.0,1.0,3.3729539862234326,-0.014904063337871606,0.6119889285622738,0.9866184278095949,0.03440750014810699,0.0815726772017481,0.13691639848542864,0.00984302028591438,-0.0005430700021516665,0.0003493826640289482,-0.01966433175751913,-0.007101364834670852,-0.025641191527932018,-0.6739620802557409,-0.48741340998142463,-0.10668884896135127,0.0051346035196155665,0.978392177020824,-0.9049574159995197,0.005779182888977972,-0.9416127213169846,1.0671072527049918,0.23701657776597435,-0.3806860209703422,0.3445387167372636,0.059126750001821105,0.10005733242549608,-0.17768875513584026,0.032516967643232024,-0.0040425752655792735,0.03280338440220021,0.05672564512081264,-0.5097139229446257,0.9446636091162341,0.0069779943183906346,0.021361147932796865,0.0009135061997678218,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.45,1.0,1.0,0.0,1.0,3.3730245416120983,-0.01487495052041288,0.6119669135444734,0.9866515885952373,0.0343298304994663,0.08147964400094533,0.13675223242730591,0.009228276914332895,0.001657288046649464,-0.002243672896910305,-0.01766531285026831,-0.027930143436587132,-0.04680469103069142,-0.6732215218842168,-0.4865335598526496,-0.10810805869436531,0.0054281591269422485,0.9783528663795409,-0.9045810727782153,0.0061720313628334115,-0.9458440013173052,1.0751976645578922,0.23699978063113786,-0.3807610080078057,0.34520096292745345,0.10050760606313824,0.10776735308138163,-0.16577218154973788,0.035485357293632995,-0.004297442029299603,0.05012954762317667,0.04393423593130191,-0.5024758660716189,0.9742067265410181,-0.006172587043587474,-0.02380016424898712,0.11707850268582898,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.458333333333334,1.0,1.0,0.0,1.0,3.373086333202551,-0.014833475027712862,0.6119313201864863,0.9866957692315815,0.03426229927680965,0.08133628431939002,0.1365355729540084,0.008968991665432347,0.0028245922445516644,-0.003647106072415976,-0.01638288166507383,-0.03729677109126635,-0.0553893984631348,-0.6722869534880219,-0.48561728743006827,-0.1094517186538469,0.005726026141176116,0.9783205529870024,-0.9041219235391335,0.00651142015449967,-0.9499873190848449,1.0833440314806755,0.2369137013152479,-0.381082690374492,0.34649002511536076,0.11686039098214751,0.11067706698483559,-0.15845109224770781,0.03559853268970863,-0.003481208144697767,0.05717597678746911,0.040651608613553464,-0.49008090931412784,0.9703605285385031,-0.012171698687303278,-0.045570796437397476,0.1722176483624105,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.466666666666667,1.0,1.0,0.0,1.0,3.3731437265912025,-0.014785870297592497,0.6118887092672468,0.9867445596660223,0.03420001376040101,0.08117014365518081,0.13629725164981718,0.008834668846239256,0.00339479339670662,-0.004359116535717519,-0.01573375165885655,-0.04153380767122821,-0.05892726604847822,-0.671273848701181,-0.48468894206956903,-0.1107489102318271,0.006021468005104059,0.9782948462437959,-0.9036281398317575,0.0068495581730593025,-0.9540120164725406,1.091370340033534,0.23679691898634947,-0.38152052128176234,0.34807125706682696,0.12352975681873213,0.11156990204416739,-0.15399731589710391,0.035313578291129265,-0.0028478371909868017,0.06014420742385562,0.04194059827490561,-0.47484093613823886,0.9510458031597002,-0.014825509320727792,-0.05570794005000934,0.1976957830577375,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.475,1.0,1.0,0.0,1.0,3.3731989466090657,-0.014735410173009012,0.6118426520934475,0.9867952738765409,0.034140236644016685,0.08099367938659363,0.13604982762295145,0.008766000984895973,0.003659423368954871,-0.0047053490813034286,-0.01543242692347542,-0.04344685001015175,-0.06041760476760112,-0.6702281242077097,-0.4837577890626655,-0.1120183405854653,0.006314585779361604,0.9782730890338193,-0.9031195200820692,0.007210430125748097,-0.9579013346871489,1.0991947948666705,0.23666660949323576,-0.38201115604199215,0.3497849548329897,0.12632369571058177,0.11174465647780463,-0.1513809066514571,0.03509705593872344,-0.0024880959599893337,0.06143132124448725,0.04531713214595452,-0.4580494907387167,0.9245444342823417,-0.015996569773457092,-0.06023188796406731,0.20909335586272726,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.483333333333333,1.0,1.0,0.0,1.0,3.3732531980436837,-0.01468368737764062,0.6117949554381402,0.9868467711587637,0.03408158695571907,0.08081255921230543,0.13579847553511074,0.008741967874566462,0.0037737030389165,-0.004867586268942875,-0.015303324827880254,-0.04430398517514979,-0.061066979342024756,-0.6691684537726713,-0.4828265311282723,-0.11327192534268472,0.006606418937416116,0.9782533779777961,-0.9026042844776827,0.007604843708825211,-0.9616461746515192,1.1067794139382396,0.23653030949012518,-0.38252438608116346,0.35155614633120574,0.12753552375841748,0.11174634634960046,-0.14992480251149576,0.034992443784307006,-0.0023048813201764773,0.062025045730502715,0.049631364950262685,-0.4404067126286537,0.8946989753941192,-0.01651623960978843,-0.06208567061733672,0.21390461877970113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.491666666666667,1.0,1.0,0.0,1.0,3.373307167777166,-0.014631450843151253,0.6117464946350937,0.986898562091492,0.03402339806405106,0.08062936115970988,0.1355453527233514,0.008750535903274142,0.0038145677288213024,-0.004939713632573522,-0.015256074363460596,-0.044682017964504224,-0.061366646536674445,-0.6681025321450694,-0.4818953499568388,-0.11451708729399022,0.006897793175766721,0.9782346743451497,-0.9020857693198941,0.008037619541585809,-0.9652414465642931,1.1141064444565725,0.23639133883307262,-0.38304591721894776,0.3533500318126514,0.12809441572636304,0.11177288600415447,-0.14918652361281454,0.034968368472091,-0.002213998881381851,0.06234253983483651,0.054360845933681526,-0.4222761502857453,0.8632798163452193,-0.016747874674176155,-0.06267652322447415,0.2156666401586449,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5,1.0,1.0,0.0,1.0,3.373361263160289,-0.014579046607029132,0.6116976819987483,0.9869504350280267,0.03396535594197968,0.08044525403754155,0.13529136889158505,0.008782732000518169,0.003819312136172337,-0.004968271424947405,-0.015246948160601617,-0.04484346678942594,-0.06151912421053898,-0.6670335468438986,-0.4809636496948697,-0.1157583674028983,0.007189225078617633,0.9782164779964397,-0.9015652421471021,0.008510857807719903,-0.968684110489615,1.1211674108773266,0.23625117824555558,-0.38356899480157136,0.3551505903338498,0.12838305074197143,0.11187711961745173,-0.14888554818758615,0.034993182374164246,-0.0021663272161598357,0.06255931953472738,0.05926689189386984,-0.4038436755127006,0.8310978511423972,-0.016850315274312133,-0.0626699412341647,0.2160278564533269,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.508333333333333,1.0,1.0,0.0,1.0,3.373415732518478,-0.014526632967903122,0.6116487078440083,0.987002297890152,0.033907314968377435,0.08026076495099199,0.13503691184515607,0.008831624753983462,0.0038059850790706498,-0.004975840241543958,-0.015255399509871388,-0.04490755077385901,-0.06160890963899374,-0.6659628146327032,-0.48003073129654794,-0.11699851309711666,0.0074810128820027915,0.978198568891547,-0.9010431139943154,0.009025401073150306,-0.9719721744895048,1.1279580753089458,0.23611050024516742,-0.3840904162395172,0.3569504960868735,0.12856045967628793,0.11205844886560845,-0.14884866430412869,0.035045930097890574,-0.0021371203571352027,0.06274687639605592,0.064237847251187,-0.38520500454591655,0.798523579117254,-0.01689363590184567,-0.06237951295488209,0.21575004695762234,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.516666666666666,1.0,1.0,0.0,1.0,3.373470730123772,-0.014474281967685312,0.6115996585043662,0.9870541104290335,0.03384920832939742,0.08007612982481256,0.13478214871748526,0.008892052287730903,0.0037833984224065935,-0.004973274140583231,-0.015271936804936288,-0.04492821644184122,-0.061671654358434004,-0.6648908725159605,-0.4790960088804429,-0.11823917847463378,0.007773323913582476,0.9781808593238208,-0.9005194608738345,0.009581488595239687,-0.9751041938987136,1.1344761371959475,0.2359696176471915,-0.3846086533508194,0.3587464244498102,0.1286928744760596,0.11230100837641532,-0.1489707521323208,0.035114333474977735,-0.0021149487854899007,0.06293228060991085,0.06921895743328688,-0.3664108964953483,0.7657269309543535,-0.016909176306182383,-0.06195333024334393,0.21518334842768327,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.525,1.0,1.0,0.0,1.0,3.3735263532237543,-0.014422026401056208,0.6115505723851321,0.987105854976411,0.03379100555172828,0.07989145305881433,0.1345271524386178,0.008960336263956464,0.0037559195791059693,-0.004965786203226678,-0.015292226659912572,-0.04492976371974253,-0.061722552778023666,-0.6638179333914356,-0.4781590478236077,-0.11948135896598867,0.00806625177325242,0.9781633197451222,-0.8999942426508168,0.010179050363705087,-0.9780790227644273,1.1407201908248517,0.23582868064006438,-0.3851229717435729,0.3605368852273349,0.12880773243514998,0.11258790450060951,-0.14918860863984473,0.0351915380289464,-0.0020949018775229256,0.06312424757530799,0.07418109930558504,-0.34748977382188073,0.73278713968294,-0.016911185976136167,-0.06146182885210072,0.2144882021516381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.533333333333333,1.0,1.0,0.0,1.0,3.373582664016261,-0.01436988134772911,0.6115014660603566,0.9871575237341399,0.03373269271996778,0.07970677996512807,0.13427195539103476,0.009033951381351359,0.0037257549384160354,-0.004955894298586012,-0.015314309171244184,-0.04492307837663636,-0.06176813756920818,-0.6627440769753746,-0.47721954380543274,-0.12072565528529786,0.008359849547398249,0.9781459442925288,-0.8994673900809127,0.01081784025033277,-0.9808956901290783,1.1466892561906632,0.23568776454758922,-0.3856330171650211,0.36232122781900417,0.1289162301539526,0.11290550108783548,-0.14946437558053083,0.035273785137610696,-0.002075041321423221,0.06332440695986818,0.07910679165089196,-0.32845891750153733,0.6997427309918125,-0.016906266852407814,-0.06093889134475727,0.21373803360543286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.541666666666666,1.0,1.0,0.0,1.0,3.37363970302777,-0.01431785395403319,0.6114523462581491,0.9872091132245684,0.03367426338161403,0.07952212948534872,0.1340165723863371,0.00911121425238896,0.0036940433451524246,-0.004944827275797318,-0.015337305113789921,-0.04491300335612088,-0.06181123778623815,-0.6616693295555364,-0.47627728947214376,-0.12197243189233085,0.008654148192212599,0.9781287357230984,-0.8989388358681524,0.011497496891219953,-0.9835533380561196,1.1523825696747152,0.23554690952585758,-0.3861386199326522,0.36409918578742545,0.12902280205259187,0.11324395280668642,-0.14977538647820143,0.03535901845195512,-0.0020547024099615285,0.06353201693450661,0.08398389737735441,-0.30933002141813937,0.6666141407288251,-0.016897542646844843,-0.0604010562152113,0.21296644159671696,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.55,1.0,1.0,0.0,1.0,3.3736974973748874,-0.014265947845102428,0.6114032153117333,0.9872606218596455,0.033615714412367215,0.07933750889370628,0.1337610105837774,0.009191028770373894,0.0036613857420992567,-0.004933192964465907,-0.015360822737947546,-0.04490167290475355,-0.061853085220307594,-0.6605936969411648,-0.47533214459198797,-0.12322191172660121,0.008949166521597501,0.9781116992523627,-0.8984085231320043,0.012217571873288677,-0.9860511904860473,1.157799491869477,0.23540613883680847,-0.3866397014352746,0.3658706685122828,0.12912910685725087,0.11359656149726893,-0.15010805831287194,0.03544610560161209,-0.0020337274892012758,0.0637458163313398,0.08880276777002674,-0.2901119815835207,0.633413898760935,-0.016886526025982618,-0.05985652794024077,0.21218879753465258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.558333333333334,1.0,1.0,0.0,1.0,3.3737560659010732,-0.01421416510095823,0.6113540736205145,0.9873120488742271,0.033557044156476507,0.07915292036749749,0.13350527380052302,0.00927269525637473,0.0036281059009627397,-0.00492129617896467,-0.0153846880869286,-0.04489001407548014,-0.06189421784794972,-0.6595171777745822,-0.4743840134471893,-0.12447423286421205,0.009244916618906134,0.9780948402649451,-0.8978764055959634,0.012977543020720399,-0.9883885377491782,1.1629394679873974,0.23526546742542453,-0.3871362287316562,0.3676356657463363,0.12923569510569832,0.11395893581652383,-0.1504542464693992,0.035534415977114785,-0.002012138381453088,0.06396466716613425,0.09355493895390879,-0.2708123226674486,0.6001511935482817,-0.0168739682905511,-0.05930943817824441,0.21141211377151525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.566666666666666,1.0,1.0,0.0,1.0,3.373815422378443,-0.014162507134013099,0.6113049207544067,0.9873633938579565,0.033498251599895015,0.078968363903595,0.13324936439412177,0.00935577535312996,0.0035943813872429,-0.004909291340370201,-0.015408823404396699,-0.044878419730144656,-0.061934870680475054,-0.6584397686894031,-0.4734328289950459,-0.1257294825010912,0.009541406787882747,0.9780781636126719,-0.897342445345902,0.013776820855853824,-0.9905647291971714,1.1678020117619483,0.23512490603196595,-0.38762819207157867,0.36939420374180804,0.1293426972237044,0.11432827202911722,-0.15080907314228953,0.03562359365187614,-0.001990005270968709,0.0641877147331571,0.09823253502896957,-0.2514379430789804,0.5668339074401052,-0.016860253068847753,-0.0587618870423523,0.21063955380820953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.575,1.0,1.0,0.0,1.0,3.3738755775034748,-0.014110975073964433,0.6112557559462339,0.9874146565503057,0.03343933600778677,0.07878383860191733,0.13299328408663058,0.009439886422486152,0.0035603791767128056,-0.004897215186777741,-0.015433102526202466,-0.04486718295798071,-0.06197502291051226,-0.6573614661541871,-0.472478542246704,-0.12698771741658355,0.009838643179770736,0.9780616735104289,-0.8968066103504108,0.014614751937869892,-0.9925791701338279,1.1723866997780659,0.2349844632076104,-0.3881155935156954,0.37114632497647315,0.12944996944839415,0.11470444498837273,-0.1511726305783756,0.035713199431563064,-0.0019675323951884316,0.06441448936638894,0.10282788106131306,-0.2319958071451178,0.5334696288764684,-0.01684568174270873,-0.05821519863176472,0.2098728646926451,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.583333333333334,1.0,1.0,0.0,1.0,3.373936538157721,-0.014059569376028322,0.6112065793681485,0.9874658367218957,0.033380297742092155,0.0785993421868768,0.13273703524825514,0.00952513578168791,0.003525997862884268,-0.0048852116995461254,-0.015457719525746674,-0.04485605110624976,-0.06201498955949886,-0.6562822691985966,-0.4715210882452397,-0.12824902634406413,0.010136626778408798,0.9780453714060854,-0.8962688705231289,0.015490618873542375,-0.9944313259829234,1.1766931722432228,0.23484414466958747,-0.3885984453821081,0.3728920848200188,0.12955773298079176,0.11508353049358933,-0.15153802406374095,0.03580366514923217,-0.0019443976318433975,0.06464426718416849,0.1073339044328512,-0.21249195380265817,0.5000656591508879,-0.016830114277017194,-0.057669364823875746,0.20911189939318842,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.591666666666667,1.0,1.0,0.0,1.0,3.373998316781515,-0.014008292239075957,0.6111573875003821,0.9875169342584469,0.03332113398133205,0.07841487570508013,0.13248061719297394,0.009611391972290126,0.003491292386866611,-0.0048732593907173435,-0.015482610107196506,-0.04484509998489474,-0.062054761486683874,-0.6552021706045073,-0.47056048340514417,-0.12951335115097923,0.010435370932257939,0.9780292668832316,-0.8957292058973413,0.016403650345084078,-0.9961207026972055,1.1807211274305807,0.23470396130299345,-0.38907674959609334,0.37463152329969296,0.12966594368528872,0.11546432555135211,-0.15190301069664125,0.03589481140965394,-0.0019208205642518017,0.06487708132582704,0.11174330844290342,-0.1929330973462684,0.4666294959148498,-0.016813694975820193,-0.05712455351664425,0.20835669485829045,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6,1.0,1.0,0.0,1.0,3.374060917994422,-0.013957143871530625,0.6111081812886628,0.9875679489570165,0.033261845700706026,0.07823043632539976,0.1322240323056971,0.00969832872267867,0.0034564366622913878,-0.004861273403406923,-0.015507571513881086,-0.04483462738529034,-0.06209407974884014,-0.6541211701371751,-0.4695966828193838,-0.13078074318900815,0.010734873635236364,0.9780133577300145,-0.8951875858343651,0.017353007347590765,-0.9976468776053612,1.1844703305084703,0.23456391641999047,-0.38955052127405215,0.3763646964009903,0.12977427508579886,0.11584941991319098,-0.15227246871020061,0.035986061310431285,-0.0018971806253920143,0.06511306420670326,0.11604874543053714,-0.17332682865109028,0.4331691871902432,-0.01679669492554936,-0.056581443733287884,0.2076080136621017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.608333333333333,1.0,1.0,0.0,1.0,3.374124348545683,-0.013906125222131832,0.6110589596704109,0.9876188806474537,0.033202432249655085,0.07804602280583715,0.13196728182639844,0.009786074782083435,0.0034213482886159036,-0.004849340509665607,-0.015532741297279733,-0.04482442403969673,-0.06213310580000096,-0.6530392660197439,-0.4686296597399243,-0.13205122562948257,0.011035138620765127,0.9779976472061417,-0.8946439881605629,0.018337796102259697,-0.9990094831747237,1.1879406138837514,0.23442401638756763,-0.3900197736583148,0.378091656860728,0.12988281621281184,0.11623759750053142,-0.15264444164716617,0.03607773653357377,-0.0018731783807335312,0.06535175319644981,0.12024348557595384,-0.1536800078605638,0.39969282859349864,-0.016778959742027588,-0.05603985342905071,0.20686553812136244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.616666666666667,1.0,1.0,0.0,1.0,3.3741886152152323,-0.013855237205679306,0.6110097217486932,0.9876697291583445,0.033142893129856604,0.07786163392675768,0.13171036695366,0.009874631486180986,0.003386033123195814,-0.004837446998275929,-0.015558094567257173,-0.04481448819561977,-0.0621718456025647,-0.6519564565336282,-0.4676593895277083,-0.13332481721646092,0.01133616924412926,0.9779821380903356,-0.8940983899477576,0.01935706544052333,-1.000208211069704,1.1911318776516953,0.23428426709095668,-0.390484518831203,0.37981245536967967,0.12999155905966564,0.11662868932376447,-0.1530185749700319,0.03616980260674911,-0.0018488616450018647,0.06559321841421051,0.1243207354150333,-0.13399987739553199,0.3662086895705574,-0.016760532150381646,-0.05549966623065172,0.20612905800055703,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.625,1.0,1.0,0.0,1.0,3.3742537247869158,-0.013804480704684374,0.6109604667070991,0.9877204943182527,0.03308322788764654,0.07767726849062202,0.13145328886268953,0.009964001553841756,0.003350496219959098,-0.0048255862191209226,-0.0155836205961041,-0.044804814511434615,-0.062210305214160655,-0.6508727400354162,-0.4666858482511949,-0.13460153521231644,0.011637968664210945,0.9779668328453917,-0.8935507678536594,0.02040980835917692,-1.0012428144646492,1.1940440920432607,0.23414467418506127,-0.39094476809549233,0.38152714116073727,0.13010049391338985,0.11702264211561952,-0.1533947553521814,0.03626223921151767,-0.0018242593409811825,0.0658374993975519,0.12827388781889423,-0.1142939256358444,0.3327253056390056,-0.016741437625059086,-0.05496079365678197,0.20539841088127342,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.633333333333333,1.0,1.0,0.0,1.0,3.3743196840813865,-0.013753856569199911,0.6109111937744047,0.9877711759561798,0.033023436101115564,0.07749292533608995,0.13119604869681853,0.010054191365380705,0.0033147418048483975,-0.00481375384515939,-0.015609309859218804,-0.04479539549525306,-0.06224849302540419,-0.649788114968405,-0.46570901215911464,-0.1358813964723306,0.011940539897654555,0.9779517337679859,-0.8930010982911317,0.021494963570838233,-1.0021131098303013,1.1966772994123454,0.23400524313053903,-0.39140053205881603,0.3832357622177009,0.13020961101030126,0.11741944918557845,-0.15377296161214637,0.03635503011517667,-0.0017993879133104684,0.06608462381460178,0.13209653068375288,-0.09456984332042673,0.2992514387208045,-0.01672169969501036,-0.054423153622495946,0.2046734531962202,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.641666666666666,1.0,1.0,0.0,1.0,3.3743864999786286,-0.013703365612465155,0.610861902211781,0.9878217739026032,0.03296351737931999,0.0773086033408678,0.1309386475582092,0.010145209402852491,0.003278774119653611,-0.004801946404021549,-0.015635152583264103,-0.044786223592788416,-0.06228641960533006,-0.6487025798519112,-0.46472885743143527,-0.1371644179058522,0.012243885832797223,0.9779368430468365,-0.8924493574567494,0.022611417203906133,-1.0028189785199897,1.1990316160219407,0.23386597919014443,-0.39185182065586727,0.3849383653806743,0.13031890195461582,0.11781912506888759,-0.15415321125227144,0.036448159810585114,-0.001774258865694378,0.0663346172159951,0.13578246613616932,-0.07483550280350748,0.26579605638762605,-0.016701343042193617,-0.053886667157666546,0.2039540532659767,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.65,1.0,1.0,0.0,1.0,3.3744541794265435,-0.013653008605315597,0.6108125913066309,0.9878722879906997,0.03290347136374189,0.07712430142018167,0.13068108649909468,0.010237064772684344,0.003242597931931124,-0.004790161018205504,-0.01566113851964493,-0.04477729189927991,-0.06232409753291851,-0.6476161332691615,-0.4637453600746332,-0.13845061665986846,0.012548009227830973,0.977922162786891,-0.8918955213375318,0.02375800467310772,-1.0033603682103598,1.2011072336854725,0.23372688741316913,-0.3922986431781105,0.3866349964388005,0.1304283595313782,0.11822169182253317,-0.15453553515193397,0.036541612091685674,-0.001748881560583726,0.0665875037144037,0.1393257310781817,-0.05509894079738231,0.23236831520674794,-0.016680394519523745,-0.05335125995759804,0.20324009083312555,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.658333333333333,1.0,1.0,0.0,1.0,3.374522729438595,-0.013602786270409532,0.6107632603683825,0.9879227180575687,0.032843297730264426,0.07694001852395833,0.13042336651352734,0.010329766114952881,0.0032062188328162897,-0.004778395430723765,-0.015687256913023383,-0.04476859433878943,-0.062361541270281394,-0.6465287738597215,-0.4627584959010597,-0.13974001015838444,0.012852912700991984,0.9779076950208268,-0.891339565728176,0.024933512721875828,-1.003737294199946,1.2029044212753865,0.23358797261481903,-0.39274100832182723,0.38832570022789303,0.13053797714398518,0.11862717086689734,-0.1549199639820914,0.03663536931711623,-0.0017232643120412838,0.06684330447136011,0.1427206175786406,-0.035368340928814135,0.19897754497946174,-0.01665888359249912,-0.052816864375185846,0.2025314576101478,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.666666666666666,1.0,1.0,0.0,1.0,3.3745921570837805,-0.013552699276636269,0.610713908724939,0.9879730639453932,0.03278299619117541,0.07675575363381196,0.13016548852959295,0.010423320846214845,0.0031696434068863664,-0.004766648068748847,-0.015713496522570567,-0.04476012565921112,-0.0623987670486877,-0.6454405003167617,-0.4617682405601849,-0.14103261605957,0.013158598716449577,0.9778934417150237,-0.8907814662630091,0.02613668163275173,-1.0039498405591734,1.2044235261017968,0.23344923935329415,-0.39317892425103024,0.39001052073230297,0.13064774829166348,0.11903557789377128,-0.15530652028858227,0.03672941201475183,-0.001697414894261673,0.06710203608661258,0.14596169265297715,-0.01565201549922346,0.1656332332118282,-0.016636842527321116,-0.05228342089594329,0.20182805758391265,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.675,1.0,1.0,0.0,1.0,3.374662469471395,-0.013502748233850025,0.6106645357194436,0.9880233255025123,0.03272256649704025,0.07657150576020146,0.12990745340211246,0.010517734644454053,0.0031328793209948417,-0.004754918089405731,-0.015739845662178772,-0.04475188136654049,-0.062435792750540016,-0.6443513113881938,-0.4607745696028302,-0.14232845216319415,0.013465069567904515,0.9778794047725891,-0.8902211984600658,0.027366207599425447,-1.0039981611249331,1.2056649751622504,0.23331069190603035,-0.39361239867009296,0.3916895011876249,0.13075766616189588,0.11944691960231957,-0.15569521364278027,0.03682371867980025,-0.0016713408288948628,0.06736370934240954,0.14904381716685158,0.004041613463101612,0.1323450097169676,-0.0166143064365043,-0.05175087905330611,0.20112980694418803,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.683333333333334,1.0,1.0,0.0,1.0,3.374733673732358,-0.013452933688003373,0.610615140707274,0.9880735025843941,0.032662008438382906,0.07638727393987271,0.12964926190587242,0.010613011100366814,0.0030959353599654457,-0.004743205401904949,-0.01576629224958538,-0.04474385764087429,-0.06247263778121165,-0.6432612058807301,-0.4597774585668129,-0.14362753628694966,0.013772327361112915,0.9778655860345421,-0.889658737773969,0.028620745252199258,-1.0038824803347883,1.2066292762637463,0.23317233424601908,-0.3940414389019187,0.39336268418137277,0.13086772332451257,0.11986119157436304,-0.15608603759157402,0.036918265692418746,-0.001645049574274804,0.0676283283157697,0.15196216366868395,0.023704033643907607,0.09912263137572985,-0.016591313231857363,-0.05121919791749807,0.20043663372324882,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.691666666666666,1.0,1.0,0.0,1.0,3.374805776998262,-0.013403256116726152,0.6105657230532533,0.9881235950545025,0.03260132184714928,0.07620305723361011,0.1293909147294361,0.010709151481103671,0.003058821426678685,-0.004731510670269588,-0.015792823860724746,-0.04473605124949011,-0.06250932292896093,-0.6421701826661186,-0.4587768830765908,-0.1449298861230537,0.014080373996111494,0.9778519872796845,-0.8890940596548029,0.029898910327236846,-1.0036030938975347,1.2073170190185125,0.23303417001883273,-0.3944660519687179,0.39503011174967906,0.130977911502268,0.12027837689558507,-0.15647896773714143,0.03701302731293755,-0.0016185486640751812,0.06789588978439731,0.15471223299147033,0.04332666217034209,0.06597596710365305,-0.016567903513097226,-0.05068834628654151,0.199748477243179,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7,1.0,1.0,0.0,1.0,3.3748787863789684,-0.013353715925383614,0.6105162821290812,0.9881736027850548,0.032540506597939785,0.07601885472428954,0.12913241246958632,0.010806154573683063,0.003021548516657864,-0.004719835301725075,-0.015819427788190014,-0.0447284594617368,-0.06254587021368219,-0.6410782406890256,-0.4577728189518865,-0.14623551908256868,0.014389211149661874,0.9778386102234742,-0.8885271396108957,0.031199282468723763,-1.003160369298616,1.2077288757154738,0.2328962025208008,-0.39488624467336103,0.3966918254687591,0.13108822139739962,0.12069844528032503,-0.15687396056261405,0.037107975730456405,-0.0015918458146435555,0.06816638284763199,0.15728986948893653,0.06290086543610851,0.03291498308013896,-0.01654412040819675,-0.05015830267038002,0.19906528744016883,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.708333333333334,1.0,1.0,0.0,1.0,3.374952708939334,-0.013304313443642898,0.610466817310984,0.9882235256576647,0.03247956260899929,0.07583466551521917,0.12887375562644215,0.010904016584659374,0.0029841286742432766,-0.004708181424851504,-0.015846091103145103,-0.04472107996713745,-0.06258230272604183,-0.6399853789761619,-0.45676524232191873,-0.14754445213243061,0.014698840258285767,0.9778254565161071,-0.8879579532740091,0.032520408152052455,-1.0025547461402662,1.2078656020698482,0.2327584346786961,-0.3953020236798909,0.39834786654034854,0.13119864255870084,0.12112135254858325,-0.15727095277149883,0.03720308115078393,-0.0015649490119451492,0.06843978871078127,0.1596912747924019,0.08241797887038604,-5.027170918214807e-05,-0.016520009376713718,-0.04962905513010374,0.1983870241101282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.716666666666667,1.0,1.0,0.0,1.0,3.3750275516754784,-0.013255048922571075,0.6104173279775915,0.9882733635638716,0.032418489842957,0.07565048872875035,0.12861494459928796,0.011002731082185038,0.0029465749347808183,-0.004696551860037667,-0.015872800720098824,-0.044713910797139544,-0.06261864445829968,-0.6388915966463806,-0.45575412974274343,-0.14885670162876033,0.01500926250217494,0.9778125277399418,-0.887386476465716,0.033860803715263794,-1.0017867363174429,1.2077280378536541,0.2326208690311889,-0.3957133955921961,0.39999827587059456,0.13130916327963593,0.12154704036716812,-0.15766986100558045,0.03729831191391468,-0.0015378665836851546,0.06871608059631162,0.16191301998905921,0.10186932650481761,-0.03290967956319335,-0.01649561798382826,-0.04910060101214864,0.19771365610479652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.725,1.0,1.0,0.0,1.0,3.375103321490934,-0.013205922532284257,0.6103678135080377,0.9883231164055549,0.03235728830730893,0.07546632350514225,0.12835597968314533,0.011102288972473142,0.0029089012555512618,-0.00468495008416852,-0.015899543464136523,-0.044706950250572544,-0.06265492012865895,-0.6377968929215013,-0.45473945831579926,-0.1501722831491903,0.015320478790184345,0.977799825406379,-0.8868126852640705,0.03521895848520344,-1.0008569240318526,1.2073171074104616,0.23248350771229898,-0.3961203670300934,0.40164309414209515,0.1314197705219744,0.12197543619164586,-0.15807058184941436,0.037393634634841494,-0.0015106072588211283,0.06899522375305445,0.16395205614034167,0.1212462402101755,-0.06565306773538282,-0.016470995650236242,-0.048572946601094236,0.19704516049526832,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.733333333333333,1.0,1.0,0.0,1.0,3.3751800251729387,-0.013156934360162941,0.6103182732802851,0.9883727840952315,0.03229595805463743,0.07528216900166296,0.1280968610661109,0.011202678503280156,0.0028711224381832642,-0.004673380190629312,-0.015926306139756485,-0.044700196823074,-0.06269115500046739,-0.636701267137681,-0.453721205806216,-0.15149121132625057,0.015632489746088964,0.9777873509522947,-0.8862365560698318,0.03659333798426949,-0.9997659656472733,1.2066338200580644,0.2323463524370183,-0.39652294470221433,0.403282361878849,0.13153044986002893,0.12240645337672218,-0.15847299207083276,0.037489014362786476,-0.0014831802173564945,0.06927717555055057,0.16580572307264202,0.14054007848090855,-0.09827022163292565,-0.016446193383530816,-0.048046106711003844,0.1963815217192122,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.741666666666667,1.0,1.0,0.0,1.0,3.3752576693690837,-0.013108084409642114,0.6102687066696764,0.9884223665562396,0.032234499182567114,0.07509802439191007,0.12783758882747928,0.011303885292078724,0.002833254043698368,-0.004661846845900338,-0.015953075601025875,-0.04469364914014244,-0.06272737469843534,-0.6356047187571675,-0.45269935075952056,-0.15281349968370417,0.015945295696230787,0.9777751057360897,-0.8856580656715614,0.03798238720308081,-0.9985145893905041,1.2056792703832462,0.23220940448924013,-0.3969211354752768,0.404916119504082,0.13164118544321868,0.12283999142472024,-0.15887694905545202,0.03758441475588417,-0.001455595130575027,0.06956188564415156,0.16747175638847908,0.15974224465310272,-0.1307508974902527,-0.016421263493686666,-0.04752010422646835,0.19572273072157476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.75,1.0,1.0,0.0,1.0,3.3753362605645347,-0.013059372599583579,0.6102191130476997,0.9884718637228086,0.032172911833451674,0.07491388886533695,0.12757816293665605,0.011405892375769465,0.0027953123018005614,-0.004650355243062426,-0.015979838822190773,-0.044687305894336816,-0.06276360502311054,-0.6345072473802941,-0.451673872615804,-0.15413916047717477,0.016258896658687034,0.9777630910334518,-0.8850771913090959,0.039384533924077474,-0.9971035949030549,1.2044546384332269,0.2320726647121235,-0.39731494643932214,0.4065444073908753,0.1317519599758321,0.12327593635632073,-0.15928229140976358,0.03767979826764689,-0.0014278621943608627,0.0698492962028574,0.16894829266168324,0.1788442044504257,-0.1630848344664937,-0.016396259297479787,-0.04699496960072436,0.19506878409314643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.758333333333333,1.0,1.0,0.0,1.0,3.3754158050599763,-0.013010798764227937,0.6101694917809765,0.9885212755400186,0.032111196193798326,0.07472976162696485,0.12731858325286916,0.01150868027892081,0.002757314015954217,-0.004638911053003134,-0.016006582967878692,-0.044681165786670564,-0.06279987176538328,-0.6334088527575703,-0.45064475182024855,-0.15546820454053356,0.0165732923340249,0.9777513080328504,-0.8844939107348471,0.04079819208077553,-0.9955338526496637,1.2029611898088046,0.2319361335009488,-0.3977043849686222,0.40816726590563446,0.13186275471173126,0.12371416119302259,-0.15968883971734904,0.03777512634255992,-0.0013999921542184879,0.07013934219480156,0.17023387279320082,0.19783750275309986,-0.19526176611571522,-0.016371234815028557,-0.04647074032199772,0.19441968321910585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.766666666666666,1.0,1.0,0.0,1.0,3.3754963089504426,-0.012962362653722498,0.6101198422304552,0.9885706019636533,0.03204935249342993,0.07454564189726794,0.12705884952566876,0.011612227099964796,0.002719276464898905,-0.004627520374109127,-0.01603329546269763,-0.04467522747183936,-0.06283620052314104,-0.6323095348017652,-0.4496119699292536,-0.1568006411391306,0.0168884820977297,0.9777397578308815,-0.8839082022725159,0.04222176513729749,-0.9938063031905032,1.2012002756646316,0.2317998107985397,-0.3980894587780221,0.40978473544452704,0.13197354946309803,0.12415452653134706,-0.16009639742249338,0.037870359619716215,-0.0013719963220792941,0.07043195172214967,0.1713274435220334,0.21671377949839643,-0.22727143118054016,-0.016346244461074022,-0.04594746035055386,0.1937754334401709,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.775,1.0,1.0,0.0,1.0,3.375577778105172,-0.012914063935215114,0.610070163750811,0.9886198429599491,0.03198738100439163,0.07436152891221554,0.1267989613962059,0.011716508613313375,0.0026812173019969934,-0.004616189680321092,-0.016059964059013915,-0.0446694895079056,-0.06287261652092334,-0.631209293599852,-0.44857550971139276,-0.15813647783090845,0.017204464994353505,0.9777284414274824,-0.8833200448728112,0.04365364947280942,-0.9919219563246904,1.1991733326224623,0.23166369609326423,-0.39847017597446477,0.41139685646297064,0.1320843226232027,0.12459688120766255,-0.16050475183480462,0.03796545814019024,-0.0013438865880188722,0.07072704640077587,0.1722283570982798,0.23546478462254328,-0.25910358366210584,-0.01632134273503616,-0.04542517953410541,0.19313604323163203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.783333333333333,1.0,1.0,0.0,1.0,3.3756602181486106,-0.012865902194497623,0.6100204556900429,0.9886689985052453,0.03192528203961196,0.0741774219234543,0.12653891839927253,0.011821498385990156,0.0026431544532869665,-0.004604925768550225,-0.016086576902614707,-0.04466395031016769,-0.06290914443489105,-0.6301081294247118,-0.44753535524245924,-0.15947572033637733,0.017521239733399536,0.9777173597210812,-0.8827294181658363,0.04509223775560215,-0.9898818901134608,1.1968818826035965,0.23152778841962243,-0.3988465451035905,0.41300366949838757,0.13219505120017017,0.12504106303693696,-0.16091367523526912,0.03806038155731016,-0.0013156754237275692,0.07102454177883466,0.17293636914048366,0.2540823919657953,-0.2907480021217568,-0.016296583912424056,-0.0449039530072326,0.1925015234074623,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.791666666666666,1.0,1.0,0.0,1.0,3.3757436344426712,-0.012817876938181065,0.6099707173892576,0.9887180685855426,0.03186305595132625,0.07399332019861833,0.126278719966074,0.011927167906640425,0.0026051060155019294,-0.004593735705646112,-0.016113122595324346,-0.04465860810932783,-0.06294580822410606,-0.6290060427465158,-0.4464914919941105,-0.16081837241816294,0.01783880468697534,0.9777065135037536,-0.8821363025098307,0.04653592229181748,-0.9876872497919271,1.1943275325870997,0.2313920863613905,-0.399218575191252,0.41460521518642834,0.13230571086298326,0.12548689962011195,-0.16132292607337395,0.03815508934708972,-0.0012873758811049463,0.07132434779056451,0.1734516347135759,0.2725586120667267,-0.322194498171573,-0.016272021741263742,-0.04438384057905642,0.1918718863517921,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.8,1.0,1.0,0.0,1.0,3.3758280320703373,-0.012769987596375864,0.6099209481826361,0.9887670531959746,0.03180070312927916,0.07380922302175015,0.12601836542770775,0.012033486726209897,0.002567090154727123,-0.0045826267752349745,-0.016139590254181588,-0.04465346091368359,-0.06298263096966938,-0.6279030342436621,-0.4454439069154574,-0.16216443577093356,0.018157157889184365,0.9776959034563961,-0.8815406790359935,0.04798309833416175,-0.9853392465790154,1.191511974300737,0.23125658805726804,-0.39958627577990813,0.41620153427091744,0.13241627599770434,0.125934209208165,-0.16173225023910942,0.03824954101690321,-0.0012590015845526104,0.07162636923850885,0.17377470267740613,0.29088560378109696,-0.35343292411367244,-0.01624770914563367,-0.043864906114007285,0.19124714528054643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.808333333333334,1.0,1.0,0.0,1.0,3.3759134158207016,-0.0127222335258518,0.6098711473975695,0.9888159523401979,0.03173822399871642,0.07362512969382318,0.12575785401930636,0.012140422608446439,0.002529125006658737,-0.004571606425027401,-0.016165969566599478,-0.04464850647533762,-0.06301963472314868,-0.6267991048132208,-0.44439258850730773,-0.1635139099221481,0.01847629703725706,0.977685530144011,-0.8809425296891888,0.049432167336440916,-0.9828391563955755,1.1884369838518718,0.23112129120896327,-0.39994965695981877,0.4177926676077708,0.1325267197717439,0.12638280161052284,-0.16214138239483866,0.038343696310679035,-0.0012305667174050683,0.0719305062981257,0.17390650836817748,0.309055684673758,-0.3844531796928363,-0.016223697939298787,-0.043347216910628594,0.19062731353969298,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.816666666666666,1.0,1.0,0.0,1.0,3.375999790175493,-0.01267461401364352,0.6098213143549566,0.9888647660297105,0.03167561901818622,0.07344103953334992,0.1254971848848064,0.012247941687819269,0.0024912285796777718,-0.004560682214793977,-0.016192250840691938,-0.04464374226051135,-0.06305684036497773,-0.6256942555807997,-0.44333752688861533,-0.16486679214418087,0.01879621949436235,0.977675394011106,-0.8803418372643581,0.05088154014029804,-0.9801883185011194,1.1851044213058564,0.23098619309161306,-0.40030872939508527,0.41937865616324566,0.1326370142069888,0.12683247914483164,-0.1625500473589725,0.038437515407667155,-0.001202086004656877,0.07223665504142884,0.17384836468593276,0.32706134013216426,-0.41524521792864366,-0.016200038552640628,-0.04283084308476348,0.19001240394087682,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.825,1.0,1.0,0.0,1.0,3.37608715929714,-0.012627128281067376,0.6097714483696526,0.9889134942831029,0.03161288867716706,0.07325695187706674,0.12523635708229547,0.012356008634355087,0.00245341866109133,-0.00454986176527551,-0.016218425050743432,-0.04463916542319147,-0.06309426747424447,-0.624588487909771,-0.44227871385489387,-0.16622307737813097,0.019116922294051514,0.9776654953772668,-0.8797385854384984,0.05232964008120646,-0.9773881340600394,1.1815162302197277,0.23085129056641926,-0.4006635043445648,0.4209595410067854,0.13274713025915208,0.1272830376115941,-0.162957961521229,0.03853095911410913,-0.0011735746910934708,0.07254470797208645,0.17360195167441278,0.3448952311672926,-0.44579904999651365,-0.016176779774490502,-0.04231585695819717,0.18940242813461516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.833333333333334,1.0,1.0,0.0,1.0,3.376175527018416,-0.01257977548811203,0.6097215487510617,0.9889621371252524,0.03155003349354106,0.07307286608068593,0.12497536958988739,0.012464586823073446,0.0024157127274914464,-0.004539152708518568,-0.016244483877260747,-0.04463477278202604,-0.06313193421062127,-0.6234818034098139,-0.4412161429284221,-0.1675827581695347,0.019438402146264168,0.9776558344329211,-0.8791327587981567,0.05377490600153825,-0.9744400646483312,1.1776744371392478,0.23071658009537155,-0.4010139936777219,0.4225353632988226,0.13285703790221204,0.12773426728346804,-0.16336483427549064,0.0386239890460148,-0.0011450485154851364,0.07285455456757406,0.17316930468763786,0.3625502008750403,-0.47610474913122314,-0.01615396851087414,-0.04180233245905329,0.1887973960264111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.841666666666667,1.0,1.0,0.0,1.0,3.3762648968336677,-0.012532554738163011,0.609671614803859,0.9890106945864646,0.031487054010933366,0.0728887815197073,0.12471422131207086,0.01257363850633689,0.0023781278600200116,-0.004528562639654253,-0.016270419741019334,-0.04463056080050343,-0.06316985720873333,-0.6223742039447341,-0.4401498094001694,-0.1689458246160558,0.019760655444818427,0.977646411235342,-0.8785243428623721,0.05521579515933376,-0.9713456307121221,1.1735811510675407,0.2305820577579047,-0.40136020988554905,0.42410616427389225,0.1329667062174411,0.12818595390543308,-0.16377036946296997,0.03871656780077129,-0.0011165236825028124,0.07316608182465156,0.17255280124519795,0.3800192795353263,-0.5061524535303041,-0.016131649563195793,-0.04129034453773439,0.18819731523344818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.85,1.0,1.0,0.0,1.0,3.3763552718916463,-0.012485465083018213,0.60962164582884,0.9890591667015743,0.03142395079594176,0.0727046975902805,0.12445291108647939,0.012683124987510706,0.0023406806650024857,-0.004518099070459366,-0.016296225831255243,-0.044626525569443784,-0.06320805148578595,-0.6212656916395232,-0.43907971036333154,-0.17031226432725086,0.020083678276277023,0.9776372257048794,-0.8779133241010791,0.05665078602229155,-0.9681064099894091,1.1692385629137427,0.23044771926931829,-0.40170216608668413,0.42567198521938004,0.13307610348468613,0.12863787969145335,-0.16417426680832237,0.03880865911684586,-0.0010880168321425465,0.07347917479925803,0.17175514668837155,0.3972956883413348,-0.5359323682352457,-0.01610986542724735,-0.040779968601607486,0.18760219058426064,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.858333333333333,1.0,1.0,0.0,1.0,3.3764466549899157,-0.01243850552815366,0.6095716411238824,0.989107553509009,0.03136072443527439,0.072520613710118,0.12419143769102141,0.012793006794804397,0.0023033872003548873,-0.004507769384990293,-0.01632189612763913,-0.04462266279155113,-0.06324653036283313,-0.620156268886656,-0.4380058447386452,-0.17168206239619452,0.02040746643009919,0.977628277621473,-0.8772996899490512,0.058078380937473285,-0.9647240359064332,1.1646489449302866,0.2303135600007839,-0.40203987602890917,0.4272328674502966,0.13318519727473443,0.12908982430688165,-0.16457622333335198,0.03890022802083018,-0.0010595450069983414,0.07379371713984506,0.17077935875256564,0.41437284175527056,-0.5654347659738468,-0.016088656113613653,-0.04027127996925728,0.18701202365847824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.866666666666667,1.0,1.0,0.0,1.0,3.376539048570833,-0.012391675038194487,0.6095215999850153,0.9891558550498255,0.03129737553282217,0.07233652931945245,0.12392979985131426,0.01290324385328244,0.0022662629083872897,-0.004497580797088154,-0.016347425415815624,-0.044618967767806716,-0.06328530539936546,-0.6190459383516109,-0.4369282132915502,-0.17305520138280672,0.020732015409957526,0.9776195666214295,-0.8766834288154151,0.059497108668167646,-0.9612001959601546,1.159814650147512,0.23017957500075806,-0.40237335408617175,0.4287888522803547,0.13329395454231285,0.12954156583377396,-0.16497593474335437,0.03899124095987645,-0.0010311256199946328,0.07410959160746078,0.16962875117743123,0.4312443484986406,-0.5946499869501176,-0.016068058991459133,-0.039764353350908443,0.18642681236795133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.875,1.0,1.0,0.0,1.0,3.3766324547190454,-0.012344972542548887,0.6094715217075911,0.9892040713667255,0.031233904706685814,0.0721524438820402,0.1236679962483648,0.013013795653572503,0.0022293225552774128,-0.004487540310186857,-0.01637280929663062,-0.04461543538489894,-0.06332438634159586,-0.6179347029776174,-0.4358468186414156,-0.17443166130858376,0.021057320446097132,0.9776110921944731,-0.8760645300889268,0.06090552679043047,-0.9575366300981225,1.1547381118144513,0.23004575901759292,-0.4027026152514243,0.43033998098976245,0.1334023417175545,0.12999288170651768,-0.16537309677085332,0.03908166591913016,-0.001002776421226148,0.07442668057795476,0.16830691647943014,0.44790401118865786,-0.6235684375682871,-0.016048108655902227,-0.03925926235431754,0.18584655057668154,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.883333333333333,1.0,1.0,0.0,1.0,3.376726875160473,-0.012298396941161163,0.6094214055875496,0.9892522025030575,0.03117031258618207,0.07196835688621123,0.1234060255264367,0.013124621416445771,0.002192580177348604,-0.0044776546792395224,-0.016398044188878746,-0.04461206010324011,-0.06336378108407326,-0.6168225659896517,-0.4347616652631082,-0.17581141966232094,0.021383376508609695,0.9776028536810757,-0.8754429841391158,0.062302223942824815,-0.9537351291070103,1.1494218428547072,0.2299121065231597,-0.4030276751254104,0.43188629478996604,0.13351032479465452,0.1304435496121481,-0.16576740646830845,0.03917147252415626,-0.0009745154654505761,0.07474486652574441,0.1668177080127764,0.4643458246402199,-0.6521805880825626,-0.0160288368193906,-0.03875607901799305,0.1852712277569668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.891666666666666,1.0,1.0,0.0,1.0,3.3768223112627074,-0.012251947110342746,0.6093712509227752,0.9893002485018112,0.031106599808850208,0.07178426784597057,0.12314388630105012,0.01323568025170268,0.0021560490342832847,-0.004467930374986896,-0.016423127326027548,-0.04460883594472545,-0.06340349564444633,-0.6157095308977065,-0.43367275948121314,-0.1771944514163889,0.021710178321499737,0.9775948502700489,-0.8748187823134977,0.06368582192397675,-0.9497975330207855,1.1438684353464086,0.22977861173726974,-0.4033485499017242,0.4334278347857119,0.1336178694169754,0.1308933483446717,-0.16615856343706048,0.03926063212787337,-0.0009463610807936007,0.07506403248092264,0.16516522144717258,0.48056397286359687,-0.6804769691638102,-0.016010272227140465,-0.03825487337456135,0.18470082868015214,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9,1.0,1.0,0.0,1.0,3.376918764036769,-0.01220562190864119,0.6093210570145364,0.9893482094046107,0.03104276701747921,0.07160017630215845,0.12288157716705662,0.013346931310123007,0.002119741569577795,-0.004458373550277933,-0.016448056746445505,-0.0446057564803522,-0.06344353415041694,-0.6145956014993688,-0.4325801094573637,-0.17858072905293862,0.022037720377407585,0.9775870809963958,-0.8741919169311004,0.06505497763361102,-0.9457257295592837,1.1380805600353103,0.22964526865270735,-0.40366525634831973,0.43496464193463524,0.13372494095762244,0.13134205861647708,-0.1665462709936516,0.03934911788031091,-0.0009183318405647789,0.07538406246059282,0.16335377578792082,0.49655282478530793,-0.7084481673787701,-0.015992440596994673,-0.03775571304381553,0.1841353331376394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.908333333333333,1.0,1.0,0.0,1.0,3.377016234140137,-0.012159420182705969,0.609270823169016,0.9893960852507113,0.030978814857181246,0.07141608182367258,0.12261909670674193,0.013458333928142312,0.0020836693778276,-0.004448990008488975,-0.016472831277928368,-0.044602814816367825,-0.06348389883886038,-0.6134807818817462,-0.4314837251709385,-0.17997022259961643,0.022365996952838252,0.9775795447393728,-0.8735623812724879,0.06640838485377543,-0.941521652607697,1.1320609658900957,0.22951207106065316,-0.4039778117857878,0.43649675700467255,0.13383150459347792,0.13178946381181555,-0.16693023725800504,0.039436904783417964,-0.0008904465362458147,0.0757048418696682,0.16138789406475146,0.5123069287311743,-0.7360848195756686,-0.015975364582575535,-0.03725866285609003,0.18357471569004136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.916666666666666,1.0,1.0,0.0,1.0,3.3771147218809885,-0.012113340773118576,0.6092205486989204,0.9894438760760058,0.03091474397252412,0.07123198400877043,0.12235644349790056,0.013569847763752405,0.0020478431789678407,-0.004439785174125169,-0.01649745051651446,-0.04460000357848704,-0.0635245900660937,-0.6123650764228108,-0.43038361839383343,-0.18136289967390537,0.022695002123797884,0.9775722402207917,-0.872930169566606,0.06774477586802355,-0.9371872807470975,1.1258124797090492,0.2293790125763311,-0.4042862340625879,0.43802422052946927,0.1339375253725672,0.13223535068082937,-0.16731017615936872,0.03952396972982185,-0.0008627241544889586,0.0760262578693438,0.15927228381149183,0.5278210057121302,-0.7633776061728526,-0.01595906375944589,-0.03676378450522155,0.183018945438278,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.925,1.0,1.0,0.0,1.0,3.3772142272235355,-0.012067382520149331,0.609170232925177,0.9894915819120432,0.030850555004748818,0.07104788248645824,0.12209361612184368,0.013681432923249767,0.0020122727992902567,-0.004430764065009319,-0.01652191479968647,-0.04459731489385001,-0.06356560632820651,-0.6112484897922034,-0.42927980265959137,-0.1827587255356059,0.023024729781668616,0.9775651660034647,-0.8722952769746655,0.06906292291730029,-0.9327246358458282,1.1193380057872149,0.2292460866646624,-0.4045905415275415,0.4395470727619772,0.13404296827387752,0.13267950997629563,-0.16768580836290237,0.039610291525707525,-0.0008351838589981675,0.07634819971320095,0.1570118174552454,0.5430899415537183,-0.790317243347971,-0.015943554633885415,-0.03627113623261513,0.18246798581507018,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.933333333333334,1.0,1.0,0.0,1.0,3.3773147497943934,-0.012021544269412628,0.6091198751787199,0.9895392027850651,0.030786248589084214,0.07086377691798658,0.12183061317129322,0.013793161055967552,0.001976896645318007,-0.0044219864361328,-0.016546326907332966,-0.04459462296440971,-0.06360706805155938,-0.6101310269515795,-0.42817229322756184,-0.1841576631466204,0.023355173649226343,0.9775583204898084,-0.871657699571386,0.07036163949227764,-0.9281357817212021,1.1126405256532497,0.22911328666576633,-0.40489075299979815,0.4410653536263871,0.13414789071365396,0.13312042905106014,-0.16805438151619834,0.03969607759169089,-0.0008077648082949196,0.07667051057900443,0.15461159303271327,0.5581092316573977,-0.8168947394755133,-0.01592875709561903,-0.035780441627842885,0.18192135238241813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.941666666666666,1.0,1.0,0.0,1.0,3.37741629080839,-0.011975825521316163,0.6090694735564247,0.9895867387232792,0.03072182431910217,0.07067966788999021,0.12156743231841043,0.013904772753540271,0.001941865041069721,-0.004413330321621686,-0.016570471419503834,-0.04459216696386269,-0.06364872913666224,-0.6090126916136425,-0.4270611288420737,-0.1855596318942092,0.023686331074863464,0.9775517032566597,-0.8710174351316821,0.07163978280117884,-0.9234228153182049,1.105723093462623,0.2289806073797354,-0.40518688222133886,0.44257909530168416,0.13425209067581267,0.13356026234812357,-0.1684200100952249,0.03978083755873052,-0.0007807264232906341,0.07699331958844091,0.15207656219755505,0.5728732530894498,-0.8431004294816979,-0.0159148972999279,-0.035292313971464484,0.18137973451558875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.95,1.0,1.0,0.0,1.0,3.3775188454555694,-0.01193022384821215,0.6090190301655777,0.9896341897262337,0.03065728499748968,0.07049555325478138,0.12130407401561467,0.014016231929689548,0.0019071796435829059,-0.0044048289072225934,-0.016594381425017415,-0.04458990928598708,-0.06369057887907191,-0.6078934921069826,-0.4259462888550931,-0.18696466331487416,0.024018187608538518,0.9775453083827536,-0.8703744775782453,0.07289624886223689,-0.9185878941697113,1.0985888518285547,0.2288480383774342,-0.4054789582326559,0.4440883492016469,0.13435550622962644,0.1339992282901259,-0.1687833720436216,0.03986460127639861,-0.0007539562134617483,0.07731629075218738,0.14941203187871788,0.5873771910435077,-0.8689249236301233,-0.01590192941629931,-0.034806945531721256,0.18084329065434002,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.958333333333334,1.0,1.0,0.0,1.0,3.377622414292503,-0.011884738842465738,0.6089685426341716,0.9896815558014969,0.030592629917013493,0.0703114338739079,0.12104053605170612,0.014127726309200585,0.0018727055891716617,-0.004396600948161236,-0.01661826235180179,-0.04458759926262207,-0.0637328494431122,-0.606773433176482,-0.4248278083705716,-0.18837268809493624,0.024350741096136774,0.9775391373197687,-0.8697288302858123,0.07412998333249081,-0.9136331954674798,1.091241011402121,0.2287155752227971,-0.4057669979802009,0.44559315014592316,0.13445827753427952,0.1344347020523129,-0.1691396347624191,0.03994781261713064,-0.0007272660756418858,0.07763916356108957,0.14662351425729664,0.601617347070571,-0.8943594507124963,-0.015889660777785863,-0.03432376480464239,0.1803111573107341,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.966666666666667,1.0,1.0,0.0,1.0,3.3777269957616705,-0.011839369401553335,0.6089180105204569,0.9897288369452918,0.030527859789758523,0.07012730950571361,0.12077681713419433,0.014239105852755748,0.0018385248203958843,-0.004388561232699855,-0.01664198372469237,-0.04458537575811859,-0.0637754093683233,-0.6056525208147446,-0.42370571048755457,-0.18978365722758114,0.024683984485490695,0.9775331872814929,-0.8690804915188938,0.0753399740998585,-0.9085609383852018,1.0836828609833464,0.22858321069780443,-0.40605102097939993,0.4470935351568258,0.13456030708940414,0.1348673677791723,-0.16949004089861275,0.040030182916452814,-0.0007009020355508433,0.07796214735730445,0.1437162756091176,0.6155889662079628,-0.9193946494563932,-0.01587824408704308,-0.03384298380151973,0.1797834813252841,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.975,1.0,1.0,0.0,1.0,3.3778325879118185,-0.011794114467055724,0.6088674332887059,0.9897760331443325,0.03046297520578699,0.06994317996918156,0.12051291603176684,0.014350330060109865,0.0018046414171562896,-0.004380721785529528,-0.016665563263896267,-0.044583220923637264,-0.06381824681807378,-0.6045307613916586,-0.4225800189075854,-0.19119752210991312,0.025017910811410988,0.9775274556191762,-0.8684294611631905,0.07652525459264277,-0.9033733793640137,1.0759177672445144,0.22845093782134637,-0.4063310477102262,0.44858954150134456,0.13466155213224695,0.13529711764162178,-0.16983454564354072,0.040111715656645855,-0.0006748566314174198,0.07828507950194963,0.1406957906950454,0.6292876520673696,-0.9440211818475719,-0.015867661644967113,-0.033364685630506985,0.1792602510877872,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.983333333333333,1.0,1.0,0.0,1.0,3.3779391884987913,-0.011748973023280752,0.6088168103881132,0.9898231443741051,0.030397976720658602,0.06975904514789796,0.12024883156481544,0.014461364794323844,0.0017710582269458066,-0.004373087004810899,-0.016689007152627937,-0.04458111899253206,-0.06386134931076697,-0.6034081616125405,-0.42145075852686087,-0.19261423298830682,0.025352513079768126,0.9775219396709692,-0.8677757401938613,0.07768490394477592,-0.8980728108507456,1.0679491746192202,0.22831874967038832,-0.4066070990732417,0.45008120600828894,0.1347619745945794,0.13572380329033185,-0.17017299085763993,0.04019240633092232,-0.0006491379642614703,0.0786078454857897,0.13756755514539504,0.6427091275496433,-0.9682296934519252,-0.015857907141996752,-0.03288890974471159,0.17874140002080985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.991666666666667,1.0,1.0,0.0,1.0,3.3780467950098942,-0.011703944096941638,0.608766141283065,0.9898701705984447,0.030332864865570176,0.06957490498051956,0.11998456261288247,0.01457217767785714,0.0017377775669074357,-0.004365658493418685,-0.016712320533990604,-0.044579055648390514,-0.06390470248290345,-0.602284728481749,-0.4203179555194132,-0.1940337386242071,0.025687784250259693,0.9775166366531052,-0.867119330405094,0.07881804717839935,-0.8926615605715197,1.0597806056869823,0.22818663936897976,-0.4068791962059714,0.4515685648350247,0.1348615392236474,0.13614727169672602,-0.1705051952882991,0.040272249641108426,-0.0006237627897132114,0.07893035299187723,0.13433707961835378,0.6558491895417395,-0.9920107702805314,-0.01584897418821174,-0.0324156800290476,0.1782268415693189,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0,1.0,1.0,0.0,1.0,3.3781554046763365,-0.011659026759756073,0.6087154254635918,0.9899171117688947,0.030267640148385098,0.06939075945899872,0.11972010812173842,0.01468273742581485,0.0017048010918048607,-0.004358436670995529,-0.01673550859911129,-0.04457701653470354,-0.06394829035859922,-0.6011604692921464,-0.41918163733191544,-0.1954559862431118,0.026023717240453267,0.977511543624474,-0.8664602343106633,0.07992385527174849,-0.88714199102505,1.0514156617812114,0.2280546001005848,-0.4071473604070592,0.4530516533677776,0.13496021150513293,0.13656737212808467,-0.17083097688926852,0.04035124106309934,-0.0005987507301496997,0.07925251847607395,0.13100987532579683,0.6687036861849416,-1.0153549150497643,-0.01584085470982377,-0.03194501289477403,0.17771647905186483,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.008333333333333,1.0,1.0,0.0,1.0,3.3782650144834494,-0.01161422013184176,0.6086646624504253,0.9899639678239801,0.030202303053128265,0.0692066086303158,0.11945546710962664,0.01479301375911772,0.0016721297442540838,-0.004351421190810289,-0.016758576719145116,-0.0445749866341744,-0.06399209554775512,-0.6000353916233301,-0.4180418326506118,-0.1968809215723616,0.026360304934644682,0.9775066574742693,-0.8657984550971595,0.08100154510049597,-0.881516499135104,1.0428580237694862,0.22792262512381603,-0.407411613087551,0.4545305061525558,0.1350579569845234,0.13698395844449096,-0.1711501600078541,0.04042937720701856,-0.0005741225064692657,0.07957426311806293,0.12759143905374387,0.6812684984185968,-1.0382525267347553,-0.01583353874990423,-0.03147691921214557,0.17721020772176632,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.016666666666666,1.0,1.0,0.0,1.0,3.378375621180879,-0.011569523385212754,0.6086138517987527,0.9900107386884612,0.03013685403918344,0.06902245259974714,0.11919063867294223,0.014902977438010438,0.001639763745925127,-0.004344611026017739,-0.016781530433561898,-0.04457294998683255,-0.06403609936982431,-0.5989095033424043,-0.4168985713578406,-0.19830848890990938,0.026697540193903576,0.9775019749160329,-0.8651339965920289,0.08205037925597755,-0.8757875160514067,1.0341114530022988,0.22779070778808638,-0.4076719757272616,0.456005156829807,0.1351547410595244,0.13739688998015587,-0.17146257796254227,0.040506655887675505,-0.000549899464323822,0.07989551169500286,0.1240872387436287,0.6935395220668261,-1.0606938799305432,-0.015827014529462002,-0.03101140459463525,0.17670791483943904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.025,1.0,1.0,0.0,1.0,3.3784872212931294,-0.01152493574716461,0.6085629931018097,0.9900574242725901,0.030071293540530158,0.06883829153497172,0.11892562199152033,0.015012600308400025,0.0016077026064435572,-0.004338004466761448,-0.016804375402014425,-0.04457088952210452,-0.064080281939977,-0.5977828126056713,-0.41575188448427586,-0.19973863120507063,0.02703541586610594,0.9774974924831973,-0.8644668632355761,0.08306966574622311,-0.8699575071006569,1.0251797924373105,0.227658841548325,-0.4079284698307949,0.45747563806654645,0.13525052888658795,0.13780603187996232,-0.17176807404385097,0.04058307609643305,-0.000526103480200657,0.08021619227254195,0.12050269983241435,0.7055126495497799,-1.082669103201206,-0.01582126857492483,-0.03054846928629118,0.17620947928031594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.033333333333333,1.0,1.0,0.0,1.0,3.3785998111304356,-0.011480456503489455,0.6085120859946342,0.9901040244713666,0.03000562196512248,0.06865412567080041,0.11866041633361835,0.015121855335846564,0.0015759451410761087,-0.004331599093424956,-0.01682711734436445,-0.04456878692351812,-0.06412462223702492,-0.5966553278609612,-0.4146018041598412,-0.20117129014397356,0.027373924795510794,0.9774932065246962,-0.8637970600541532,0.08405875758651779,-0.8640289718922437,1.0160669679489454,0.2275270199785043,-0.4081811168820331,0.45894198148447896,0.13534528530097623,0.1382112551766268,-0.17206650190203454,0.0406586379320624,-0.000502756984850361,0.0805362360960582,0.11684319241572233,0.7171837509947077,-1.1041681562018946,-0.01581628586746653,-0.030088107975129175,0.1757147710317064,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.041666666666666,1.0,1.0,0.0,1.0,3.378713386799812,-0.011436085001506542,0.6084611301580911,0.9901505391637948,0.02993983969445047,0.06846995531448116,0.11839502106064273,0.015230716623423896,0.0015444894932114266,-0.004325391742644933,-0.016849761976098377,-0.04456662249690851,-0.06416909816103711,-0.5955270578506551,-0.4134483635646654,-0.2026064062367712,0.027713059831640314,0.9774891132001164,-0.8631245926339751,0.08501705228648515,-0.8580044445840784,1.0067769898339456,0.22739523678386722,-0.40842993829704705,0.46040421758374156,0.13543897472462207,0.1386124367196162,-0.172357725654681,0.04073334251145512,-0.00047988303053969616,0.08085557750752592,0.11311401926434594,0.7285486547043019,-1.1251808055005874,-0.01581205000184993,-0.029630309606728522,0.17522365064472134,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.05,1.0,1.0,0.0,1.0,3.37882794421617,-0.011391820652915973,0.6084101253232181,0.9901969682121329,0.02987394708329307,0.06828578085159953,0.1181294356316513,0.015339159416389437,0.001513333158988453,-0.004319378469671166,-0.016872314941832486,-0.044564375030805875,-0.06421368658386624,-0.5943980116155508,-0.41229159688118094,-0.2040439189048849,0.02805281383736838,0.9774852084741872,-0.8624494670956945,0.08594399124092356,-0.8518864943138387,0.9973139545239356,0.2272634858118068,-0.4086749553754786,0.461862375661891,0.13553156105677644,0.13900945899744,-0.1726416198337477,0.040807191870515375,-0.00045750537909450273,0.08117415384355064,0.10932040471122562,0.7396031269886505,-1.1456965990593893,-0.015808543349541404,-0.02917505720071878,0.17473596863404994,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.058333333333334,1.0,1.0,0.0,1.0,3.3789434791134014,-0.011347662936488596,0.6083590712759338,0.9902433114611295,0.029807944459667886,0.06810160275261885,0.11786365960765947,0.015447160096211544,0.0014824730126652753,-0.004313554507539027,-0.016894781747612435,-0.04456202164456183,-0.06425836339292296,-0.5932681984997088,-0.4111315392480414,-0.20548376656733366,0.028393179696148903,0.9774814881104649,-0.8617716900699159,0.08683905903167224,-0.8456777258009343,0.9876820465162891,0.22713176106137486,-0.40891618925039236,0.4633164837276424,0.13562300754721646,0.13940220988437946,-0.17291806923501185,0.04088018885908373,-0.00043564860518374715,0.08149190530677197,0.10546748441576076,0.7503428513640964,-1.1657048393351688,-0.015805747223297528,-0.028722327664475467,0.17425156481638893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.066666666666666,1.0,1.0,0.0,1.0,3.379059987055364,-0.011303611400611225,0.608307967862142,0.9902895687372433,0.029741832124976216,0.06791742158011625,0.11759769265578014,0.015554696165992674,0.001451905331743249,-0.004307914222373385,-0.016917167692306376,-0.04455953762155363,-0.06430310352785974,-0.5921376281564306,-0.4099682267164413,-0.20692588672546844,0.028734150318353108,0.9774779476641008,-0.861091268673915,0.0877017826478529,-0.8393807801244371,0.9778855405350161,0.2270000566914185,-0.4091536608365532,0.4647665684088308,0.13571327665240052,0.1397905823279677,-0.17318696870111894,0.040952337032656716,-0.00041433821289960093,0.08180877481221316,0.10156029600627253,0.7607634071238589,-1.1851945549574072,-0.015803642042098165,-0.02827209159933508,0.1737702675782249,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.075,1.0,1.0,0.0,1.0,3.379177463446703,-0.011259665665707854,0.6082568149932794,0.9903357398478322,0.02967561035434395,0.06773323799677962,0.11733153455322909,0.015661746229443396,0.001421625821036986,-0.004302451064255929,-0.016939477798195754,-0.044556896226332514,-0.06434788101000184,-0.5910063105555021,-0.40880169620924195,-0.20837021604568565,0.029075718646693182,0.9774745824735832,-0.8604082104897124,0.08853173063177679,-0.8329983356822033,0.9679288039336656,0.2268683670273399,-0.40938739077704794,0.46621265485394614,0.13580232987482344,0.14017447398659955,-0.17344822285520922,0.041023640542075246,-0.00039360076590000403,0.08212470781156833,0.09760377059530007,0.7708602472829962,-1.2041544709406926,-0.01580220749474892,-0.027824313088531394,0.1732918930589078,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.083333333333334,1.0,1.0,0.0,1.0,3.379295903543486,-0.011215825426560475,0.608205612652344,0.9903818245803125,0.029609279397155092,0.06754905277423162,0.11706518519122759,0.01576828996510561,0.0013916296350120882,-0.004297157513143303,-0.01696171674072039,-0.04455406850418243,-0.06439266896371598,-0.5898742559918502,-0.4076319854833313,-0.20981669043972193,0.02941787766072103,0.9774713876513358,-0.8597225235437221,0.08932851215777457,-0.8265331093363871,0.9578162993526712,0.22673668656650603,-0.4096173993880287,0.46765476662647926,0.13589012758577823,0.1405537868264206,-0.1737017458008211,0.0410941040224054,-0.00037346403106042203,0.08243965209939752,0.0936027251565108,0.7806286758866565,-1.2225729773801208,-0.01580142270112883,-0.02737894946359898,0.17281624424409947,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.091666666666667,1.0,1.0,0.0,1.0,3.379415302463614,-0.01117209045455438,0.6081543609004539,0.9904278227012722,0.02954283947777788,0.06736486680275824,0.11679864457884094,0.015874308096591704,0.001361911398030814,-0.004292025019040937,-0.016983888777239893,-0.04455102306171104,-0.06443743962931697,-0.5887414750957392,-0.4064591330954683,-0.211265245142366,0.02976062038039994,0.9774683580730655,-0.8590342162880558,0.09009177605105197,-0.819987857750759,0.947552587643997,0.22660500998232108,-0.40984370660144126,0.4690929255913478,0.1359766288311981,0.14092842668328442,-0.17394746079793355,0.0411637324822859,-0.0003539571352417781,0.08275355760518632,0.08956185574741093,0.7900638246736724,-1.2404380965830875,-0.015801266370895073,-0.026935951042629247,0.17234310995993485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1,1.0,1.0,0.0,1.0,3.379535655196999,-0.011128460599874625,0.6081030598839875,0.9904737339555344,0.029476290796480526,0.06718068110201907,0.11653191284678797,0.01597978236056443,0.0013324652219119035,-0.004287043935931578,-0.017005997674707018,-0.04454772582742297,-0.0644821643671514,-0.5876079788446635,-0.4052831783719432,-0.21271581478635415,0.030103939868759127,0.9774654883657484,-0.8583432975836357,0.09082120975356475,-0.8133653789251593,0.9371423310762864,0.2264733321269911,-0.41006633190540587,0.47052715179247817,0.13606179112053196,0.141298302792785,-0.17418529992194898,0.04123253119327534,-0.00033511073679326486,0.08306637617066404,0.08548573155864464,0.799160629082587,-1.2577374485858117,-0.015801716958439016,-0.026495260834979995,0.17187226375871667,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.108333333333333,1.0,1.0,0.0,1.0,3.379656956615509,-0.011084935793681503,0.6080517098423551,0.9905195580651612,0.029409633530536744,0.06699649683282614,0.11626499025126386,0.016084695472658075,0.0013032847206455667,-0.004282203448785285,-0.017028046635913813,-0.044544139790805695,-0.06452681365205117,-0.5864737785770636,-0.4041041613822552,-0.21416833347439848,0.030447829233621194,0.977462772894119,-0.8576497766852114,0.09151653824369604,-0.8066685139327159,0.9265902968342334,0.22634164803301376,-0.41028529428202426,0.47195746332065974,0.13614557019834717,0.14166332729477316,-0.1744152037156732,0.04130050558002196,-0.0003169572125494291,0.08337806131811565,0.08137878976545249,0.8079138035797495,-1.2744582150018346,-0.01580275281447996,-0.02605681421080308,0.17140346269109763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.116666666666667,1.0,1.0,0.0,1.0,3.3797792014826658,-0.011041516050293772,0.6080003111164657,0.9905652947283857,0.029342867835520023,0.0668123153100804,0.11599787717781747,0.016189031092152147,0.0012743630219724696,-0.004277491493194195,-0.017050038224145893,-0.04454022471867985,-0.06457135705812565,-0.5853388860080244,-0.40292212291703033,-0.21562273484828204,0.03079228162842616,0.9774602057455393,-0.8569536632283338,0.0921775229163223,-0.7999001488654968,0.9159013608262558,0.22620995291341645,-0.4105006121422526,0.47338387617066313,0.1362279197976468,0.14202341471416524,-0.17463712083927385,0.0413676611115308,-0.00029953086032152854,0.08368856800885505,0.07724533115468946,0.8163178162916407,-1.2905871011546965,-0.015804352334046756,-0.025620538526923697,0.17093644595359225,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.125,1.0,1.0,0.0,1.0,3.3799023844631186,-0.010998201469409228,0.6079488641579441,0.9906109436184664,0.029275993846787394,0.06662813801696338,0.11573057414532661,0.016292773786832644,0.0012456927753622302,-0.004272894666978319,-0.017071974285921665,-0.044535936847018696,-0.06461576323350086,-0.5842033132471028,-0.40173710447035244,-0.21707895215505305,0.031137290252146708,0.9774577807131136,-0.8562549672183971,0.09280396042960753,-0.7930632169945219,0.9050805118149885,0.22607824216077965,-0.410712303257473,0.47480640408655295,0.13630879137491503,0.14237848141933962,-0.17485100772278495,0.04143400319337097,-0.0002828681178823622,0.0839978523936713,0.07308951649814599,0.8243668629202117,-1.3061102964448734,-0.015806494100351065,-0.025186352709674065,0.1704709334068122,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.133333333333333,1.0,1.0,0.0,1.0,3.380026500131902,-0.010954992238393668,0.6078973695391685,0.9906565043824505,0.029209011681152856,0.06644396662048807,0.11546308181011568,0.016395908998244595,0.0012172661563252482,-0.0042683981331095066,-0.01709385587150746,-0.044531228547133234,-0.06465999986468053,-0.5830670728184425,-0.400549148226708,-0.21853691831032845,0.031482848348315676,0.9774554912769079,-0.8555536990217726,0.09339568152462473,-0.7861607011501599,0.894132855885508,0.22594651134507726,-0.4109203846874138,0.47622505839411,0.13638813382543802,0.14272844506016624,-0.1750568282257775,0.04149953706136862,-0.00026700779931054797,0.08430587155807912,0.06891536364044326,0.8320548399218319,-1.321013432908127,-0.015809157025328258,-0.024754166787567256,0.17000662395424637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.141666666666666,1.0,1.0,0.0,1.0,3.380151542983503,-0.010911888634668541,0.6078458279641947,0.9907019766398376,0.029141921438753153,0.0662598029885162,0.11519540097026143,0.016498423007876063,0.0011890748669399621,-0.004263985513403373,-0.017115683152740056,-0.04452604796470944,-0.06470403363027322,-0.5819301776833455,-0.399358297052683,-0.219996565958816,0.03182894920316952,0.9774533305831251,-0.8548498693590958,0.09395254982361492,-0.779195636329158,0.8830636212665197,0.22581475621035751,-0.41112487270393244,0.4776398478191237,0.136465893179194,0.14307322399057187,-0.17525455331226625,0.04156426767590732,-0.00025199135044617904,0.08461258326249332,0.06472674526715766,0.8393753169278306,-1.3352815419285569,-0.01581232048708414,-0.024323881371403067,0.16954319377504135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.15,1.0,1.0,0.0,1.0,3.3802775074407623,-0.010868891028228543,0.6077942402806447,0.9907473599811312,0.029074723205108916,0.06607564920835861,0.11492753257013412,0.016600302904772095,0.0011611101324523624,-0.00425963877255495,-0.01713745533780244,-0.044520338630121316,-0.06474783014400622,-0.5807926412654559,-0.3981645944935318,-0.22145782753219956,0.03217558614291413,0.9774512914210671,-0.854143489300731,0.09447446061241069,-0.7721711125346961,0.871878163520032,0.22568297267029253,-0.41132578271027054,0.4790507782903607,0.13654201227635276,0.14341273667526133,-0.17544416074337876,0.041628199616841055,-0.0002378631227983874,0.0849179456770277,0.06052738731871038,0.8463215083914699,-1.3488990090753084,-0.015815964464145904,-0.0238953870788583,0.16908029440438677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.158333333333333,1.0,1.0,0.0,1.0,3.3804043878636354,-0.010825999884320142,0.6077426074926319,0.9907926539662693,0.029007417053385644,0.06589150760707939,0.11465947770522042,0.016701536555901775,0.0011333626936904815,-0.004255338091855739,-0.017159170582554336,-0.044514039038702574,-0.06479135388709141,-0.5796544774787397,-0.396968084774762,-0.22292063530453898,0.03252275253011687,0.9774493661977451,-0.8534345702644787,0.0949613396122601,-0.7650902778559668,0.8605819711152646,0.22555115680262175,-0.41152312915524675,0.4804578527258635,0.13661643042123917,0.14374690108151067,-0.17562563479133264,0.04169133697949329,-0.00022467066721709728,0.08522191711449523,0.05632086801388103,0.852886244448654,-1.3618495270455533,-0.01582006966762972,-0.023468563899318173,0.16861755065305295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.166666666666666,1.0,1.0,0.0,1.0,3.3805321785578686,-0.010783215766311898,0.6076909307748085,0.9908378581229207,0.028940003046859723,0.06570738077363218,0.11439123762727463,0.016802112579440517,0.0011058227953284023,-0.004251061732019201,-0.017180825898036024,-0.04450708219960446,-0.06483456812983847,-0.5785157007584353,-0.39576881280883996,-0.22438492144538844,0.03287044175923902,0.9774475469099468,-0.8527231240154894,0.09541314174597537,-0.7579563417938852,0.8491806714026061,0.2254193048424987,-0.41171692544192584,0.4818610708012449,0.13668908301510685,0.14407563405782087,-0.17579896597843925,0.04175368327067261,-0.00021246504920746645,0.08552445576120338,0.05211061744604811,0.8590619409866784,-1.3741160467126212,-0.01582461767170973,-0.023043280497320184,0.16815455836172055,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.175,1.0,1.0,0.0,1.0,3.3806608737836146,-0.01074053933878688,0.6076392114876171,0.9908829719446376,0.028872481241596283,0.06552327158296027,0.11412281374984558,0.01690202032121016,0.001078480170106897,-0.004246785884981589,-0.017202417053547754,-0.04449939515236682,-0.06487743484266367,-0.5773763260951545,-0.39456682420713163,-0.2258506180708463,0.033218647251294746,0.9774458251135917,-0.8520091626684586,0.09582984990302756,-0.7507725788395222,0.8376800370033876,0.22528741317475992,-0.4119071838302021,0.48326042869855884,0.13675990116702286,0.14439885070258618,-0.17596415084761396,0.04181524130460121,-0.00020130118467465152,0.08582551940680361,0.047899917714823714,0.8648405689220584,-1.3856807262913229,-0.015829591043052815,-0.02261939345171271,0.16769088198529292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.183333333333334,1.0,1.0,0.0,1.0,3.3807904677640455,-0.01069797137088561,0.6075874511938327,0.9909279948888514,0.02880485168934836,0.06533918322219749,0.11385420765422467,0.01700124983523363,0.0010513240189704244,-0.004242484513981317,-0.017223938474945414,-0.044490898450358814,-0.06491991459678753,-0.5762363690723182,-0.3933621652971302,-0.22731765729284867,0.03356736244764904,0.9774441918902023,-0.8512926986920427,0.0962114737078891,-0.7435423323118509,0.8260859926310841,0.22515547832511448,-0.4120939153327877,0.4846559188343331,0.13682881128282975,0.1447164637252385,-0.17612119176791008,0.04187601309811495,-0.00019123819805066944,0.0861250651738743,0.04369190355570235,0.8702136227036039,-1.3965248786613338,-0.01583497347008689,-0.02219674642784053,0.16722605200253815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.191666666666666,1.0,1.0,0.0,1.0,3.380920954694008,-0.01065551273992744,0.6075356516764887,0.9909729263747032,0.02873711444068662,0.06515511921910856,0.1135854210958598,0.017099791869222305,0.001024342987073434,-0.004238129182006639,-0.01724538313796354,-0.04448150561015794,-0.06496196645515345,-0.5750958459071074,-0.3921548831450443,-0.22878597126697814,0.033916580802929995,0.9774426378102908,-0.8505737449155607,0.0965580482956226,-0.7362690184611288,0.814404622359032,0.22502349695025847,-0.4122771296039994,0.4860475295652678,0.13689573463240512,0.14502838279747965,-0.1762700967749048,0.041935999765315146,-0.00018233980225712543,0.08642304924803668,0.03948956343131055,0.8751720880693314,-1.4066289169160906,-0.015840749893043515,-0.021775169284239393,0.16675956215226329,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2,1.0,1.0,0.0,1.0,3.3810523287487877,-0.010613164435336574,0.6074838149582689,0.9910177657806963,0.028669269548369826,0.06497108347291412,0.11331645601127606,0.017197637855353776,0.0009975251359872466,-0.004233688868349945,-0.017266742455864438,-0.04447112252731196,-0.06500354785408957,-0.5739547734951115,-0.39094502558383887,-0.23025549223909708,0.03426629577707096,0.977441152893498,-0.8498523145379088,0.09686963309841094,-0.7289561308440287,0.8026421773491492,0.2248914658268971,-0.4124568348208584,0.4874352448702042,0.1369605868954782,0.14533451390157937,-0.17641087945495515,0.04199520141094509,-0.00017467469981768957,0.08671942661262033,0.03529574104656652,0.8797064091015772,-1.4159722982362477,-0.015846906635715863,-0.021354477112700554,0.16629086649643687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.208333333333334,1.0,1.0,0.0,1.0,3.381184584093033,-0.01057092756289432,0.6074319433224633,0.9910625124421627,0.0286013170709716,0.06478708028763609,0.11304731452554369,0.017294779906316025,0.0009708579124786182,-0.004229129773380497,-0.017288006161367424,-0.0444596468591561,-0.06504461447636699,-0.5728131694588494,-0.38973264124668466,-0.2317261525912274,0.03461650082644575,0.9774397265652939,-0.8491284211386837,0.09714631064639871,-0.7216072449761025,0.7908050840550945,0.2247593818396632,-0.41263303755587777,0.4888190440068751,0.13702327768800204,0.1456347586791895,-0.17654355887497086,0.042053617021233225,-0.00016831700679231787,0.08701415078467445,0.031113137252546386,0.8838064546537128,-1.4245334662346032,-0.015853431539757934,-0.0209344692104263,0.165819376313614,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.216666666666667,1.0,1.0,0.0,1.0,3.3813177148899016,-0.010528803349338015,0.6073800393355695,0.991107165648533,0.028533257076774808,0.0646031144081035,0.11277799896032792,0.0173912108185517,0.000944328113794796,-0.004224415112175135,-0.017309162182698904,-0.04444696737532034,-0.06508512011719941,-0.5716710522003114,-0.3885177796058524,-0.23319788488701326,0.03496718939409151,0.9774383476100514,-0.8484020786914975,0.09738818538595338,-0.7142260232664668,0.7788999529119058,0.22462724196790113,-0.41280574264103215,0.49019890114209774,0.13708371007019382,0.14592901378016165,-0.17666815956012383,0.04211124435344271,-0.00016334669561635096,0.08730717355815987,0.026944312303262274,0.8874614842385986,-1.4322897919632616,-0.01586031410248101,-0.020514927992110188,0.1653444568358231,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.225,1.0,1.0,0.0,1.0,3.3814517153105137,-0.01048679314732176,0.6073281058716218,0.9911517246404031,0.02846508964795039,0.06441919105874931,0.11250851184254862,0.017486924082428655,0.0009179218502109792,-0.004219504897321391,-0.01733019651359816,-0.044432963279078246,-0.06512501654417847,-0.5705284409576795,-0.3873004910170153,-0.23467062191722945,0.035318354899003125,0.9774370041203669,-0.847673301579381,0.09759538251811975,-0.7068162202387925,0.7669335875223735,0.22449504327128852,-0.41297495302241294,0.4915747849541388,0.1371417800385144,0.14621717022002767,-0.17678471152542952,0.04216807982232562,-0.0001598500567046024,0.08759844475406897,0.022791688431247903,0.8906601135121472,-1.4392175138373298,-0.015867545619567824,-0.020095617842971203,0.16486542384030578,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.233333333333333,1.0,1.0,0.0,1.0,3.3815865795437596,-0.010444898440748326,0.6072761461383273,0.9911961886063936,0.028396814885036432,0.06423531598531344,0.11223885591367505,0.017581913899626857,0.0008916245054747599,-0.004214355712325641,-0.017351093077457268,-0.044417503502719786,-0.0651642533531478,-0.5693853558663362,-0.3860808267688519,-0.23614429674577042,0.035669990724463606,0.9774356834424397,-0.846942104612263,0.09776804685980751,-0.6993816880412643,0.7549129943479503,0.22436278287424166,-0.41314066960508167,0.49294665820610284,0.13719737600647708,0.1464991127519788,-0.1768932503645676,0.04222411838365733,-0.00015792017716842466,0.08788791198217627,0.018657552708758185,0.8933902795156201,-1.4452916767979485,-0.01587511933337893,-0.0196762839207254,0.16438154011842454,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.241666666666667,1.0,1.0,0.0,1.0,3.381722301806549,-0.010403120850475322,0.6072241637050682,0.9912405566797929,0.028328432911734855,0.0640514954995557,0.11196903413966648,0.017676175209657842,0.000865420695504192,-0.004208920477176499,-0.017371833586034478,-0.04440044598183714,-0.06520277782243974,-0.5682418180242382,-0.38485883913781566,-0.23761884275663891,0.036022090205397414,0.9774343721174141,-0.8462085030463448,0.09790634172993239,-0.6919263822468655,0.7428453929090744,0.22423045794906554,-0.41330289108775836,0.4943144772894459,0.1372503782775425,0.14677471925724994,-0.17699381739824327,0.04227935341531541,-0.00015765742945150762,0.08817552041497256,0.01454406016230203,0.8956392058845641,-1.4504860711155043,-0.015883030587357516,-0.01925665091697004,0.16389201185267765,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.25,1.0,1.0,0.0,1.0,3.3818588763545767,-0.010361462140391275,0.6071721625328198,0.9912848279349924,0.028259943880041574,0.06386773652705437,0.11169904972156298,0.01776970372514175,0.0008392942265803222,-0.0042031482080131955,-0.01739239739328901,-0.044381636915909704,-0.06524053476783508,-0.5670978495617105,-0.38363458144789775,-0.2390941937024078,0.03637464661471886,0.9774330558186155,-0.8454725126053468,0.09801044786251255,-0.6844543679431883,0.7307382264960253,0.2240980656977857,-0.41346161378703117,0.4956781917369808,0.13730065851785378,0.1470438601684243,-0.17708645988849747,0.042333776594385,-0.00015916996902509695,0.08846121257708006,0.01045323711028251,0.897393368295365,-1.4547731713390921,-0.01589127698813475,-0.01883642179135281,0.16339598494012675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.258333333333333,1.0,1.0,0.0,1.0,3.3819962974936724,-0.010319924223845143,0.6071201470060147,0.9913290013837065,0.028191347975728913,0.06368404665813238,0.1114289061067162,0.017862495976680187,0.0008132280540406804,-0.00419698377413499,-0.017412761345336196,-0.0443609100239651,-0.06527746640228457,-0.5659534737156073,-0.3824081081350086,-0.24057028375478054,0.036727653148637164,0.977431719284597,-0.8447341495033934,0.0980805623484371,-0.6769698261086095,0.7185991733867562,0.22396560333259663,-0.4136168314509476,0.49703774370511467,0.1373480792363524,0.14730639793329892,-0.17717123132097612,0.042387377771825746,-0.00016257423318899455,0.08874492815980739,0.006386984693403652,0.8986384604659503,-1.4581240759967495,-0.015899858575408876,-0.018415276495998834,0.1628925413142357,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.266666666666666,1.0,1.0,0.0,1.0,3.3821345595918153,-0.010278509170403651,0.6070681219663481,0.9913730759709953,0.028122645424194112,0.06350043420191519,0.11115860700062921,0.01795454936806908,0.0007872042428277936,-0.004190367656067716,-0.017432899627954003,-0.044338085807326594,-0.06531351220429987,-0.5648087149077713,-0.3811794748156761,-0.2420470475577574,0.03708110291091596,0.9774303462480624,-0.84399343046935,0.09811689760740261,-0.6694770602687558,0.7064361585627461,0.22383306805486222,-0.4137685350619645,0.4983930674255514,0.13739249328220016,0.14756218653360964,-0.17724819175930828,0.04244014484474354,-0.00016799543007373074,0.08902660386013173,0.002347082570643144,0.8993593611097106,-1.4605084487838815,-0.015908778000439106,-0.017992870714392817,0.1623806953320006,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.275,1.0,1.0,0.0,1.0,3.382273657091879,-0.010237219212893191,0.6070160927484948,0.9914170505710966,0.028053836496689997,0.06331690824346176,0.11088815637936177,0.018045862242813564,0.0007612039314589748,-0.004183235709401142,-0.017452783613659824,-0.04431297083440693,-0.06534860880017626,-0.5636635988275707,-0.3799487383594484,-0.24352442028410234,0.037434988896049556,0.9774289193607625,-0.8432503727723912,0.09811968039128115,-0.6619805034234476,0.6942573659070248,0.2237004570325893,-0.4139167126295208,0.4997440886273147,0.13743374337334968,0.14781107107590508,-0.17731740827409304,0.04249206362632624,-0.00017556801169549274,0.08930617325277446,-0.0016648072461450392,0.8995401023191429,-1.461894462126958,-0.015918040712727954,-0.017568834640835362,0.16185939030814223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.283333333333333,1.0,1.0,0.0,1.0,3.3824135845251893,-0.01019605675466901,0.6069640652176549,0.9914609239830907,0.02798492151694613,0.06313347870384867,0.11061755850242345,0.01813643396204996,0.0007352073014770945,-0.0041755189406942304,-0.017472381710829696,-0.044285357066273984,-0.06538268986633065,-0.5625181525182155,-0.378715956964411,-0.24500233769565896,0.03778930397135473,0.9774274201145341,-0.8425049942484705,0.09808915081996686,-0.6544847252301034,0.6820712508606301,0.22356776737631676,-0.41406134897264507,0.5010907239306871,0.1374716616711713,0.1480528874737741,-0.1773789554495242,0.042543117715298506,-0.00018543611480348332,0.08958356670337064,-0.005647136444355272,0.8991638399439394,-1.4622487441641385,-0.01592765515502359,-0.017142771837290738,0.16132749529968127,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.291666666666666,1.0,1.0,0.0,1.0,3.3825543365259363,-0.010155024377030936,0.6069120458087967,0.9915046949264283,0.027915900868189934,0.06295015640299347,0.11034681792605779,0.01822626499429112,0.0007091935548091755,-0.004167143302860856,-0.01749165921805848,-0.044255021246531634,-0.06541568605884474,-0.5613724044663845,-0.3774811902348855,-0.24648073620826108,0.0381440408579712,0.9774258287588491,-0.841757313327335,0.09802556145054189,-0.646994439424382,0.6698865535042892,0.22343499611333892,-0.41420242549347563,0.5024328802156427,0.13750606942085408,0.1482874622477126,-0.17743291597278055,0.04259328836599907,-0.00019775395383891947,0.0898587113319449,-0.009598466373517134,0.8982128266369882,-1.4615363303805595,-0.015937632966478987,-0.01671425821531125,0.16078380226880462,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3,1.0,1.0,0.0,1.0,3.382695907846515,-0.010114124846683047,0.606860041567394,0.9915483620363575,0.02784677500056712,0.06276695312490087,0.11007593951677608,0.018315357017892546,0.0006831409016501253,-0.004158029519143385,-0.01751057818815252,-0.04422172438343808,-0.06544752497918374,-0.5602263846945346,-0.3762444992602825,-0.24795955296187197,0.03849919211078805,0.9774241242153034,-0.8410073490596047,0.09792917638040824,-0.6395145114528202,0.6577123120209541,0.22330214016020877,-0.41433991994290026,0.5037704539685005,0.13753677668086217,0.14851461246802922,-0.17747938130430962,0.042642554361179974,-0.00021268614746716707,0.09013153103623273,-0.013517463940849461,0.8966683883580151,-1.459720621342071,-0.015947989191546497,-0.016282841190946584,0.160227023775954,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.308333333333334,1.0,1.0,0.0,1.0,3.3828382933738164,-0.010073361123105225,0.6068080601913785,0.9915919238593051,0.02777754443895499,0.0625838816848849,0.10980492846496644,0.01840371303621063,0.0006570265621930337,-0.004148092947098144,-0.017529097306823165,-0.04418521135861835,-0.06547813118608004,-0.5590801248550368,-0.3750059466937517,-0.24943872589666624,0.0388547500973242,0.9774222839897246,-0.8402551211433978,0.09780027038486107,-0.6320499662850817,0.6455578764819213,0.2231691962934798,-0.4144738061799914,0.5051033306119086,0.1375635821689314,0.14873414587408318,-0.17751845242934328,0.04269089189059869,-0.0002304079531434411,0.0904019465863315,-0.01740289746086615,0.894510905253072,-1.4567633482038467,-0.015958742493493716,-0.015848039078455445,0.1596557913855845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.316666666666666,1.0,1.0,0.0,1.0,3.3829814881465095,-0.010032736365673225,0.6067561100739176,0.9916353788482751,0.02770820979115146,0.0624009559981649,0.10953379029834902,0.018491337505313787,0.0006308267860722573,-0.004137243495575544,-0.017547171792365673,-0.04414521070315676,-0.06550742626545965,-0.5579336583250524,-0.37376559682904775,-0.25091819383569436,0.03921070697563136,0.9774202840827511,-0.8395006499498325,0.0976391280893938,-0.624605996365269,0.6334329228842234,0.22303616111865054,-0.4146040539275412,0.5064313838249269,0.137586273257706,0.14894586121054876,-0.1775502406917423,0.04273827443867048,-0.0002511053830800414,0.09066987580770736,-0.021253632478697992,0.8917197979756852,-1.452624547931598,-0.01596991536950143,-0.015409340803048677,0.15906865500700196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.325,1.0,1.0,0.0,1.0,3.3831254873732983,-0.009992253940324986,0.6067042003465314,0.9916787253583478,0.027638771756410944,0.062218191149047156,0.10926253089499818,0.018578236474329626,0.0006045168938252406,-0.004125385610520451,-0.01756475332405822,-0.04410143458948355,-0.0655353289720021,-0.5567870203007417,-0.3725235156735759,-0.25239789657486195,0.03956705467130204,0.9774180989000066,-0.8387439565466027,0.09744604317688277,-0.6171879696521536,0.621347467349728,0.22290303103732145,-0.4147306285267089,0.5077544748620253,0.13760462615819202,0.14914954882417453,-0.17757486870683792,0.04278467268540226,-0.0002749751671426992,0.09093523386548785,-0.025068627585541625,0.8882735206712411,-1.4472625504514336,-0.01598153436318528,-0.014966206018345307,0.15846408342450546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.333333333333334,1.0,1.0,0.0,1.0,3.383270286452147,-0.00995191742552975,0.6066523409219013,0.991721961642381,0.02756923113428149,0.06203560345968651,0.1089911564955839,0.01866441773815764,0.0005780713452670765,-0.0041124183483325,-0.01758179000846796,-0.04405357909534775,-0.06556175545828295,-0.5556402478890825,-0.3712797710153115,-0.2538777749808083,0.039923784853721396,0.9774157011632987,-0.8379850627187411,0.09722131762963478,-0.609801437687415,0.6093118803766995,0.22276980221259746,-0.4148534906945136,0.509072451882002,0.1376184063353847,0.14934499156902925,-0.17759247134454537,0.04283005442663801,-0.00030222452397365984,0.09119793366915152,-0.028846930243016378,0.8841495620183393,-1.4406339802530899,-0.01599363026936862,-0.014518065734147045,0.15784046631725168,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.341666666666667,1.0,1.0,0.0,1.0,3.3834158809904027,-0.009911730617267543,0.6066005425355804,0.991765085847037,0.027499588833678847,0.06185321055716913,0.10871967371441299,0.018749891000464813,0.0005514638407688819,-0.004098235557696847,-0.017598226394319297,-0.04400132480552816,-0.06558661960876436,-0.5544933801951519,-0.37003443248075873,-0.25535777109727104,0.040280888911746006,0.9774130618246071,-0.8372239909854502,0.09696526100616583,-0.6024521436185146,0.5973369010121765,0.22263647053283198,-0.4149725962889447,0.5103851493006462,0.1376273692086083,0.14953196608335384,-0.17760319677924907,0.04287438451990963,-0.00033307069486454566,0.09145788642073605,-0.03258767263282336,0.8793244559079239,-1.4326937753022895,-0.016006238325156352,-0.014064323579641158,0.1571961181162962,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.35,1.0,1.0,0.0,1.0,3.3835622668257153,-0.009871697532672823,0.6065488167856247,0.9918080960092822,0.02742984588211139,0.061671031437361704,0.10844808954877042,0.018834668046870437,0.0005246674613738869,-0.00408272619478118,-0.01761400354860973,-0.04394433782618986,-0.06560983349870796,-0.5533464584022724,-0.36878757158058895,-0.2568378282604625,0.04063835792905322,0.9774101499850509,-0.8364607646117288,0.09667818975242105,-0.5951460300889496,0.585433650788328,0.22250303157384485,-0.4150878960875076,0.5116923871839403,0.137631261193083,0.1497102444981513,-0.17760720759129156,0.04291762486382342,-0.00036774018997931535,0.09171500232588947,-0.03629006754593794,0.8737738035292364,-1.423395226456119,-0.016019398378331884,-0.013604357835611536,0.15652928409010558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.358333333333333,1.0,1.0,0.0,1.0,3.383709440047615,-0.009831822411938059,0.6064971761689499,0.9918509900535376,0.02736000343494034,0.06148908652364233,0.10817641138596516,0.018918762925499752,0.0004976548549180337,-0.004065774799410242,-0.017629059208436295,-0.04388227129661918,-0.06563130800009577,-0.5521995258419339,-0.3675392617391229,-0.25831789122379256,0.040996182659476396,0.9774069328214408,-0.835695407613352,0.09636042654706686,-0.5878892468930274,0.5736136472379079,0.22236948055985978,-0.41519933558620487,0.5129939707021479,0.13762982114855937,0.14987959664800488,-0.1776046819029664,0.042959734420734835,-0.00040646768783458853,0.09196919149513594,-0.039953404324147845,0.8674723088411418,-1.4126900409424037,-0.016033155022865397,-0.013137524394370992,0.15583814910557603,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.366666666666667,1.0,1.0,0.0,1.0,3.383857397019526,-0.009792109718007477,0.6064456341129915,0.9918937657896859,0.02729006278453021,0.06130739771824893,0.1079046470073869,0.01900219213219638,0.0004703984757049892,-0.004047262163235202,-0.017643328024858386,-0.04381476749309938,-0.0656509535581214,-0.5510526280497964,-0.3662895783031222,-0.2597979062921786,0.04135435350273214,0.977403375523587,-0.8349279447534765,0.09601229968035192,-0.5806881582749306,0.5618888167726213,0.22223581232346376,-0.4153068548274138,0.5142896896690332,0.13762278230784908,0.15003979286291158,-0.17759581452841844,0.04300066929359497,-0.00044949452235654164,0.09222036506150166,-0.04357704486700975,0.8603938296061853,-1.4005284338280144,-0.016047557690055947,-0.01266316082127572,0.1551208495564449,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.375,1.0,1.0,0.0,1.0,3.3840061344009564,-0.00975256413352424,0.6063942050009707,0.9919364209121762,0.027220025369106445,0.06112598844356734,0.10763280458877017,0.019084974797060686,0.0004428708857663905,-0.0040270662239092975,-0.017656741917022604,-0.0437414606291487,-0.06566868116399222,-0.5499058128034697,-0.365038598524741,-0.26127782146593287,0.04171286048103631,0.9773994412460681,-0.8341584015289937,0.09563414246595003,-0.5735493497329243,0.5502715066741076,0.2221020212650255,-0.41541038826655946,0.5155793181947553,0.13760987476264974,0.15019060742465062,-0.1775808181114502,0.043040382869266314,-0.0004970666894621445,0.09246843654555637,-0.04716041971483925,0.8525114463666306,-1.3868592517587053,-0.016062660680472574,-0.012180591705162058,0.15437548899717157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.383333333333333,1.0,1.0,0.0,1.0,3.3841556491694944,-0.009713190554421259,0.6063429041888013,0.9919789530005012,0.027149892781098212,0.06094488367022204,0.10736089269574607,0.01916713286738561,0.00041504512616447357,-0.0040050632221544005,-0.017669230556871637,-0.04366198046430392,-0.06568440355092264,-0.5487591301370855,-0.36378640151271135,-0.2627575865940361,0.04207169321721991,0.9773950910787627,-0.8333868041443839,0.0952262926851046,-0.5664796341688201,0.5387744959099762,0.22196810131212255,-0.4155098646891665,0.5168626144856527,0.13759082859154947,0.15033182277116697,-0.17755992421419453,0.043078826042998175,-0.0005494322945343022,0.09271332349606753,-0.0507030242167511,0.8437975519438146,-1.3716301336064096,-0.01607852311959812,-0.011689135503244463,0.1536001580628965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.391666666666666,1.0,1.0,0.0,1.0,3.3843059386421834,-0.009673994079475794,0.6062917480113454,0.9920213595213626,0.027079666774694082,0.06076410992835151,0.10708892027364127,0.019248691281623546,0.0003868951667687537,-0.003981129160621514,-0.017680722005924965,-0.04357595684006995,-0.0656980366405759,-0.5476126323269439,-0.36253306814522157,-0.26423715353616944,0.04243084091508628,0.9773902840411592,-0.8326131794707259,0.09478909206233752,-0.5594860572005274,0.5274110044473341,0.22183404587969888,-0.41560520719161353,0.5181393208291369,0.13756537771704824,0.1504632345362833,-0.17753338431451327,0.04311594754009565,-0.0006068383605750682,0.0929549494377091,-0.054204414792637656,0.8342239642050631,-1.3547877129688302,-0.016095208817921147,-0.011188113093634211,0.15279295928213976,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4,1.0,1.0,0.0,1.0,3.3844570004957255,-0.009634979995075552,0.60624075377543,0.9920636378328722,0.027009349272293582,0.06058369529793647,0.1068168966303643,0.019329678127920743,0.0003583964427822453,-0.0039551416042305915,-0.01769114352671864,-0.04348302526548247,-0.06570950126677008,-0.5464663738418014,-0.36127868093710663,-0.2657164763326113,0.04279029234288817,0.9773849771060864,-0.8318375549870888,0.09432288577189397,-0.552575901432069,0.516194700693829,0.22169984783182387,-0.4156963332407271,0.5194091638070217,0.13753326458012527,0.15058465751423888,-0.17750147066567634,0.04315169435116853,-0.0006695269172940499,0.09319324615679303,-0.05766420529627059,0.8237620649893285,-1.3362778677287457,-0.016112786014575997,-0.0106768582538741,0.15195203740021812,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.408333333333333,1.0,1.0,1.0,1.0,3.3846088327848842,-0.009596153754379859,0.6061899397366979,0.9921057851911793,0.026938942369480502,0.060403669373535786,0.10654483141110169,0.019410124779150568,0.00032952648553861465,-0.003926981862044034,-0.017700422592338543,-0.043382833672721,-0.06571872520190802,-0.5453204112506085,-0.3600233238533176,-0.2671955113805974,0.04315003582093909,0.9773791252592043,-0.831059958701446,0.09382802197406634,-0.5457566894507052,0.505139706651855,0.2215654994461226,-0.4157831548291781,0.5206718547858072,0.13749424571863011,0.1506959326218138,-0.17746447695299983,0.04318601230055952,-0.0007377302878719405,0.09342815635206891,-0.06108206348398898,0.8123829681889649,-1.3160460220727044,-0.016131326979216265,-0.010154730275917512,0.15107561581874318,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.416666666666666,1.0,0.0,1.0,1.0,3.38476143395832,-0.009557520950004722,0.6061393250570642,0.9921477987599434,0.02686844833808895,0.06022406319828649,0.10627273456343957,0.018809534049757458,-0.0009719262578320232,0.0027768541427117812,-0.012195781147627406,-0.024059288280650418,-0.06117105183281785,-0.5441748030798242,-0.3587670820600764,-0.2686742176151613,0.04351005921456416,0.9773726816012885,-0.8302804190478876,0.09330485138049416,-0.5390361852955863,0.4942606003259506,0.22143099238217026,-0.4158655787453257,0.5219270907373341,0.12034462693696124,0.1267347517478401,-0.16683532042198745,0.03822108392400381,-0.01561470830570899,0.08663370467985487,-0.040204121147610905,0.44499184258006474,-0.6718162150981788,-0.02167095559749921,0.02607252163472462,0.04557867937982962,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.425,1.0,0.0,1.0,1.0,3.384922128382028,-0.009546715602832686,0.6061990743394721,0.9921747917494771,0.02682875461904809,0.06020764142358734,0.10603980604184333,0.06485124953923943,-0.008124177260747205,0.020316186197794992,-0.01859315246517132,-0.049688755745055484,-0.04113363768116396,-0.5433146674683258,-0.3579110779908536,-0.2699761000542972,0.043787053886339154,0.9771188801207759,-0.8296160636234484,0.09315795328827282,-0.5383401587410375,0.49394276973355206,0.22120431685283096,-0.4153486128019327,0.5214314994421377,0.1525595069565422,0.28795175339566326,-0.2465923747373988,0.11267686463960272,1.0461589025702134,-1.217832339959788,0.01262409537802961,0.15636045815026423,0.04650769405079469,0.005821362689052423,0.1881625026056244,-0.050885882178162145,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.433333333333334,1.0,0.0,1.0,1.0,3.385880579400541,-0.009472461608875913,0.6063430653875108,0.9922131717720202,0.026737893905288492,0.05980600987183504,0.1059308641276347,0.12118932386393443,-0.015775239474760047,0.024876202682759453,-0.020355192580580418,-0.08610478634655373,-0.026856489306878027,-0.5416321446305485,-0.3539678861701487,-0.2727840905274513,0.04538800695855754,0.9948086633107921,-0.8505776247138841,0.09351525297012798,-0.5364301776597485,0.4950357285601305,0.22152801509365447,-0.41272953703523196,0.5210789927010314,0.18420653662879927,0.5423584638415768,-0.47565807509850844,0.18336553140092873,2.166353958672007,-2.571716918064404,0.035569324971001515,0.22395888677638975,0.15716376286496803,0.03263249012296077,0.3051717363669837,-0.009431865397875328,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.441666666666666,1.0,0.0,1.0,1.0,3.386988153577411,-0.009389054431796957,0.6063645652832369,0.9922459770395469,0.02672308848460184,0.05948369645425777,0.10580873048485656,0.13636534554269983,-0.018780534091982486,0.017041544309977535,-0.009673966401577923,-0.0748396343001558,-0.02918790360622798,-0.5402445585245125,-0.34887177026016064,-0.2779037346392723,0.04684314607635463,1.013224779431976,-0.8724780122578552,0.09375077537112285,-0.5346075106280976,0.4965621657813015,0.22174819168821364,-0.4102624171958163,0.5212743016855065,0.16544283848725527,0.6476901686855308,-0.6794482692466808,0.17251410132489167,2.210856621444568,-2.624201822719334,0.029434814624249572,0.2223206613473705,0.19031938015266037,0.027608020839082204,0.30106038898916276,0.02690094876599547,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.45,1.0,0.0,1.0,1.0,3.3881862259201374,-0.009305051049568785,0.6063487013565756,0.9922781661251616,0.02670942930023157,0.059185152263787934,0.10567764744379246,0.14511028159514036,-0.020808010229197507,0.01497148602428236,-0.009274321929759258,-0.07071727663783317,-0.03126363445296698,-0.5388747639890943,-0.34317305002538984,-0.2841082283482293,0.04826324198063907,1.0316562736682016,-0.8943143217592063,0.09400583321386548,-0.532724833303959,0.4982077182293415,0.22198814877430584,-0.4077118638854126,0.5215273418471313,0.16540337562374496,0.7017451389487395,-0.7748534308994415,0.16766793443827116,2.2050869375474447,-2.6102905539554344,0.03165265348213153,0.23053498422733965,0.1979134950090744,0.02970006068052533,0.31160510773975747,0.027964507417270745,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.458333333333334,1.0,0.0,1.0,1.0,3.389438048683898,-0.009222855895533125,0.6063188495018305,0.9923104541408823,0.02669326048318238,0.058897727952872236,0.10553904533149097,0.1498851664360394,-0.0220844661228879,0.014235056038714278,-0.009506082472978435,-0.06840727595566336,-0.0330280693881401,-0.5374878355974501,-0.3371760179443483,-0.29081795848759634,0.04963761165032582,1.0499762283911,-0.9159828548237791,0.09427831959582504,-0.5307652608909753,0.49986072403145276,0.22224319269955572,-0.405068998733487,0.5217403768091277,0.16721919305841215,0.7271657413352961,-0.8184422615607034,0.16123501591515682,2.189169022316202,-2.591257559793134,0.033210834288773805,0.23819954041455205,0.19691579284723426,0.03097909117943831,0.3204057292527063,0.02267154570081198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.466666666666667,1.0,0.0,1.0,1.0,3.3907163373950637,-0.009142929007941327,0.6062819678339517,0.9923429052243505,0.026674777140961326,0.058618461811109364,0.1053939782448464,0.15188369320467887,-0.022776294874979855,0.013707675491756704,-0.009758192006339945,-0.06652636935026257,-0.034566431745238005,-0.5360877774381207,-0.3310536210031349,-0.29774893270757435,0.05095049224589168,1.0681424240401383,-0.9375019477557586,0.09455934711867837,-0.5287548409637165,0.5014896481101287,0.2225044669606298,-0.4023717683978675,0.5219052009421449,0.1682850541615899,0.7358948024528955,-0.8355731238355613,0.1531219155900261,2.169518041412841,-2.575304452111604,0.03384717648961061,0.24254265598486757,0.19362658624023865,0.031362955283491534,0.3246782155050143,0.017485885283592406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.475,1.0,0.0,1.0,1.0,3.392001890188897,-0.009065341299260647,0.6062403612892432,0.9923754808378132,0.026654111349636182,0.05834670013034832,0.10524317537959146,0.15196717988023967,-0.023055439803850265,0.013136183020875197,-0.01000979848363349,-0.06473898035191683,-0.0359564757784334,-0.5346830846947569,-0.3249111045701334,-0.304744177218189,0.052189643576826254,1.0861348624146474,-0.9589045956923058,0.09484243920398522,-0.5267228832912275,0.5030878338021234,0.22276590862094725,-0.39965769514173677,0.5220318082305209,0.1684254193197865,0.73429012021615,-0.8376114472651541,0.1437099725526729,2.1478714938994825,-2.5629252311864636,0.033830428106029764,0.24371040483909479,0.18997018410449318,0.031141096893881892,0.32495561605620393,0.013606945377235835,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.483333333333333,1.0,0.0,1.0,1.0,3.393281422894943,-0.008990091446704016,0.6061949592470162,0.992408142008731,0.026631295690429387,0.05808229166975859,0.10508711224035332,0.15072854085813425,-0.02304827939316098,0.012488184474801132,-0.010266164746870832,-0.0629783825273594,-0.03725111675504142,-0.5332806871161243,-0.31881545233286573,-0.3117091234953269,0.0533456584551029,1.1039402822717963,-0.980217368275533,0.0951231875871122,-0.5246930008830649,0.5046558178452036,0.2230234852421945,-0.3969558414635974,0.5221319833650988,0.16785970973927977,0.7260335012068486,-0.8303742420672044,0.1332781621642326,2.1247675076140293,-2.553222910885482,0.03336617315051249,0.24240309489205858,0.1864995394035951,0.030511182271298898,0.32221164345897946,0.01104780377461756,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.491666666666667,1.0,0.0,1.0,1.0,3.3945456922591304,-0.00891716026217382,0.6061462584620795,0.9924408647353153,0.026606333509334456,0.05782514162591147,0.10492609788109439,0.148563829887281,-0.02283974297295694,0.011779475471270999,-0.01052900424834716,-0.061242809366495905,-0.038483233282611974,-0.5318854228657689,-0.3128105462166859,-0.3185837479193091,0.054410946279563464,1.1215476542082146,-1.0014583108737305,0.09539854208982709,-0.5226828317096932,0.50619615945885,0.2232744283254689,-0.3942875010840871,0.5222159382934312,0.16681061695845267,0.7133794006320826,-0.8171732134807519,0.12200313589218872,2.100386198108408,-2.5452794664500744,0.032588342788511804,0.23925225894464663,0.18336801895193933,0.02959678837328117,0.3172549928032309,0.009605659060902827,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5,1.0,0.0,1.0,1.0,3.3957881448889404,-0.008846520162663553,0.6060946027649445,0.9924736380404273,0.026579225239402655,0.05757511916030452,0.10476033712311532,0.14573479903617118,-0.022485763152423215,0.011030560920911186,-0.010798059662266955,-0.059542196484744125,-0.03967309394364402,-0.5305005101668168,-0.30692579565566436,-0.32532867705333945,0.05537904405330604,1.1389467189069364,-1.0226386927163675,0.0956663266335874,-0.5207054632339875,0.5077119514944026,0.22351676504841586,-0.39166825825021023,0.5222920776827805,0.1654423078917877,0.6977514098379978,-0.8000210041108624,0.10999422949225915,2.074786311691117,-2.538400068678013,0.031583447206873505,0.2347214064448755,0.18061390953056478,0.02847639052925177,0.31066392972825096,0.009086765880725878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.508333333333333,1.0,0.0,1.0,1.0,3.39700400563064,-0.008778137873256852,0.6060402713256678,0.9925064599393503,0.026549974920333473,0.0573320520105435,0.1045899690345566,0.14241434748953422,-0.022023184336793747,0.010257619393685746,-0.011072572351045525,-0.05788558549474426,-0.0408335170267373,-0.5291280510675724,-0.3011813560527193,-0.3319174313211568,0.056244183437767784,1.1561274260697332,-1.0437649786850307,0.09592493287660832,-0.5187708082689453,0.5092063912843594,0.22374903483428976,-0.3891097689219496,0.5223673843914433,0.16386629909801886,0.6800644794995014,-0.7801864335707753,0.09731849755411595,2.0479768112788843,-2.53209804297438,0.03040791990496866,0.22913032483770301,0.17824241412131014,0.027200836407058615,0.3028330827448622,0.009344610133574793,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.516666666666666,1.0,0.0,1.0,1.0,3.398189677276986,-0.008711975905402665,0.6059835098483146,0.9925393342441743,0.026518590712530172,0.0570957380393924,0.10441509001332279,0.13871729466457935,-0.021476451469762643,0.009471985535050114,-0.011351766289053013,-0.05627910972574255,-0.04197291400182934,-0.5277694051818498,-0.295591387664006,-0.33833178427951904,0.05700101901254131,1.1730796657615845,-1.0648403267659405,0.09617312529867021,-0.5168866244866924,0.5106826583964245,0.22397011232186684,-0.38662104020446253,0.5224478211850068,0.16215649030526302,0.6609138456617003,-0.7584868368121267,0.0840163767963277,2.01994105848716,-2.526037922761013,0.029098963652444687,0.2226957504993221,0.17624946126814978,0.025803554484602476,0.2940283879540251,0.010275078329160525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.525,1.0,0.0,1.0,1.0,3.39934234873705,-0.008647993460701026,0.6059245435180156,0.9925722683984035,0.02648508414036966,0.05686595676153571,0.10423576778688307,0.1347206450919563,-0.02086195800875083,0.008681289084201179,-0.01163493753888743,-0.0547264017806576,-0.043097020750149026,-0.526425442895818,-0.29016612529169095,-0.3445588786013589,0.057644456384373245,1.1897931103778525,-1.0858656107310476,0.09640991560414906,-0.5150592124272899,0.5121438823054952,0.2241790940756998,-0.3842092957893825,0.5225386356969293,0.1603615746184217,0.6406909336593558,-0.7354567324612971,0.07011145691334014,1.9906464931241352,-2.519985840984935,0.027681342862791447,0.21556468899148307,0.17462865769207747,0.02430676440738022,0.2844295137872621,0.011805039577852394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.533333333333333,1.0,0.0,1.0,1.0,3.4004597398788596,-0.008586146895650588,0.605863583338317,0.9926052720682943,0.026449469373662732,0.0566424778335274,0.10405205013337572,0.13047679368698806,-0.0201908529550313,0.00789059570242089,-0.011921434001658127,-0.05322932492931343,-0.044209890682016244,-0.5250967122715428,-0.28491320543635007,-0.3505893964872073,0.05816954329443031,1.2062571073136534,-1.1068400907823561,0.09663448101305007,-0.5132938796701677,0.5135931360246258,0.22437522506198984,-0.38188054830800816,0.5226445718446376,0.15851366774369602,0.6196561425643565,-0.7114503486286206,0.05561669777754935,1.9600493250379847,-2.5137740309356893,0.026171708866218613,0.20783799111077306,0.17337323405014038,0.0227253888730794,0.27415928069545625,0.013882518528540722,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.541666666666666,1.0,0.0,1.0,1.0,3.401539935324922,-0.008526389866808396,0.6058008296326488,0.9926383562296299,0.026411762794011875,0.056425066773456795,0.10386397049729762,0.12602210411480347,-0.01947085500807424,0.00710325511362446,-0.012210618416942121,-0.05178856843380735,-0.04531447695241744,-0.5237835484334231,-0.27983852291561834,-0.35641638441183593,0.0585714013473324,1.2224605991284856,-1.1277618445799757,0.09684611075191937,-0.511595245908777,0.5150334362063309,0.2245578505569178,-0.37963997444445824,0.5227700110057383,0.15663400564215557,0.5979851172169182,-0.6867056769090119,0.04053846949701803,1.928097180071977,-2.5072769537542205,0.024581388862665865,0.1995862401047721,0.17247645698821756,0.02106956824034112,0.26330331557598674,0.016469539097581087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.55,1.0,0.0,1.0,1.0,3.4025812760514764,-0.008468673262249822,0.6057364741082563,0.9926715325674718,0.026371982819809275,0.0562134886908783,0.103671551746373,0.12138248269925231,-0.01870742836791518,0.006321480089498253,-0.012501837418660306,-0.05040406081040149,-0.04641298058407346,-0.5224861455108402,-0.2749467868160681,-0.3620344911023575,0.058845184452713944,1.238392060314853,-1.1486280400115931,0.09704417082742783,-0.5099674423350882,0.516467743641096,0.2247263845326622,-0.37749215971507505,0.5229190641629307,0.1547366426817498,0.5757983818024293,-0.6613850845652491,0.024879229665968478,1.894730733872123,-2.5003955946237832,0.022918197954804875,0.1908602714102603,0.17193156912938434,0.019346294197575276,0.25192300854218974,0.01953718078934852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.558333333333334,1.0,0.0,1.0,1.0,3.403582288588037,-0.008412944997186894,0.6056707010961765,0.9927048130710342,0.02633014992059041,0.05600751069382951,0.10347480880216757,0.11657700707065471,-0.017904547267008825,0.0055467297995849575,-0.012794398931232343,-0.04907524072404735,-0.04750706082737854,-0.5212046043887273,-0.2702418832189112,-0.3674394691545901,0.05898605517509854,1.254039444693021,-1.1694351044903721,0.09722808071783279,-0.5084142413852727,0.5178989623584873,0.22488028879354405,-0.37544125763542174,0.5230956306855608,0.15283083875184733,0.5531804218292558,-0.6356012997728766,0.008639334547518862,1.859884771932654,-2.49304720234222,0.02118762236404198,0.18169809909462487,0.17173160028610024,0.01756047766208635,0.24006402120629988,0.023062227382930622,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.566666666666666,1.0,0.0,1.0,1.0,3.4045416387354854,-0.008359149725555768,0.6056036882810594,0.9927382097490877,0.02628628676326298,0.0558069034450224,0.1032737505867615,0.11162029584927075,-0.01706519495116846,0.004779960744293326,-0.013087555793259969,-0.04780122982286472,-0.04859796201154694,-0.519938964864976,-0.26572711311891384,-0.37262784609857214,0.05898917336183926,1.269390139847064,-1.1901788267172968,0.09739729786682853,-0.5069391406835111,0.5193299369791977,0.22501905916036363,-0.37349109269497005,0.5233034346193128,0.15092259727752522,0.5301920363692814,-0.6094341600751507,-0.008181704308459076,1.823488901582011,-2.485158585263947,0.019393595610942282,0.17212947364906306,0.1718691659077476,0.015715650488539734,0.22776187521938773,0.027024910447375206,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.575,1.0,0.0,1.0,1.0,3.4054581013327807,-0.008307228500882193,0.6055356070984924,0.9927717344187924,0.02624041845079125,0.05561144218176901,0.10306838155853991,0.10652406330965433,-0.016191691001588945,0.0040217903363929716,-0.013380493445809282,-0.04658094089355853,-0.049686588663328986,-0.5186892277674352,-0.26140534927942316,-0.3775967051558426,0.058849693436624224,1.2844309263860545,-1.2108544142447712,0.09755130731134849,-0.505545416824455,0.5207634484569498,0.22514221630168638,-0.3716452263817653,0.5235460458596837,0.14901565522593252,0.5068783837229218,-0.5829414912673936,-0.025584318878468654,1.785468049983261,-2.476661713186026,0.017539010816746692,0.1621788875113861,0.17233629076426338,0.013814429674793849,0.21504563283444744,0.03140739288234551,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.583333333333334,1.0,0.0,1.0,1.0,3.4063305405878452,-0.008257118408236694,0.6054666229058675,0.992805398538194,0.02619257282755381,0.0554209074047653,0.10285870300819075,0.10129814646276641,-0.015285907742475882,0.0032726034245619817,-0.013672320269146738,-0.04541314399441569,-0.05077354817142643,-0.5174553706112105,-0.25727914005686514,-0.38234353761969536,0.058562768047198115,1.2991479406801183,-1.231456521937064,0.09768961471377431,-0.504236159224988,0.5222022084919354,0.22524929965494353,-0.3699069988143959,0.5238268911673519,0.14711211997926466,0.4832742659315892,-0.5561662440173043,-0.04356821005687711,1.7457428350420923,-2.467490809698032,0.015626062188563716,0.15186756614839148,0.17312426694852556,0.011858827757749157,0.20194033320039995,0.03619274883379653,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.591666666666667,1.0,0.0,1.0,1.0,3.407157897423779,-0.008208752182582085,0.6053968949915378,0.9928392130635776,0.026142780834175487,0.05523508536853138,0.10264471422283586,0.09595119105587965,-0.014349415184982693,0.002532621722019176,-0.013962059810814399,-0.0442965054048747,-0.05185917303213386,-0.5162373591011141,-0.25335077818056334,-0.386866142556131,0.05812355660234294,1.3135266403034227,-1.2519792610730718,0.09781174168115789,-0.5030142907219818,0.5236488529060919,0.2253398634309822,-0.3682795541617586,0.524149258340247,0.14521287931904325,0.45940764203762474,-0.5291412411773488,-0.062131815625519615,1.7042298688387758,-2.457580406061255,0.013656476456534727,0.14121479803924641,0.17422354423822783,0.00985046408265855,0.18846861903437984,0.04136427469568327,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6,1.0,0.0,1.0,1.0,3.407939181549713,-0.00816205782551277,0.6053265764621135,0.9928731883199026,0.02609107689949798,0.05505376845930023,0.10242641358619572,0.09049111784765176,-0.013383580229175799,0.001801949230496697,-0.01424864458976235,-0.04322960901335502,-0.05294353036566654,-0.5150351559558931,-0.24962234602290473,-0.3911625583059845,0.05752723778677279,1.3275517718274312,-1.2724161953714181,0.09791722265471656,-0.5018825792576672,0.5251059342292392,0.22541347405632117,-0.36676585516382293,0.5245162957456133,0.14331786665807922,0.43530200665990393,-0.501892400465862,-0.08127186580957693,1.660842036592296,-2.44686401411625,0.011631674094852995,0.13023883595408625,0.17562364701040112,0.007790712803154576,0.17465183871879897,0.04690501938610092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.608333333333333,1.0,0.0,1.0,1.0,3.408673466786039,-0.008116958231019168,0.6052558140325252,0.9929073338770747,0.026037499359824336,0.054876755515599146,0.10220379965682765,0.08492544840537833,-0.012389636966419218,0.001080602261512081,-0.014530911431290167,-0.04221096640078766,-0.05402642372178976,-0.5138487279901461,-0.2460957447362316,-0.3952310158972287,0.05676902550551666,1.3412073409132943,-1.2927603279750093,0.0980056029160721,-0.5008436434560803,0.5265759136895986,0.2254697086443681,-0.36536869018311197,0.5249310086633486,0.14142623531007148,0.41097804495888124,-0.4744409875963307,-0.10098299037060512,1.615488783983583,-2.435273196642407,0.009552886544630101,0.11895752286149364,0.17731311109911552,0.005680811214040515,0.1605108113644027,0.052797458172904044,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.616666666666667,1.0,0.0,1.0,1.0,3.4093598887109073,-0.008073370830687154,0.6051847477342719,0.9929416584278111,0.02598209089655085,0.054703852126745396,0.10197687224941102,0.07926154239347973,-0.011368739165687985,0.00036852974435633637,-0.014807598448377179,-0.04123901974102254,-0.05510739052786432,-0.5126780520340586,-0.2427727119402567,-0.3990699080992567,0.0558441879472627,1.3544765848938243,-1.313004081982125,0.09807643743046039,-0.4998999538766423,0.5280611527475578,0.22550815424322185,-0.3640906749744162,0.5253962533818284,0.1395364773396901,0.38645483072710873,-0.446805257877283,-0.12125735366273038,1.5680764396189417,-2.422736892145303,0.0074212467844553265,0.10738874409482624,0.17927943447024308,0.003521944023602841,0.14606637875934636,0.05902325864031388,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.625,1.0,0.0,1.0,1.0,3.4099976440482114,-0.008031207269167307,0.6051135105518765,0.9929761696648648,0.02592489898337541,0.05453487093108284,0.10174563353251283,0.07350678061091839,-0.01032200228019428,-0.00033437237273974824,-0.015077343880478059,-0.04031214030237987,-0.05618569748587061,-0.5115231200344846,-0.2396548308907798,-0.4026777701951834,0.05474806961113782,1.3673419482402767,-1.333139276177431,0.09812929036247969,-0.4990538310544999,0.5295639042641026,0.22552840771142815,-0.36293425053712286,0.5259147296406872,0.13764651077734502,0.36175074171625854,-0.41900171848584744,-0.1420843023894111,1.5185085960875444,-2.409180902302306,0.005237864796474867,0.09555077353168184,0.18150903656420692,0.0013153139449006979,0.13133982655135434,0.0655631037838944,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.633333333333333,1.0,0.0,1.0,1.0,3.4105859914511343,-0.00799037312151627,0.6050422279947161,0.9930108741567786,0.02586597633379297,0.054369631926502925,0.10151008914819315,0.0676687164933566,-0.00925053986067077,-0.0010282500370011457,-0.015338687059602603,-0.03942862451317724,-0.057260335566780785,-0.5103839435211028,-0.2367435329116524,-0.4060532700740208,0.05347611624077252,1.3797850614952833,-1.3531570970204967,0.0981637351770683,-0.4983074409844476,0.5310863033569613,0.22553007614230353,-0.361901677865227,0.5264889717782266,0.13575375139492474,0.3368842066676786,-0.39104616297780725,-0.16345001642024098,1.466686571575031,-2.394527484001374,0.0030038956713152043,0.08346255926908519,0.1839872222666017,-0.000937794450475149,0.1163532297391856,0.07239654835212717,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.641666666666666,1.0,0.0,1.0,1.0,3.411124253490998,-0.00795076766493149,0.6049710176102477,0.9930457772223537,0.025805381338773158,0.0542079627989949,0.10127024935292085,0.061755211230231824,-0.008155497646264716,-0.0017132815124434701,-0.015590071810394315,-0.03858668906701875,-0.05833001583739891,-0.5092605575112359,-0.23404009411298515,-0.40919520624481354,0.05202390267080047,1.3917867244331938,-1.373048067577454,0.09817935529033495,-0.49766278840001515,0.532630357968546,0.22551277780392023,-0.36099503004146977,0.5271213387798893,0.13385518033091515,0.3118743599210083,-0.36295457764994876,-0.18533715692663752,1.4125099737355118,-2.3786950103602544,0.0007206055753580798,0.07114397953205565,0.1866981475684959,-0.0032359529470921133,0.10112975954952419,0.07950189220073067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.65,1.0,0.0,1.0,1.0,3.411611819765421,-0.00791228371833159,0.6048999884447447,0.9930808828047989,0.025743178483499364,0.054049699269592535,0.10102613017473709,0.05577456263936753,-0.007038087523486762,-0.0023896680018351615,-0.01582985261388766,-0.03778446627624893,-0.05939316709478289,-0.5081530238489209,-0.23154562691296893,-0.4121025130348533,0.05038716362532856,1.4033268943908752,-1.3928020138598343,0.09817574526999094,-0.4971217079922467,0.5341979391497695,0.22547614359318532,-0.3602161818727349,0.5278140033149055,0.1319474156599698,0.28674165429434684,-0.3347439856083434,-0.20772450891088548,1.355877388071307,-2.3615976803964944,-0.0016105608881711309,0.05861608968446563,0.18962478502975832,-0.005577526831292423,0.08569397676621349,0.08685605978699495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.658333333333333,1.0,0.0,1.0,1.0,3.412048151109679,-0.00787480756407332,0.6048292404586801,0.9931161933471655,0.025679438730926294,0.05389468545542116,0.10077775457793331,0.049735634557731084,-0.005899622800022217,-0.0030576234865705206,-0.01605630387618228,-0.03702000075738238,-0.06044793611688134,-0.5070614339169031,-0.2292610665414127,-0.41477427267161926,0.04856182752228571,1.414384680901049,-1.4124080289173955,0.09815251260886543,-0.4966858535719407,0.5357907710523753,0.2254198190233987,-0.3595667970953662,0.5285689397763392,0.13002679389232386,0.2615084662438921,-0.30643327210617244,-0.23058661735051875,1.2966872141124863,-2.343145267779261,-0.003987909566332826,0.04590137443871045,0.19274888817412572,-0.007960608891667276,0.07007212837826238,0.09443447884427192,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.666666666666666,1.0,0.0,1.0,1.0,3.4124327849414313,-0.007838218966741306,0.6047588639056849,0.9931517096712178,0.025614239858762797,0.0537427742361564,0.10052515362338665,0.04364799113918418,-0.0047415557042743235,-0.0037173630123393895,-0.016267632643610103,-0.03629124850300599,-0.06149219122695734,-0.5059859106173822,-0.22718715247557073,-0.41720973423662283,0.046544053336153246,1.4249383479594167,-1.4318544349894886,0.09810928011055206,-0.49635668508493486,0.5374104206193383,0.2253434667783242,-0.35904831306643054,0.5293879112956433,0.12808946594508486,0.23619971591655353,-0.2780440195598799,-0.25389341794467807,1.2348386739539352,-2.3232429070481864,-0.006409420389218157,0.03302401452500825,0.19605095494291014,-0.010382948972155193,0.054292458599295434,0.10221095428594174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.675,1.0,0.0,1.0,1.0,3.4127653417982606,-0.007802391304303671,0.6046889386864311,0.993187430862391,0.025547666735375937,0.05359382761276189,0.10026836760995103,0.03752203868970461,-0.0035655176064191686,-0.004369088792042797,-0.01646199509321451,-0.035596079424306225,-0.062523529784998,-0.504926609484485,-0.22532440460947015,-0.4194083396642839,0.044330270556541075,1.4349653254669479,-1.4511287440348652,0.09804568893571179,-0.49613545332985726,0.5390582869680904,0.22524676987386277,-0.35866192278537795,0.5302724556811049,0.1261315110660699,0.2108435165188588,-0.2496013698225319,-0.2776098650259175,1.1702330189425725,-2.3017909219783306,-0.008872664917761452,0.02001017339213651,0.19951019135679982,-0.012841878385494998,0.03838554091641133,0.11015753588125454,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.683333333333334,1.0,0.0,1.0,1.0,3.4130455331435137,-0.007767191826891256,0.6046195336917998,0.9932233541639366,0.025479811519117587,0.05344771704072839,0.10000744717986383,0.031369176244030995,-0.0023733621042782904,-0.005012973605314247,-0.016637517098743712,-0.03493228451106541,-0.06353929014420691,-0.503883718766281,-0.22367309386692308,-0.42136975706699836,0.041917222252387955,1.4444422316084595,-1.4702176170224608,0.0979614023619227,-0.4960231821950659,0.540735590475285,0.2251294354718993,-0.358408554051157,0.5312238702269976,0.1241490713171034,0.1854718610366768,-0.22113492293072357,-0.3016955607157583,1.1027749612419235,-2.2786847061121707,-0.011374717562058212,0.0068883064178992814,0.2031044775978641,-0.015334229022050394,0.022384634188533648,0.1182443804892852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.691666666666666,1.0,0.0,1.0,1.0,3.413273170520686,-0.007732482057921927,0.6045507061531805,0.9932594748837859,0.025410773764771244,0.053304323715083465,0.09974245436898034,0.02520195480347335,-0.0011672107872733655,-0.0056491410706023,-0.01679231912375117,-0.034297588829331836,-0.06453656853139225,-0.5028574582958666,-0.22223320692552553,-0.4230939217131293,0.03930201121127844,1.4533449081543133,-1.489106822470068,0.09785611030967749,-0.49602064822289227,0.5424433615947215,0.22499119939016193,-0.3582888455489024,0.5322431953559263,0.12213850839617235,0.1601213488061376,-0.19267967441240708,-0.3261043909508989,1.032374357321002,-2.2538146703395334,-0.013912060787119318,-0.006310507755437067,0.2068103398432375,-0.017856247497423094,0.00632606248296641,0.1264396118070965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.7,1.0,0.0,1.0,1.0,3.41344817613051,-0.007698118351138706,0.604482501021662,0.9932957863180412,0.025340660420303224,0.0531635387792132,0.09947346358083191,0.019034243881307925,5.049884257686196e-05,-0.006277642468211093,-0.016924545621057302,-0.03368967163721871,-0.06551224121554261,-0.5018480769596781,-0.22100440472015412,-0.4245810849738718,0.036482149069872974,1.461648470897143,-1.507781194861453,0.09772953468213738,-0.4961283573243232,0.5441824294726723,0.22483183134694223,-0.3583031196764409,0.5333311970904492,0.12009658369390941,0.13483394909970192,-0.164276986502776,-0.3507841756489005,0.9589481697467583,-2.2270662770548055,-0.01648048520650286,-0.019552217042291264,0.21060293235360739,-0.020403505207030048,-0.009750385006903617,0.1347091827845892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.708333333333334,1.0,0.0,1.0,1.0,3.413570594887696,-0.00766395261524792,0.6044149504020764,0.9933322796953282,0.025269585696968435,0.05302526342412577,0.09920056246209424,0.012881402649649147,0.0012769641694170414,-0.006898429917924727,-0.01703239901727431,-0.03310619492407801,-0.06646299221460818,-0.5008558485676348,-0.2199859744405305,-0.4258318714881756,0.03345560828379676,1.4693273776500926,-1.5262245937543149,0.09758143555623577,-0.49634651850693046,0.5459534104672816,0.22465114097004477,-0.3584513519656841,0.5344883484023362,0.11802066145756518,0.1096577932803866,-0.13597558169061386,-0.37567634205090494,0.8824227315731559,-2.1983201849749445,-0.019074986102759206,-0.03279943330326218,0.2144560355323466,-0.022970805730448962,-0.02580104119845328,0.1430167481457545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.716666666666667,1.0,0.0,1.0,1.0,3.4136406079848287,-0.007629833215117029,0.6043480730721914,0.993368944146503,0.025197670796188006,0.05288940883941331,0.09892385265613934,0.006760451488129691,0.002508968246152074,-0.007511325875306454,-0.01711417822763612,-0.03254484163983124,-0.06738534665099868,-0.4998810659353854,-0.21917677483214767,-0.4268473446687154,0.03022087670235789,1.4763555164233622,-1.5444198646110354,0.0974116182470914,-0.49667501454604424,0.5477566967315447,0.22444898458476809,-0.35873313702974846,0.5357148095595451,0.1159089337146213,0.08464798087902958,-0.10783253953371763,-0.4007156321905731,0.8027363335824855,-2.167452533148815,-0.021689658624902686,-0.04601106717288306,0.21834207686712848,-0.0255520916699864,-0.04177794670462087,0.15132355683578735,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.725,1.0,0.0,1.0,1.0,3.4136585479479136,-0.00759560605482671,0.6042818741215853,0.9934057667043387,0.025125043477591397,0.05275589597215449,0.09864345041104303,0.0006902380647851279,0.0037428322468362526,-0.008115989117773793,-0.017168321476803406,-0.03200336474973169,-0.06827570970063104,-0.4989240330057244,-0.21857517475921334,-0.4276290804804042,0.026777014413953876,1.482706316543134,-1.5623488026401284,0.09721994124582073,-0.4971133696264785,0.5495924450817338,0.224225272775545,-0.3591476510774278,0.5370104076829326,0.11376066414679809,0.05986737796495112,-0.0799142694217847,-0.42582985747896074,0.7198421480576966,-2.1343353969003376,-0.02431759470670758,-0.059141974049033985,0.22223218277883872,-0.02814035372236623,-0.05762844936466838,0.15958837663295755,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.733333333333333,1.0,0.0,1.0,1.0,3.4136249151097635,-0.007561115843194412,0.6042163447485903,0.9934427323378369,0.02505183745432531,0.05262465504581807,0.09835948701883888,-0.005308409763858813,0.004974371725102044,-0.008711877656579825,-0.01719345299206342,-0.0314796479925959,-0.06913041088999386,-0.4979850548662721,-0.2181789851993985,-0.42817924915907846,0.02312371241104188,1.488352885557657,-1.579992121226041,0.0970063250019796,-0.49766071411352814,0.5514605664445253,0.22397997868939531,-0.35969361118582627,0.538374615836761,0.11157644637639352,0.03538737833129857,-0.05229742286804506,-0.45093971552466466,0.633711492994804,-2.0988374521716047,-0.026950785622935902,-0.07214262920598125,0.2260962703379299,-0.030727545573045467,-0.07329483816026494,0.16776746553230693,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.741666666666667,1.0,0.0,1.0,1.0,3.413540395352544,-0.007526207536665446,0.6041514622567454,0.9934798240256217,0.024978191604287055,0.05249562478847083,0.09807210906405442,-0.011212553936427564,0.00619885928066061,-0.009298209338683906,-0.017188432886003167,-0.030971778802516788,-0.06994575328595058,-0.49706442556611785,-0.21798538512035837,-0.42850070419487163,0.0192613524885428,1.493268174759714,-1.5973294268429885,0.09677076148543846,-0.49831574677991153,0.5533607162540326,0.22371314701599423,-0.3603692317134322,0.5398065321084711,0.10935847013059719,0.011288589351611256,-0.025069699073846374,-0.4759586864527876,0.5443374270118051,-2.0608248875681845,-0.029580035032710505,-0.08495885451101803,0.22990318842535773,-0.03330450904739213,-0.08871403714057147,0.17581460665553772,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.75,1.0,0.0,1.0,1.0,3.4134058788781116,-0.00749072794772938,0.6040871902940177,0.9935170228724841,0.024904248989441713,0.05236875131902583,0.0977814784617065,-0.016997050821926665,0.007410996694074457,-0.009873921296090422,-0.017152409257373425,-0.030478133243288394,-0.07071806690148122,-0.4961624136974288,-0.2179908420435383,-0.4285970774769759,0.015191067636828752,1.4974251760078539,-1.6143392026855108,0.09651332441810109,-0.4990766950220451,0.5552922862516146,0.22342490353860545,-0.36117217847150246,0.54130485928102,0.1071107865185239,-0.012338604880832715,0.0016695127601451532,-0.5007930280259069,0.4517386470515605,-2.020162604825715,-0.032194888319021786,-0.09753162386212488,0.2336209180589166,-0.03586091482735865,-0.1038173903068551,0.18368122515465268,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.758333333333333,1.0,0.0,1.0,1.0,3.4132224796542263,-0.007454527499359782,0.6040234793780526,0.9935543082724791,0.024830155679909004,0.05224398664274804,0.09748777226802317,-0.02263450429258577,0.008604900005516457,-0.010437629856462226,-0.01708487121695999,-0.02999747197429849,-0.07144376541903474,-0.4952792457908091,-0.2181910285350389,-0.42847287898220254,0.010914802021444351,1.5007971522105734,-1.6309988035900838,0.09623418001345477,-0.4999412738442803,0.5572543982216812,0.22311546510220492,-0.3620995215518798,0.5428678858610486,0.10483956125514227,-0.035393659928757426,0.02780872107552068,-0.5253418906452983,0.35596363777760764,-1.9767157477538477,-0.03478358496058459,-0.1097969789009956,0.23721684108348962,-0.03838522489148344,-0.11853057354445973,0.19131660658361582,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.766666666666666,1.0,0.0,1.0,1.0,3.412991555057149,-0.007417462097593388,0.6039602677482916,0.993591658121004,0.02475605938508884,0.05212128671374647,0.09719118225117407,-0.028095282820532686,0.009774101340967518,-0.010987593032282476,-0.016985701199499954,-0.02952904520278995,-0.07211940512678007,-0.49441508767650977,-0.21858073637568426,-0.4281335987923839,0.006435369459407112,1.5033579033041473,-1.647284465148075,0.09593359800209135,-0.500906644670395,0.5592459002696728,0.22278514979041406,-0.3631476880305768,0.5444934693907469,0.10255330221925041,-0.057765732600397746,0.05322422552152428,-0.5494975746046419,0.25709499307501105,-1.9303515961695927,-0.03733304148995781,-0.12168609040585143,0.24065808505410402,-0.04086468358995343,-0.13277367417226293,0.19866823616442764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.775,1.0,0.0,1.0,1.0,3.412714725089467,-0.007379395085557891,0.6038974825803236,0.9936290490769769,0.02468210790072145,0.052000609033695105,0.09689191421416736,-0.033347617532132084,0.01091157147120044,-0.011521678233804202,-0.01685522457048575,-0.0290727032864021,-0.07274174479048548,-0.49357002408715495,-0.21915379074504554,-0.4275858085568438,0.001756509111366987,1.5050820687618236,-1.6631713301929103,0.0956119626552888,-0.5019693753510445,0.5612653663059163,0.22243438704237237,-0.3643124161214175,0.5461790231304557,0.1002630454064457,-0.07933386095528294,0.07778039973825979,-0.5731459525058303,0.15525379646759152,-1.880941854036009,-0.03982887319508244,-0.13312550348035357,0.2439119497262876,-0.043285344831894834,-0.14646148190756492,0.2056822769382438,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.783333333333333,1.0,0.0,1.0,1.0,3.412393890401093,-0.007340199233460101,0.6038350415886813,0.9936664568745562,0.024608447388339366,0.05188190977345828,0.09659018706763342,-0.03835779876244247,0.012009767058744649,-0.01203733836206006,-0.01669425420017825,-0.028629008170463575,-0.07330780506088055,-0.4927440369197357,-0.21990296739160564,-0.4268372587967462,-0.0031170630823567267,1.5059454665786072,-1.678633496048675,0.09526978344883998,-0.5031254030617343,0.5633110994317776,0.22206372737654914,-0.3655887127290362,0.5479215073397177,0.09798248137618093,-0.09996754078621217,0.10133045060678691,-0.5961670792218302,0.050603909305078076,-1.82836534910634,-0.042255462979224334,-0.14403760556886303,0.24694641696147324,-0.04563214311508523,-0.15950403623650078,0.21230420157987595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.791666666666666,1.0,0.0,1.0,1.0,3.412031248189116,-0.0072997587107992675,0.6037728550310283,0.9937038566818127,0.024535220511898097,0.05176514042828348,0.09628623165626735,-0.04309048818784311,0.01306070623295496,-0.012531599879140895,-0.016504127389290607,-0.028199339251623445,-0.07381492596372088,-0.49193698273088526,-0.22081991642481574,-0.42589696771339736,-0.008179608875663517,1.5059254672502416,-1.6936440860113493,0.0949077049389684,-0.5043700021105255,0.5653811399219408,0.2216738513237876,-0.3669708167253592,0.5497174264901203,0.09572800298289996,-0.11952777745782572,0.12371774023812954,-0.6184360098439985,-0.05664402511813549,-1.772511144048372,-0.0445960855608879,-0.15434135472238486,0.249730740992129,-0.047889015937291335,-0.17180747352931847,0.21847958737757356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8,1.0,0.0,1.0,1.0,3.4116293049091806,-0.0072579709800516395,0.603710828108988,0.9937412235014043,0.02446256446514614,0.05165024404804512,0.09598028934889949,-0.04750916173121863,0.01405607546389503,-0.01300106675213284,-0.016286732330148435,-0.027785985678315292,-0.07426082105054503,-0.491148570203354,-0.22189509701590274,-0.42477529645944406,-0.013424329913090035,1.505001399493305,-1.7081753484494813,0.09452651535615851,-0.505697758973774,0.5674732784483131,0.22126557711092762,-0.3684521706211915,0.5515628337960106,0.09351865487272626,-0.13786868714741496,0.14477774930723109,-0.6398238423321521,-0.16622909417545184,-1.7132820357975742,-0.04683309431266547,-0.16395330064390645,0.2522361099166237,-0.050039084342173856,-0.18327521182608497,0.22415507632489007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.808333333333334,1.0,0.0,1.0,1.0,3.411190884611143,-0.007214748546024136,0.6036488637389208,0.9937785326056857,0.024390608932123248,0.05153715112124271,0.09567261040818686,-0.0515766947925626,0.014987369621802263,-0.01344194424072847,-0.016044521219871172,-0.027392215705658855,-0.07464362690940744,-0.4903783384830065,-0.22311772787727266,-0.4234840052249435,-0.018843339581199384,1.5031549823473174,-1.7221987866079755,0.09412715336709064,-0.5071025571212573,0.5695850750872179,0.22083986658475138,-0.3700254035891273,0.5534533444288685,0.09137596629032685,-0.15483970943236558,0.16434074428122947,-0.6601989957763104,-0.27783741511954396,-1.6505983907087352,-0.04894817635674953,-0.17278892216141983,0.25443636220797927,-0.0520648968298959,-0.1938095012231955,0.22927949240543422,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.816666666666666,1.0,0.0,1.0,1.0,3.410719131631388,-0.007170020492799649,0.6035868656402733,0.9938157599959349,0.024319474031492806,0.051425775233862096,0.09536345216135175,-0.055256095709200544,0.015846065577424285,-0.013850086257658012,-0.015780507257122118,-0.02702231273917318,-0.07496194694575717,-0.48962563743184856,-0.2244757588397755,-0.4220362840547569,-0.024427646509361873,1.5003707759079792,-1.7356853216279602,0.09371071241687935,-0.508577574343131,0.5717138844851127,0.22039782883042935,-0.37168232897491144,0.5553841586694345,0.08932365152717892,-0.17028847240794398,0.182235185251014,-0.6794287270463859,-0.3911005194458905,-1.5844022285739268,-0.05092267893966579,-0.1807642914312768,0.2563087343551196,-0.05394873949200574,-0.20331335265153405,0.23380509625644308,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.825,1.0,0.0,1.0,1.0,3.410217506351472,-0.0071237337414433695,0.6035247416609498,0.9938528828726377,0.024249268302595155,0.05131600866949404,0.09505307699789854,-0.05851138558290865,0.016623827725291546,-0.014221069388827536,-0.015498243097394407,-0.026681567386356145,-0.07521488863019056,-0.4888896109575535,-0.22595586908407173,-0.4204467521374266,-0.03016715169863915,1.4966366403565525,-1.748605490417541,0.09327844205142954,-0.5101152953117786,0.5738568873264699,0.2199407209265513,-0.37341395946665284,0.5573500960331426,0.08738716714435157,-0.18406432118606875,0.1982918746673501,-0.6973808780878573,-0.5055951353139143,-1.5146614302737582,-0.05273800654573363,-0.1877980572060589,0.25783460812367043,-0.05567301195286978,-0.211692837294013,0.23768894400222784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.833333333333334,1.0,0.0,1.0,1.0,3.409689772786143,-0.007075853967047771,0.6034624072302733,0.9938898801012929,0.024180086796407763,0.05120771816187931,0.0947417502234862,-0.06130861283203487,0.017312741456296875,-0.014550295552773995,-0.015201778951167387,-0.026376215448981787,-0.07540209374674191,-0.48816918464610937,-0.22754349752620998,-0.41873141947696774,-0.036050661144159495,1.491944190319414,-1.7609296787991895,0.09283174564111712,-0.511707541963232,0.5760111279538406,0.21946994529788152,-0.37521054292981165,0.5593456410694716,0.08559312206000036,-0.1960224806826405,0.21234880054288863,-0.7139258333751426,-0.6208446746008089,-1.441373904300196,-0.054376083722104396,-0.19381371729044083,0.2590002191782337,-0.05722066454787622,-0.21885972334304893,0.2408943031252142,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.841666666666667,1.0,0.0,1.0,1.0,3.4091399769095077,-0.007026366123654641,0.6033997888030226,0.9939267326561947,0.024112009337279472,0.051100741050816016,0.09442973780095791,-0.06361697943130114,0.017905567994242325,-0.014833123676553952,-0.014895599401038741,-0.026113313559922878,-0.07552376152403381,-0.48746305892322017,-0.2292229104287824,-0.4169076054617118,-0.04206591558822486,1.4862892291132057,-1.7726283888225443,0.09237217398939447,-0.5133455239332859,0.5781735576461071,0.21898704318408668,-0.3770616215223703,0.5613650010852295,0.08396854563847866,-0.20602877514350693,0.22425657216728734,-0.7289386525228302,-0.7363226981086068,-1.3645715102655487,-0.05581987334731697,-0.1987421248502308,0.2597972839308138,-0.05857568729418228,-0.22473438736023588,0.24339206508525724,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.85,1.0,0.0,1.0,1.0,3.4085724148778715,-0.00697527454016018,0.603336827135733,0.9939634240234292,0.024045099020659676,0.0509948821218243,0.09411730400988397,-0.06541004351355413,0.018396011338735037,-0.01506502870083859,-0.01458453917681047,-0.02590054723682104,-0.07558066484921018,-0.48676970888546806,-0.23097731044526842,-0.4149938099408463,-0.048199638686206664,1.4796721453509372,-1.7836725373036153,0.09190141441866184,-0.5150199107107358,0.5803410826860208,0.2184936838429785,-0.37895611605248225,0.5634021754875592,0.08254002969537932,-0.2139647724914262,0.23388428530150107,-0.7423013275773787,-0.8514585678726938,-1.2843235073937853,-0.05705393440183504,-0.20252414628039617,0.2602234995089181,-0.05972363590146412,-0.22924890609131277,0.24516208356526237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.858333333333333,1.0,0.0,1.0,1.0,3.407991590665312,-0.00692260256909166,0.6032734802221463,0.9939999405441308,0.023979401007526133,0.050889911423460665,0.09380470905502539,-0.06666695087756502,0.01877898558386629,-0.01524178380124786,-0.014273679510512786,-0.025745970491006586,-0.07557416000284067,-0.4860873917616305,-0.23278898997030617,-0.4130095340400201,-0.05443760438118117,1.4720982529819941,-1.7940337806124407,0.09142127508269722,-0.5167209263712925,0.5825106159712558,0.21799164925239561,-0.3808824366238922,0.5654510358113172,0.08133277215939927,-0.2197331653714646,0.2411255919951638,-0.7539050992161531,-0.9656453971719525,-1.2007392780147663,-0.05806499766756262,-0.20511336229961152,0.26028287358162316,-0.06065217476639628,-0.23235020402746498,0.2461943604389627,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.866666666666667,1.0,0.0,1.0,1.0,3.407402163087004,-0.006868391792244571,0.6032097257115282,0.9940362716801252,0.023914941667526956,0.050785563348444286,0.0934922066522057,-0.06737363729096686,0.019050868910506766,-0.015359659113553678,-0.013968228203237888,-0.025657681602068036,-0.07550619047520744,-0.4854141626828114,-0.23463952986812617,-0.4109750500742602,-0.06076472367314255,1.4635780553980713,-1.8036848586038614,0.0909336644575358,-0.5184384667490627,0.5846791305790479,0.21748281426353855,-0.38282861945294,0.5675054148282086,0.08036956198248402,-0.2232631483097247,0.24590469397292591,-0.7636527524027218,-1.0782502781891479,-1.1139700753536363,-0.058842532790704116,-0.2064786817666553,0.2599858470606109,-0.06135161215418905,-0.23400310566459304,0.24649000037003876,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.875,1.0,0.0,1.0,1.0,3.4068088827267475,-0.006812700811191053,0.603145562643926,0.9940724101865627,0.023851728110055443,0.050681537231800106,0.09318004161766313,-0.06752393574864411,0.019209729390661272,-0.015415627736364287,-0.013673388036155136,-0.025643445841416104,-0.07537928540475142,-0.48474789906192245,-0.23651004244213492,-0.4089111224738047,-0.06716515025455987,1.454127415012175,-1.8125999485350013,0.09044056620285215,-0.5201622377340701,0.5868437134222659,0.21696912238315913,-0.38478248838496876,0.5695592024841512,0.0796697554798409,-0.2245155081182698,0.24818193515421805,-0.7714608016019475,-1.188626610487833,-1.0242095656430728,-0.05937927646622959,-0.20660672259911195,0.2593491835395012,-0.0618153992271836,-0.23419312302573214,0.24606186054596524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.883333333333333,1.0,0.0,1.0,1.0,3.406216519877647,-0.006755603674772547,0.6030810123616867,0.9941083521800457,0.02378974812606947,0.050577499659231695,0.0928684474846174,-0.06712051943647127,0.01925550766802163,-0.01540756766992014,-0.013394219482032215,-0.025710282191578896,-0.07519655301680707,-0.48408633342481405,-0.23838145500343066,-0.4068386844883566,-0.07362240369984167,1.4437676118899407,-1.820755018031246,0.0899440098497653,-0.5218819121257146,0.5890016169713729,0.21645255760975216,-0.38673183817003554,0.571606445837308,0.07924830218171697,-0.2234871192473309,0.24795864556173552,-0.7772614700450714,-1.2961281818447157,-0.9316929791871775,-0.05967168979674975,-0.20550380902091936,0.2583956142138333,-0.06204056285915471,-0.23292880205429856,0.24493483490165557,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.891666666666666,1.0,0.0,1.0,1.0,3.405629785205523,-0.0066971880177557775,0.6030161184963174,0.9941440970959224,0.023728970544407525,0.05047308859309502,0.09255764416906072,-0.0661756131525894,0.0191901427718784,-0.015334446962960636,-0.013135504641405081,-0.025864036697875577,-0.07496166916114144,-0.4834270940255605,-0.24023482776292376,-0.4047784783811091,-0.08011950808864439,1.4325252786480964,-1.8281281648547876,0.08944603803957299,-0.5235873012177521,0.5911503069924965,0.21593511300217322,-0.38866463508587373,0.5736414497325121,0.07911488210758155,-0.2202145330677746,0.24528089177956902,-0.7810043681110443,-1.4001244824035908,-0.836694753234597,-0.059720313674948566,-0.20319744137142326,0.25715324476107915,-0.062028042785665094,-0.23024345859425255,0.2431457318474628,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9,1.0,0.0,1.0,1.0,3.4050532454030353,-0.0066375530026878135,0.6029509459819227,0.9941796475345412,0.023669345986026866,0.05036791931631439,0.09224783570610601,-0.06471141392227063,0.01901762982965891,-0.01519647896629708,-0.012901619774475574,-0.02610896919615798,-0.07467886069526207,-0.48276775205635436,-0.2420516972212269,-0.40275066962536377,-0.08663914316835908,1.420432203849881,-1.834699930585156,0.08894867128851616,-0.5252685361485716,0.5932875043840575,0.21541875689665774,-0.3905692291466064,0.5756588747014324,0.07927321505830864,-0.21477637390034998,0.2402418220176339,-0.7826577835241716,-1.500016582690722,-0.739524637879998,-0.05952999463660957,-0.1997371147915028,0.25565474941311894,-0.06178290688623744,-0.22619615711507612,0.24074272955360687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.908333333333333,1.0,0.0,1.0,1.0,3.404491236565867,-0.006576807168672857,0.6028855791069321,0.9942150090028653,0.02361080797969547,0.050261592074383826,0.0919392080788427,-0.06276017537183719,0.018744002147601024,-0.014995235426745426,-0.01269642360829086,-0.026447382054464178,-0.07435288310708192,-0.4821058737745887,-0.24381443399459626,-0.4007744480141485,-0.09316380448071392,1.4075250022699177,-1.8404535754861209,0.08845387146229616,-0.5269162531309438,0.5954112194827151,0.2149053978874026,-0.39243457103779167,0.5776538285584055,0.0797205954959479,-0.20729430604810084,0.2329823572577372,-0.7822095109230085,-1.5952527955301132,-0.6405223379530867,-0.059109959994675665,-0.19519439559890994,0.25393639501953613,-0.0613144242594621,-0.22087182246428694,0.23778442086858753,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.916666666666666,1.0,0.0,1.0,1.0,3.4039477783425656,-0.006515066294864249,0.6028201186791329,0.9942501895643485,0.023553274385017173,0.05015370117303521,0.09163192716350929,-0.06036392918464357,0.018377234741140287,-0.014733707243694154,-0.012523167725071886,-0.02687931874362177,-0.07398899148656346,-0.48143907546475523,-0.2455066023220286,-0.3988676303377348,-0.09967596835040922,1.3938446572577123,-1.845375302884374,0.0879635052886049,-0.5285217760752201,0.5975197776343831,0.2143968498256667,-0.39425042618767786,0.5796219483825755,0.08044769398935836,-0.19793241261440997,0.22369007047854494,-0.7796671697617533,-1.6853432887812092,-0.5400508694117834,-0.05847372979253335,-0.18966220669632383,0.2520369519815868,-0.06063598387988145,-0.21438042416143221,0.2343384879809718,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.925,1.0,0.0,1.0,1.0,3.403426492049705,-0.006452451382204274,0.6027546784387907,0.9942851994157307,0.023496649054962647,0.05004384517646306,0.09132613681761359,-0.05757383901692117,0.01792707148616402,-0.014416305929078327,-0.01238443383076466,-0.027402356352223083,-0.07359290380832584,-0.48076507887476605,-0.24711330753816976,-0.39704628017283944,-0.10615825731007647,1.3794359474568976,-1.8494544233096506,0.08747930929908727,-0.5300772899092159,0.5996118353490749,0.21389479815607124,-0.39600757810714887,0.581559470024755,0.0814386489698582,-0.18689492249603645,0.21259620637557264,-0.7750579859515558,-1.7698728320048307,-0.4384889069920428,-0.05763886345039049,-0.18325332205370026,0.24999655757697914,-0.05976485631840889,-0.20685522965184444,0.23048007176193153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.933333333333334,1.0,0.0,1.0,1.0,3.4029305258839355,-0.006389086844545155,0.6026893809045956,0.994320050413835,0.02344082366163647,0.04993163776026784,0.09102195714085906,-0.0544492054573228,0.017404783112872364,-0.014048802867080927,-0.012282100706132656,-0.02801150983068031,-0.07317075552567659,-0.4800817646485909,-0.24862151769696253,-0.39532436023147527,-0.11259360144960182,1.3643467767242985,-1.8526834513342414,0.08700285756443173,-0.5315759981094484,0.6016863869273328,0.21340076888702655,-0.39769801334854193,0.583463282911941,0.08267145228186279,-0.17442232775864708,0.19997091405454248,-0.7684280419189874,-1.8485109494663332,-0.33622247961690555,-0.05662654989649324,-0.17609812029927285,0.24785559914101585,-0.058721806311488045,-0.19845018187964913,0.2262899194858803,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.941666666666666,1.0,0.0,1.0,1.0,3.4024624901022076,-0.0063250989808479804,0.6026243528720341,0.9943547555780783,0.023385679606586586,0.04981671871460763,0.09071948294167671,-0.05105616261774976,0.016822867748951573,-0.01363820793613618,-0.012217341376205861,-0.028699257430069413,-0.07272904471884328,-0.479387221336735,-0.2500203463341472,-0.39371343160526373,-0.11896539134205959,1.3486274316324587,-1.8550581313032657,0.08653553346747905,-0.5330122585808704,0.6037427620014252,0.2129161013842131,-0.39931508113847636,0.5853309686828531,0.0841186108642511,-0.16078603898594446,0.18611688289476236,-0.7598410291963104,-1.9210189086991614,-0.23363642191351008,-0.055461060337768375,-0.1683416936028137,0.24565367950933448,-0.05753057380445015,-0.18933651147522434,0.2218524052926929,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.95,1.0,0.0,1.0,1.0,3.402024404601652,-0.006260614775594836,0.6025597208001002,0.9943893285949625,0.023331089940590855,0.04969876457302785,0.09041878244407535,-0.047466125536765866,0.016194709180367618,-0.013192593438069646,-0.01219064876281207,-0.029455687438211014,-0.07227456747580392,-0.4786797878008534,-0.25130128501339494,-0.39222241218322923,-0.12525761860287365,1.3323297949126458,-1.8565773916994666,0.08607850655880225,-0.5343816930028287,0.605780614919155,0.21244192599028572,-0.400853621873129,0.5871608230001526,0.08574804716857898,-0.1462818204453109,0.17136167529520074,-0.7493765645270037,-1.987253183458999,-0.13110600801996775,-0.05416909153635768,-0.16014044569871988,0.2434287158057824,-0.05621724943240092,-0.1796987392133198,0.2172535194193137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.958333333333334,1.0,0.0,1.0,1.0,3.401617660749459,-0.006195761047334698,0.6024956063188858,0.9944237833492857,0.02327692122685503,0.04957749836313705,0.09011989626972651,-0.04375406103458987,0.015534210118835396,-0.012720873093525473,-0.012201886072264294,-0.030268757010364505,-0.07181434376852426,-0.4779580872172587,-0.2524583766749024,-0.39085740368367705,-0.131455000750843,1.3155065452414754,-1.8572432314369318,0.08563271527520643,-0.5356812660091824,0.6077999072648549,0.21197914722700642,-0.402310060125365,0.588951860673175,0.08752418475138857,-0.13122232066491657,0.15604912913857016,-0.7371281523355389,-2.047165270424367,-0.028989175859366334,-0.05277903365500186,-0.1516583386552739,0.24121620671852195,-0.054809576409616256,-0.16973025602777914,0.2125789153248414,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.966666666666667,1.0,0.0,1.0,1.0,3.401242998641165,-0.006130663938110869,0.6024321220688216,0.9944581335034117,0.023223035294648718,0.04945269803397242,0.08982283672821835,-0.03999666194968214,0.014855418404803464,-0.012232548710489352,-0.012250356637330664,-0.03112464571063284,-0.07135553475424694,-0.47722105138833026,-0.25348832369114355,-0.38962159336425306,-0.13754308780846597,1.2982103737389064,-1.857060544630456,0.08519885599788556,-0.5369093319804166,0.6098008850311304,0.21152843305012545,-0.403682459473592,0.5907038049222333,0.0894091545040776,-0.11592906075228782,0.14053025062112923,-0.7232008914617377,-2.1007979847874703,0.07238030106757609,-0.051320199892997964,-0.143062960079674,0.23904868511652522,-0.053336213958228296,-0.15962868344632786,0.2079120899024689,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.975,1.0,0.0,1.0,1.0,3.4009005002591257,-0.006065448711961829,0.6023693680455803,0.9944923921410956,0.023169290845896796,0.04932420320461199,0.08952758744400006,-0.03627050559146923,0.014172163284139845,-0.011737438758626234,-0.012334887020855775,-0.03200818019548771,-0.07090535309998038,-0.4764679346421907,-0.2543905276874405,-0.38851523283999156,-0.14350834894187195,1.2804932454950175,-1.8560368930858056,0.08477737861032313,-0.538065648677177,0.611784052016797,0.21109021032770262,-0.4049705381828038,0.5924170621715494,0.09136405210301346,-0.10072425947369346,0.12515403162367877,-0.7077090313430834,-2.1482785853832187,0.1726984148962174,-0.04982205513683585,-0.13452158085796917,0.23695535467563644,-0.0518259975916191,-0.1495912166612745,0.20333275339037948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.983333333333333,1.0,0.0,1.0,1.0,3.400589598315986,-0.006000239810856447,0.6023074285777962,0.9945265714866425,0.023115544893336813,0.04919191998925955,0.08923410334178558,-0.03265027229361673,0.013497716890424179,-0.011245403404347012,-0.01245391694303714,-0.032903302829179394,-0.07047096851764145,-0.4756983171866134,-0.25516706134903844,-0.38753569283719175,-0.1493382383308507,1.262405730649186,-1.854182237715519,0.08436848841227162,-0.5391513583280494,0.613750140942391,0.21066466642359846,-0.40617564641794657,0.5940926841454063,0.09335017854489425,-0.08592286141592353,0.11025860615660354,-0.6907734823083816,-2.189809263551803,0.2716951127452738,-0.048313477978423336,-0.12619735991752812,0.2349618933658193,-0.050307229018868305,-0.1398101373203431,0.19891542510986682,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.991666666666667,1.0,0.0,1.0,1.0,3.4003090999476084,-0.005935161102739117,0.6022463700133682,0.9945606827041888,0.023061654023869917,0.04905582377414314,0.08894231100343752,-0.029207090269512397,0.012844493173268384,-0.010766079667837413,-0.012605589966846948,-0.03379355608981506,-0.07005941113689355,-0.47491209833310916,-0.2558225753777059,-0.38667758940404817,-0.1550212403136783,1.2439964244358208,-1.8515086412067177,0.0839721539773494,-0.5401689380091358,0.615700083572894,0.21025175651072148,-0.40730070713814287,0.5957323192567139,0.09533020237614487,-0.07182509641055046,0.09616311232028996,-0.6725193771324561,-2.2256556565938324,0.36913699034386127,-0.04682208529156073,-0.11824582963744668,0.23309039489768146,-0.04880702369129852,-0.13046865668806307,0.19472827138758086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0,1.0,0.0,1.0,1.0,3.400057223901076,-0.0058703362494261805,0.6021862391395653,0.994594735776231,0.023007475493372016,0.04891595993969168,0.08865210939923734,-0.02600706003361339,0.012223793122437904,-0.010308638474338314,-0.012787839740609389,-0.03466255621356917,-0.06967747558267838,-0.4741094804803443,-0.2563641462892143,-0.38593297429852025,-0.16054689461639163,1.2253114697059555,-1.8480299545431214,0.08358812032407895,-0.5411221221553402,0.6176349808573524,0.2098512160287435,-0.4083501240294143,0.5973381553351993,0.09726919315177218,-0.05870984100254106,0.08316055686912405,-0.6530737679504511,-2.2561341096836296,0.4648285033406152,-0.045373641885794735,-0.11081176683490623,0.23135941246437808,-0.0473507377960497,-0.12173721604727183,0.19083218506630972,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.008333333333333,1.0,0.0,1.0,1.0,3.3998316494674072,-0.005805889121718902,0.6021270623170413,0.9946287394556377,0.022952868168674395,0.04877244262775179,0.08836337098571699,-0.02310999704644212,0.011645601628193319,-0.009881572800210093,-0.01299846778322762,-0.035494433150460275,-0.06933162864304854,-0.47329094511391295,-0.25680107272774827,-0.3852915801228961,-0.1659058031128525,1.206394189274427,-1.843761499484374,0.08321592661258616,-0.5420158007897176,0.6195560737806336,0.20946257754745398,-0.40932966073893073,0.5989128556744857,0.09913548915868486,-0.04682898353847609,0.07151189737028107,-0.6325635258694084,-2.2815984108084075,0.5586117947311608,-0.0439915704130725,-0.10402652321292116,0.22978406749869507,-0.04596148960123003,-0.11377033422714788,0.18728009326477446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.016666666666666,1.0,0.0,1.0,1.0,3.399629575142842,-0.005741944194426462,0.6020688452713824,0.9946627012816105,0.022897693338372202,0.048625451740763624,0.08807594315171441,-0.020568416437355602,0.01111843801621928,-0.009492523199031986,-0.013235210122974753,-0.03627421891639169,-0.06902792321511844,-0.47245722232769954,-0.2571446293481889,-0.3847411093423489,-0.17108962004754844,1.1872848295258154,-1.8387197579642687,0.08285492748386107,-0.5428558975422222,0.6214647153156639,0.20908519120205632,-0.4102462962665334,0.6004594902229455,0.10090137684698464,-0.03640292095206887,0.06144147067020378,-0.6111134920603623,-2.3024266698910445,0.6503653037817392,-0.04269656945099093,-0.09800585877805856,0.22837618910216406,-0.044659783198947034,-0.10670405563315888,0.18411647205550663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.025,1.0,0.0,1.0,1.0,3.3994477848627858,-0.005678626863695692,0.6020115734597733,0.994696627647544,0.02284181541674784,0.04847522842353968,0.08778964998478184,-0.018426769865298467,0.010649259441978911,-0.009148144055675768,-0.013495791398966419,-0.036988172111555286,-0.0687719208354843,-0.47160925549979654,-0.2574077880769494,-0.38426755561172604,-0.1760910279805252,1.1680204114429096,-1.8329220777546784,0.08250431712173631,-0.5436492317693519,0.623362343599003,0.20871824782747153,-0.41110806166615005,0.6019814635420775,0.10254357324967711,-0.027617244201600943,0.05313381350863122,-0.5888449105285282,-2.319008918563452,0.7400013676748651,-0.0415063411470587,-0.09284829440748155,0.2271444562422431,-0.04346323646638783,-0.10065401898924464,0.18137704329743043,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.033333333333333,1.0,0.0,1.0,1.0,3.39928271962519,-0.005616063641581608,0.6019552129150766,0.9947305239074877,0.02278510256492094,0.04832206931728931,0.087504294322155,-0.01672093265046319,0.010243414068118548,-0.008854011223499892,-0.01377796617855297,-0.03762403207540528,-0.06856862458790935,-0.47074816277353826,-0.2576049167515489,-0.3838555457838717,-0.18090370188969057,1.1486346808830912,-1.8263864018363543,0.08216315513141009,-0.5444033691156802,0.6252504562530347,0.20836080392761652,-0.4119238632496875,0.6034824409445694,0.10404351478874418,-0.020620605833527872,0.04673184764015126,-0.5658741555591329,-2.331735886081807,0.8274630515750259,-0.040435424396705055,-0.08863397695911379,0.22609452341361136,-0.04238640987683284,-0.09571413913224247,0.17908862925508195,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.041666666666666,1.0,0.0,1.0,1.0,3.3991305523861644,-0.005554382196614401,0.601899711464265,0.9947643945078023,0.02272742725106578,0.04816631989107926,0.08721966004458824,-0.015477929736904544,0.009904639331108397,-0.00861456943580744,-0.014079548152930822,-0.03817120133005066,-0.06842242359812911,-0.46987519691998414,-0.25775146484084155,-0.3834886914843902,-0.18552226390651075,1.1291581466748795,-1.8191310268950946,0.08183039338179122,-0.5451264647186704,0.6271305856558965,0.20801180766285765,-0.4127032973183541,0.6049662740296622,0.1053874655425191,-0.015523710780560585,0.0423363417046696,-0.5423117520178111,-2.340989274582488,0.9127204478223927,-0.03949512545217526,-0.08542403275681787,0.22522911983488658,-0.041440728847724206,-0.09195587253483462,0.17726914376805292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.05,1.0,0.0,1.0,1.0,3.3989872642480616,-0.005493711222863417,0.6018450002210617,0.9947982431314173,0.02266866676794646,0.048008367151207744,0.08693551456765687,-0.014715881991074339,0.009635099604997498,-0.008433116153668662,-0.014398428515318968,-0.03862085925779826,-0.06833704973629118,-0.4689917050144963,-0.25786364526455824,-0.3831499400887939,-0.18994223108998742,1.109618192973383,-1.8111743943726477,0.0815049030405405,-0.5458271029949605,0.6290042749169494,0.20767012511348779,-0.41345646112526807,0.6064369266740369,0.10656646497160471,-0.01239933201832466,0.04000651735215688,-0.5182616748045726,-2.3471337263196856,0.9957666738858872,-0.03869353514407231,-0.08326037296155553,0.22454812121256662,-0.04063448965221872,-0.08942802189747523,0.1759277034134099,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.058333333333334,1.0,0.0,1.0,1.0,3.3988487201472353,-0.00543418013261184,0.6017909952617138,0.9948320728436022,0.022608703721803375,0.047848632008364866,0.08665161148356175,-0.01444414970122103,0.009435457113013076,-0.00831181734504018,-0.014732585207809281,-0.03896601317040948,-0.06831554660977267,-0.4680990891704574,-0.2579581203744803,-0.3828219161951876,-0.19415995848658696,1.090039251236218,-1.8025349156636632,0.08118550112939002,-0.546514137601363,0.6308730543427726,0.207334566168654,-0.4141937643499787,0.6078984024198857,0.10757613930943544,-0.01128322633589307,0.039761638040954894,-0.4938209049676229,-2.3505105567794216,1.0766137757045824,-0.03803562042996478,-0.0821659067452063,0.22404860068383936,-0.039972937439956,-0.08815702560500238,0.17506484721258708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.066666666666666,1.0,0.0,1.0,1.0,3.3987107424650733,-0.0053759185785266774,0.6017375994058318,0.9948658862300831,0.022547426502356912,0.04768756155075615,0.0863676933067816,-0.014663647632033577,0.009304969912722564,-0.00825175005249014,-0.015080084878796269,-0.0392014950182344,-0.06836025048342959,-0.467198769359339,-0.2580516990368231,-0.38248724612144464,-0.19817257950611447,1.0704430170270594,-1.793230831444238,0.08087097603337443,-0.5471965347740473,0.6327384182616801,0.20700390948948852,-0.41492574488535144,0.60935467412758,0.1084164026264578,-0.012175811222329136,0.041583404342048214,-0.46907921414030884,-2.3514332273176475,1.1552887123736078,-0.0375233775563491,-0.08214511450340467,0.22372487114377781,-0.03945840442774906,-0.08814767317302019,0.1746728580624346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.075,1.0,0.0,1.0,1.0,3.3985691812149406,-0.005319055819784859,0.6016847040390942,0.994899685520459,0.022484729739766295,0.04752562143325405,0.08608349427872504,-0.015367305214746902,0.009241611068178912,-0.008252966424336237,-0.01543907937341469,-0.03932391303638146,-0.06847278243650608,-0.4662921491266831,-0.2581610505615191,-0.38212885945615344,-0.20197794538892544,1.0508486974475906,-1.7832801037907697,0.08056011150345087,-0.5478832228430864,0.6346018021951689,0.2066769260948582,-0.4156628922361957,0.6108096167209263,0.10909107342656821,-0.015044459986770509,0.04541897744720469,-0.4441191457112148,-2.3501844525928073,1.2318295636814858,-0.03715603448155552,-0.0831849326240719,0.2235685344758931,-0.03909049659901853,-0.08938418687790439,0.17473618254929546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.083333333333334,1.0,0.0,1.0,1.0,3.3984199796860977,-0.005263719952930475,0.6016321909296073,0.9949334726920022,0.022420514751018923,0.04736328855221915,0.08579874318936985,-0.016540645988854706,0.009242203610561243,-0.008314574059627232,-0.01580779843764933,-0.039331567796428796,-0.06865405086152807,-0.46538058480222955,-0.25830244003660263,-0.3817302631639912,-0.20557456526796805,1.0312732761505126,-1.7727003387162132,0.08025170879201517,-0.5485829503177818,0.636464560502945,0.2063524012128382,-0.4164154813333165,0.612266943836735,0.10960743105831727,-0.01982627646326507,0.051184460266312515,-0.4190161600100356,-2.347014782135597,1.306282067009259,-0.03693029110769408,-0.0852559026271793,0.22356855422859256,-0.038866318052825366,-0.09183161143642038,0.1752319477738684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.091666666666667,1.0,0.0,1.0,1.0,3.398259234644166,-0.005210037032446,0.6015799340035132,0.9949672495509114,0.02235468997551821,0.04720104413617682,0.08551316617729521,-0.01816246183118501,0.009302566477983665,-0.008434827946745865,-0.016184540103199935,-0.039224341628739404,-0.06890426332106966,-0.4644653586090445,-0.25849148850257353,-0.38127578511838156,-0.20896154805575937,1.0117317844119973,-1.761508736007282,0.07994460665165597,-0.5493041545535394,0.6383279447656455,0.2060291541273111,-0.41719341909346935,0.6137301491838241,0.10997573372211411,-0.02643122070089765,0.058768680257855754,-0.39383891129415705,-2.3421424603968544,1.378696556962411,-0.036840587073992126,-0.08831353994964042,0.22371136723091656,-0.03878072325071591,-0.0954374568380667,0.17613057415315714,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1,1.0,0.0,1.0,1.0,3.398083250390478,-0.005158130108415427,0.6015278010571714,0.9950010177898547,0.022287171397560812,0.04703936734643142,0.08522648947310936,-0.020205559445038254,0.009417667239891746,-0.00861122985969845,-0.01656765997552275,-0.0390035694164356,-0.06922294678265221,-0.463547655906861,-0.2587429603816176,-0.3807507851596936,-0.21213854712287067,0.9922375684772317,-1.7497220627668397,0.07963769900744863,-0.5500548426502758,0.6401930832901269,0.20570605582532628,-0.41800610561395096,0.6152024534059543,0.11020871687749567,-0.034745470681474266,0.06803713731158845,-0.36864962598197715,-2.3357543526659152,1.4491253514292834,-0.036879388186066286,-0.09229988059340055,0.22398104688012843,-0.03882658863939126,-0.10013354335683511,0.17739648195639335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.108333333333333,1.0,0.0,1.0,1.0,3.3978885861667227,-0.005108118209590573,0.601475655392457,0.995034779022107,0.0222178829518747,0.04687872945041761,0.08493844205474906,-0.022637558724198127,0.009581777996302792,-0.008840631729563632,-0.016955560401545545,-0.03867189753672791,-0.06960897532036041,-0.4626285466610862,-0.2590705796805981,-0.3801418328298551,-0.21510570848879232,0.9728025452008987,-1.737356646816794,0.0793299501818882,-0.5508424858967628,0.6420609622136476,0.20538204431665458,-0.41886231148274994,0.6166867572164306,0.11032108775260063,-0.044634920420434376,0.078836001248479,-0.34350455399596747,-2.328007721812926,1.5176206024211591,-0.03703748385059186,-0.09714516676134766,0.22435952680787352,-0.03899509634194942,-0.10583800174249647,0.17898888683916203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.116666666666667,1.0,0.0,1.0,1.0,3.3976720965562617,-0.0050601152999975255,0.6014233573682974,0.9950685347937641,0.022146756907318422,0.046719588604834335,0.08464875818629361,-0.02542172472535241,0.00978863136383993,-0.009119340163645824,-0.017346680265321997,-0.038233136407590324,-0.0700606044745835,-0.4617089711109843,-0.25948687572195817,-0.3794368518055523,-0.21786362302280346,0.9534374397803496,-1.7244283860598204,0.07902040760993877,-0.551673928762965,0.6439324087369248,0.20505613755296045,-0.41977007230965924,0.6181856015199403,0.11032902868297056,-0.05594873026732117,0.09099606491870915,-0.31845446792078624,-2.319032649191808,1.584232609339562,-0.037304289058431306,-0.1027696351660401,0.2248268888341931,-0.03927602371234573,-0.11245738517577819,0.1808626762098675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.125,1.0,0.0,1.0,1.0,3.397430964680336,-0.005014229236247878,0.6013707658656737,0.9951022865763862,0.02207373422312647,0.04656238526543146,0.08435717981471942,-0.028517816927391654,0.01003157390395737,-0.009443219891497042,-0.01773948595997156,-0.037692110819341415,-0.07057551156917025,-0.46078972951637004,-0.2600030585183868,-0.3786252317478766,-0.22041328295413876,0.9341520010477019,-1.710952769994468,0.07870821203091434,-0.5525553131495301,0.6458080770275508,0.20472744392144882,-0.4207366012356796,0.6197011351532618,0.11024971932588223,-0.06852285970468164,0.10433657903999083,-0.2935451877079781,-2.308934908814597,1.6490085760986828,-0.03766814545736852,-0.10908537374134442,0.2253617140043973,-0.03965803348816632,-0.11988885253954806,0.1829693543003752,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.133333333333333,1.0,0.0,1.0,1.0,3.3971627281182877,-0.004970560751200041,0.6013177396652857,0.9951360357430171,0.021998764871634154,0.046407538225324986,0.08406345880145184,-0.03188294113706305,0.01030371471161599,-0.009807794445222114,-0.018132463914951037,-0.037054511084511785,-0.07115084137500118,-0.45987147578888626,-0.26062892338370286,-0.37769790882155246,-0.22275604281793643,0.9149551913001063,-1.696944909791509,0.07839260518564929,-0.5534920183253207,0.6476884373036648,0.20439517032815768,-0.42176821985198504,0.6212350907582799,0.11010088548425778,-0.08218352573107324,0.11866891284243342,-0.26881811169870984,-2.297799124150819,1.7119917814001973,-0.03811661686287049,-0.11599821401392152,0.2259414905204138,-0.040128960032949634,-0.1280223848653006,0.18525803975275812,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.141666666666666,1.0,0.0,1.0,1.0,3.3968652975983673,-0.004929202487719445,0.6012641387373641,0.9951697835308756,0.021921808121189663,0.046255441273179,0.08376735896775994,-0.03547239079945985,0.010598067174549444,-0.010208342814318337,-0.018524114918100246,-0.03632674708297063,-0.07178325656378629,-0.4589547147582991,-0.261372783947238,-0.37664741653383604,-0.22489358481578392,0.8958553489785216,-1.682419573637798,0.07807293508319983,-0.5544886167164288,0.6495737685362244,0.20405862792089965,-0.42287030765010125,0.622788769149141,0.109900380356317,-0.09675054064586575,0.13379999974509116,-0.24431073768456324,-2.2856920592808905,1.7732211228641104,-0.03863677518050723,-0.12340962748554452,0.22654306788033374,-0.04067608773912046,-0.13674299853667415,0.18767649576567846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.15,1.0,0.0,1.0,1.0,3.396536968612196,-0.004890238104130118,0.601209825442233,0.9952035309941458,0.021842832772920553,0.04610646045563453,0.08346865793513587,-0.039240465612541554,0.010907682149265706,-0.010639991150461388,-0.018912950357882593,-0.035515806537271696,-0.07246899240779478,-0.45803980278294765,-0.2622414323944673,-0.37546790882580094,-0.22682788844601248,0.8768603236454248,-1.6673912244104405,0.07774865893264084,-0.5555488454500798,0.6514641551016703,0.20371723553250567,-0.4240472698275963,0.6243630323543745,0.1096658024773356,-0.11204049167475083,0.14953553950000642,-0.22005716052827806,-2.2726659189187237,1.8327309900673017,-0.0392154731859537,-0.13121859521941115,0.2271431428359061,-0.04128641809680533,-0.1459329201784132,0.19017216973994389,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.158333333333333,1.0,0.0,1.0,1.0,3.396176426203535,-0.004853741470586354,0.6011546656386498,0.9952372789502529,0.021761817345178448,0.04596093192405972,0.08316714874398458,-0.04314125628985883,0.011225770999500648,-0.011097798842950153,-0.019297490417325917,-0.034629118327863084,-0.07320391514886689,-0.4571269513836768,-0.2632401254751505,-0.37415515754216927,-0.2285612041579219,0.8579775836632095,-1.6518740571366763,0.07741934386343394,-0.556675593303419,0.6533594875834895,0.20337052095261957,-0.42530252298640814,0.6259583053114735,0.1094141533867099,-0.12786973154784054,0.16568293759769537,-0.1960885354951053,-2.258761553852231,1.8905514182714223,-0.03983960097110911,-0.139323420635884,0.2277187600895214,-0.0419469222569363,-0.1554736893655051,0.19269321721408383,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.166666666666666,1.0,0.0,1.0,1.0,3.3957827432721004,-0.004819775973046231,0.6010985296951521,0.9952710279228236,0.02167875019984206,0.04581916034315159,0.08286264123637224,-0.047129385143325465,0.011545817124418052,-0.011576838451826325,-0.019676264173817164,-0.033674421330077225,-0.07398358339056707,-0.4562162335598358,-0.2643725945869313,-0.372706526532506,-0.23009603070426424,0.8392142977478876,-1.6358820341059168,0.07708466558312235,-0.5578709024606778,0.655259467769829,0.20301812016155674,-0.426638497983688,0.6275745859746092,0.10916153707308918,-0.14405715421419885,0.1820539695666057,-0.17243349889961124,-2.244011488933424,1.946708473249159,-0.04049632316007634,-0.1476234565271617,0.22824780910017495,-0.0426447761762494,-0.16524815662880776,0.19518948389601887,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.175,1.0,0.0,1.0,1.0,3.3953553728164323,-0.004788393938804923,0.6010412933980012,0.9953047780842362,0.02159362960523413,0.04568141783737054,0.08255496319137358,-0.05116069296500333,0.011861674786620941,-0.012072269092891642,-0.020047811492766732,-0.03265963909582189,-0.07480331177010849,-0.45530759243245866,-0.26564107804538717,-0.3711209247160592,-0.23143509580624874,0.8205773921809858,-1.619428915915857,0.07674440514409933,-0.5591359842455383,0.6571636177351591,0.2026597746830154,-0.4280566589302216,0.6292114633764071,0.10892290245544944,-0.1604267337359,0.19846716253163366,-0.14911853996400826,-2.228442709537717,2.001224817747018,-0.0411732942754775,-0.15602071873143997,0.22870949803208696,-0.04336757567306615,-0.17514234598696166,0.19761341992099668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.183333333333334,1.0,0.0,1.0,1.0,3.3948941346160426,-0.0047596361946421134,0.6009828387481186,0.9953385292002911,0.021506463731222617,0.04554794344998986,0.08224396120479228,-0.055192863557624754,0.012167654247816562,-0.012579402934306178,-0.02041068654689571,-0.03159276067398403,-0.07565823605840567,-0.454400851852245,-0.26704637348252963,-0.3693987404903121,-0.23258133970366437,0.802073585922259,-1.6025282871434665,0.0763984440118644,-0.5604712477728685,0.6590712927370305,0.2022953272336723,-0.4295575370834707,0.6308681429732925,0.10871182948438807,-0.17680980753852715,0.21474988957259744,-0.12616831991564492,-2.212079159303182,2.0541204114497047,-0.041858849931185604,-0.1644213609311218,0.2290847867119794,-0.04410352898202741,-0.18504715359082824,0.19992090210547708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.191666666666666,1.0,0.0,1.0,1.0,3.3943991969214373,-0.00473353176557142,0.6009230546388786,0.9953722805791061,0.021417270573124075,0.045418943088251534,0.08192950130870619,-0.05918597827347139,0.012458592443035436,-0.013093764506405047,-0.02076346274420398,-0.030481727923828375,-0.07654337873099942,-0.45349572860771886,-0.2685879081710293,-0.3675417598898492,-0.23353790113817616,0.7837094061925994,-1.5851935757250286,0.07604675764524624,-0.561876340261057,0.6609816975136921,0.20192471586664829,-0.4311407781567354,0.6325434784114984,0.108540358845014,-0.19304708800477077,0.23074017453599382,-0.1036059363342351,-2.19494391701317,2.10541329862302,-0.04254217187391579,-0.17273698778641267,0.22935676237377134,-0.044841624709556216,-0.19485985721192756,0.20207194287861885,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2,1.0,0.0,1.0,1.0,3.3938710537796277,-0.00471009771897531,0.6008618374068498,0.9954060310258841,0.021326077802310685,0.04529458992643477,0.08161146933037416,-0.06310356933651722,0.012730029798972975,-0.013611134594545887,-0.021104686736086467,-0.029334429856898193,-0.07745364945209005,-0.45259184587149476,-0.2702638249492758,-0.36555307091471223,-0.23430810530923496,0.7654911873053728,-1.5674380654997495,0.0756894078139658,-0.5633501975693087,0.66289390544326,0.20154796682184636,-0.4328052013703362,0.6342360086879362,0.10841855948558576,-0.20899220420624975,0.2462901918494198,-0.08145375780377218,-2.177063258044609,2.1551215423862313,-0.0432136877840561,-0.1808872098121106,0.22951184469448993,-0.045572018502784695,-0.20448704375865434,0.2040327073222481,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.208333333333334,1.0,0.0,1.0,1.0,3.3933104889392247,-0.00468933874644768,0.6007990923124551,0.9954397788076245,0.021232923067306602,0.0451750244310107,0.08128977149374729,-0.0669110174959044,0.012977804928112666,-0.014127712037173511,-0.021433100444385483,-0.02815809990815816,-0.07838424263770254,-0.45168875261629243,-0.2720711115744668,-0.36343692335902555,-0.23489546376823903,0.7474250185585226,-1.5492748833519248,0.07532652951551197,-0.5648911270912589,0.6648068949252669,0.2011651822249352,-0.434548895552713,0.6359440235335359,0.1083555433281036,-0.22450747983551622,0.2612614626175014,-0.05973123661602353,-2.158459638012813,2.203259282158321,-0.043864188490926326,-0.18879547157628185,0.22953623427458547,-0.04628521529468854,-0.21383983247509675,0.20577007323180574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.216666666666667,1.0,0.0,1.0,1.0,3.392718580254437,-0.004671249069153807,0.6007347286032789,0.9954735216133593,0.021137851445263423,0.04506035968103593,0.08096433166359943,-0.070577288604893,0.013198482016861416,-0.014639761706216633,-0.021747400362060736,-0.026960094201550072,-0.0793300496533954,-0.4507859201493597,-0.27400561627986775,-0.36119871320442054,-0.23530362591950202,0.7295168600051593,-1.5307170774637775,0.07495833800578369,-0.5664967887622467,0.6667195093478364,0.2007765465669349,-0.43636919857825446,0.6376655099084663,0.10835846344389943,-0.23946705829867354,0.275527463886005,-0.03845711526899276,-2.139161836472274,2.2498444113364258,-0.04448585996711718,-0.1963939690314631,0.22942086420219665,-0.046973071606216665,-0.22283949744190124,0.20725900249452867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.225,1.0,0.0,1.0,1.0,3.3920966345612933,-0.004655809872712028,0.6006686695736482,0.9955072565085493,0.021040918487310448,0.044950675002007265,0.08063509660746733,-0.07407748763301865,0.013389718953592623,-0.015144069985040556,-0.022046127432984154,-0.02574749188325865,-0.08028618217240786,-0.4498827782255608,-0.276062229212778,-0.35884479896092547,-0.2355364156893889,0.7117723212839847,-1.5117774764963177,0.07458509851606002,-0.5681643599084499,0.6686305759953035,0.20038229769816493,-0.43826288717674466,0.639398340241778,0.10843165185552728,-0.2537677371875191,0.2889854913710266,-0.01765173560495714,-2.119209477098647,2.2948978948564402,-0.04507306811218581,-0.20362908462637552,0.22916198444037583,-0.04762950395119425,-0.23142373269980587,0.20848417088046522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.233333333333333,1.0,0.0,1.0,1.0,3.3914461485664686,-0.004642991674537372,0.6006008438765734,0.9955409800555306,0.02094218813164685,0.044846024769476536,0.08030202892024432,-0.07738941027703318,0.013549518394515254,-0.01563805991794168,-0.022328110418624005,-0.024526261936530513,-0.08124823746304095,-0.4489787259517676,-0.2782350785663264,-0.35638228834823676,-0.23559782151291797,0.6941967020535151,-1.4924687792161702,0.07420712020391393,-0.569890606839353,0.670538875755176,0.19998272150108165,-0.4402262607899179,0.6411402460898074,0.10857828683139892,-0.2673192405673619,0.3015465626032865,0.002667644453527296,-2.09864122186991,2.3384386150905767,-0.04562064366685159,-0.21045286195779056,0.22875520849317654,-0.04824889341247973,-0.23953680182369874,0.20943070417632104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.241666666666667,1.0,0.0,1.0,1.0,3.3907688020238935,-0.004632754392955883,0.6005311879580489,0.9955746880954218,0.020841731398633465,0.04474643869728478,0.07996511039147483,-0.08049399064323697,0.013676414109523272,-0.016119267809905406,-0.022592254080285243,-0.023302128867860514,-0.08221170641270886,-0.4480731401117041,-0.2805175498889007,-0.35381902291753736,-0.23549195494849678,0.6767949675861529,-1.4728034995781414,0.07382475445494582,-0.5716719076077464,0.6724431628035231,0.1995781494746236,-0.44225516720713964,0.64288885197805,0.10880010607826618,-0.28004206616198957,0.3131320307348173,0.02248550051224707,-2.07750066386563,2.38048994528937,-0.04612445762057188,-0.2168248529230743,0.22819935237392341,-0.04882667396380769,-0.24713168306760958,0.21008958316470316,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.25,1.0,0.0,1.0,1.0,3.3900664116103365,-0.004625048054981244,0.6004596467354927,0.9956083758912728,0.020739626884253813,0.04465192350366332,0.07962433961589269,-0.08337682902276897,0.013769665672936419,-0.01658569039418033,-0.022837433342079536,-0.022080267576421998,-0.08317249299492538,-0.44716539085046314,-0.2829024463356929,-0.35116342116932314,-0.2352230631710472,0.659571690989088,-1.4527939467946807,0.07343837924357106,-0.5735043543880709,0.6743421982947414,0.19916894360168486,-0.44434512217437805,0.6446417391425524,0.10909705160562333,-0.29187405163419444,0.32368058410771505,0.04178630645306436,-2.055837473548423,2.4210780542236776,-0.046581888255846915,-0.2227152246708508,0.22749638515408233,-0.04935974596032067,-0.2541736834381969,0.2104579772564552,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.258333333333333,1.0,0.0,1.0,1.0,3.389340898022033,-0.004619813398590187,0.6003861725104276,0.9956420381009342,0.020635959937407897,0.04456246589442595,0.07927973106089353,-0.08602737298957548,0.013829103984973938,-0.017035770137042737,-0.023062623445496564,-0.020865160157059637,-0.08412678327448886,-0.44625485591827707,-0.2853821174161373,-0.3484243465157421,-0.23479551650761238,0.6425310096936792,-1.4324521986744134,0.07304838965068171,-0.5753838280189273,0.6762347692227578,0.1987554870419516,-0.4464913952644429,0.6463964849323243,0.10946748586449728,-0.30276812016712173,0.33314620441960097,0.06055588089873165,-2.033706278108953,2.4602324609622084,-0.04699144114300918,-0.22810293685775251,0.22665044825094904,-0.04984612466990335,-0.2606382675027419,0.21053766715798616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.266666666666666,1.0,0.0,1.0,1.0,3.388594253698767,-0.004616982707137955,0.6003107244911259,0.9956756687889502,0.020530822034210035,0.04447803530581477,0.07893131383431494,-0.08843879121024936,0.01385508367751572,-0.01746834814631311,-0.023266879004748504,-0.019660617003683427,-0.08507109161598733,-0.4453409327527215,-0.2879485816718116,-0.34561098442899646,-0.23421379848940166,0.6256765863539387,-1.4117900724453105,0.07265518855785424,-0.5773060700023668,0.6781197057655906,0.19833817485718647,-0.44868909329942375,0.6481507002618522,0.10990838729052266,-0.3126915848760292,0.34149724830135675,0.07878127058315587,-2.011166138847178,2.497986257917746,-0.0473527016533673,-0.23297535550487636,0.22566762556601283,-0.050284904843616585,-0.2665106390200189,0.21033469493120016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.275,1.0,0.0,1.0,1.0,3.3878285121860316,-0.004616480681941144,0.600233268187378,0.9957092614433429,0.020424310134871476,0.04439858673592074,0.07857913035482145,-0.0906077555240755,0.013848431517767315,-0.017882652499580737,-0.023449335800381128,-0.018469761106634876,-0.08600228024799181,-0.444423049463435,-0.29059364383073777,-0.3427327257107195,-0.23348249533122645,0.6090115740462262,-1.3908190943757843,0.07225917795645892,-0.5792667506106752,0.6799958963155247,0.19791740529455798,-0.4509332392481099,0.6499020631811776,0.11041548986225669,-0.3216253964300375,0.3487156383369916,0.0964508264770475,-1.9882799741495716,2.534376198741266,-0.04766625239784411,-0.23732771986794354,0.22455564211316892,-0.05067618496130799,-0.2717851232675761,0.20985886078827232,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.283333333333333,1.0,0.0,1.0,1.0,3.3870457195821384,-0.004618225350099688,0.6001537747108138,0.9957428089957621,0.02031652603428436,0.044324063620655225,0.07822323495790712,-0.09253417593144009,0.013810388923849943,-0.01827827996550525,-0.02360921127679684,-0.017295022711023497,-0.0869175712123768,-0.4435006745883506,-0.29330900494564555,-0.33979905712337993,-0.2326062847147842,0.5925385867847792,-1.369550469132956,0.07186075101789018,-0.5812615320001658,0.68186229980081,0.197493571774498,-0.45321884535388335,0.6516483479416567,0.11098343516282916,-0.32956322237887914,0.35479590632676583,0.11355428725929373,-1.9651138787462363,2.5694426762480216,-0.04793357616795252,-0.24116249550764968,0.22332353030612095,-0.05102097674526185,-0.2764644202645383,0.2091231641658431,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.291666666666666,1.0,0.0,1.0,1.0,3.386247908419621,-0.004622128994272734,0.6000722200021549,0.995776303843894,0.020207575715876194,0.044254400711783985,0.07786369246523672,-0.09422089939564614,0.013742551326023068,-0.018655173134919933,-0.023745803659361978,-0.016138143702727724,-0.08781455164963302,-0.44257332554405454,-0.2960863642037191,-0.3368194606052734,-0.23158992387690489,0.5762596760671223,-1.3479950497716506,0.07146028502032638,-0.5832861255358027,0.68371795515396,0.19706705568213695,-0.4555409795858522,0.6533874492506083,0.1116059307530437,-0.33651038543988765,0.3597441028060555,0.130082859121185,-1.941736374793488,2.6032295982528364,-0.04815694982402613,-0.24448864653298985,0.22198128760000602,-0.05132110505221055,-0.28055876584759054,0.20814322080279446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3,1.0,0.0,1.0,1.0,3.3854370742388853,-0.004628099088746088,0.5999885840022865,0.995809737875086,0.02009756871957338,0.04418952691847137,0.07750057674260578,-0.095673383071496,0.013646806382119594,-0.019013594266861663,-0.023858489410400245,-0.015000190730803747,-0.0886911730338791,-0.4416405757424665,-0.2989175113696437,-0.33380332207661234,-0.23043823706276445,0.5601763138715544,-1.3261633091620755,0.07105813518748974,-0.5853363427757157,0.6855619879274768,0.19663822002362782,-0.4578948247846765,0.6551174016217033,0.11227590958475697,-0.34248269460246394,0.3635766006864505,0.14602928591847253,-1.9182176284205132,2.6357841732882337,-0.04833933346236219,-0.247320855166262,0.22053954053936176,-0.05157910228171081,-0.28408503268672725,0.20693667874820854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.308333333333334,1.0,0.0,1.0,1.0,3.384615155022381,-0.004636039226512705,0.5999028497822666,0.9958431024901917,0.01998661753470373,0.044129368078356074,0.0771339692692914,-0.09689935229897559,0.013525272741603544,-0.01935409691148231,-0.023946718955125564,-0.013881575874147904,-0.08954574503491952,-0.4407020603843086,-0.30179440911376015,-0.33075985059383256,-0.22915610244493034,0.5442893822601137,-1.30406531355018,0.07065462946262034,-0.5874081397885738,0.6873936141629494,0.19620740397744177,-0.460275730130631,0.6568363938964118,0.11298568619235505,-0.3475052037223547,0.3663188234221726,0.1613879054121603,-1.8946286621618857,2.667156620684561,-0.048484258493564636,-0.24967871445668255,0.21900922638062204,-0.05179810084640024,-0.28706580081185096,0.20552265169211603,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.316666666666666,1.0,0.0,1.0,1.0,3.383784013571912,-0.004645850023413264,0.5998150026459196,0.9958763886267322,0.01987483702805054,0.04407384962964988,0.07676395773870343,-0.09790845310279411,0.013380240822033719,-0.019677496288832565,-0.0240100107017464,-0.01278208346777484,-0.09037692476679177,-0.43975748097259393,-0.30470926476501625,-0.32769800835290946,-0.22774843863922845,0.5285991695021897,-1.2817106988173328,0.070250064212597,-0.589497654683327,0.6892121417004872,0.1957749183428545,-0.4626792547982074,0.6585427791499052,0.11372710600605518,-0.35161093129404186,0.36800392798779114,0.1761546885167531,-1.8710405897383375,2.697399820582258,-0.04859571782235034,-0.25158591770074956,0.2174013007809017,-0.05198172686568692,-0.2895284246751084,0.20392118452176033,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.325,1.0,0.0,1.0,1.0,3.382945422832562,-0.004657429987122104,0.5997250292170014,0.9959095867805267,0.01976234391636289,0.04402289916187336,0.07639063470711474,-0.09871190805034218,0.013214116828758771,-0.019984839340370847,-0.024047943428163333,-0.01170090157275536,-0.09118370223576908,-0.438806608617541,-0.3076545913019942,-0.32462645179403604,-0.22622019096965112,0.5131053724311414,-1.259108649873809,0.06984470083224784,-0.5916012384169196,0.6910169691759644,0.19534104186301365,-0.46510120387521614,0.6602350803051078,0.11449168467817294,-0.35483957294743185,0.36867147156968927,0.1903272595103933,-1.8475238952002115,2.726568919576362,-0.048678060891876596,-0.25306946543780073,0.21572647766065822,-0.05213399785101103,-0.29150412071136333,0.2021527626974362,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.333333333333334,1.0,0.0,1.0,1.0,3.3821010540963186,-0.004670676340718233,0.5996329165209295,0.9959426870250302,0.0196492562915379,0.0439764488293782,0.07601409630397166,-0.09932218321096908,0.013029371003801745,-0.020277375296867628,-0.024060147136333795,-0.010636656509654058,-0.09196538281844727,-0.4378492862279577,-0.31062325764747345,-0.321553483826748,-0.22457631764738856,0.49780710458218613,-1.23626788349106,0.06943876319773239,-0.5937154791072904,0.6928075829948315,0.19490601837867097,-0.46753765681006343,0.6619119918615292,0.11527073486967021,-0.3572362351675351,0.3683660885584972,0.20390489611593288,-1.824147773792305,2.7547209070758782,-0.04873589589438787,-0.2541589077896522,0.2139950051157169,-0.05225922671746763,-0.2930270958217307,0.2002378737912025,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.341666666666667,1.0,0.0,1.0,1.0,3.3812524679582623,-0.004685485792622707,0.5995386510688566,0.9959756790276698,0.019535693205532858,0.043934437618445454,0.07563444101401606,-0.09975267269896612,0.012828490840105095,-0.020556527515056343,-0.02404629249088839,-0.009587448870572179,-0.09272156758520343,-0.4368854297030465,-0.31360852855478644,-0.31848701698472776,-0.22282177603438558,0.482702909534603,-1.2131966347558778,0.0690324359006747,-0.5958372202134138,0.6945835525945597,0.19447005475105586,-0.4699849888055783,0.6635723782016278,0.11605547851058606,-0.35885021498736736,0.36713620135922054,0.21688850923340552,-1.8009795472325518,2.781914176219251,-0.04877400096773704,-0.25488563656302476,0.2122164791874992,-0.05236193399551503,-0.2941337333854599,0.1981966264300561,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.35,1.0,0.0,1.0,1.0,3.380401107849249,-0.004701755246725498,0.5994422179494936,0.9960085520625211,0.019421774320886855,0.04389681346531013,0.07525176853829328,-0.10001740594144487,0.012613939752025396,-0.020823867232440597,-0.024006078963897094,-0.00855088946890856,-0.09345213224280051,-0.4359150282527813,-0.3166040945639296,-0.31543454713742763,-0.22096150916016513,0.46779077879497694,-1.1899026472207392,0.06862586318160344,-0.5979635730500075,0.6963445243146231,0.19403331947874572,-0.4724398856998211,0.6652152689686968,0.1168371431032289,-0.3597338462294708,0.3650327849309798,0.22928060287159824,-1.7780841615887388,2.80820808142634,-0.0487972457131397,-0.25528223811113415,0.2103996954758336,-0.05244676964687223,-0.29486184948492644,0.19604842903887754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.358333333333333,1.0,0.0,1.0,1.0,3.3795482959315413,-0.0047193824484896,0.5993435999316421,0.9960412950187073,0.019307619631609717,0.043863535228726616,0.07486617873817547,-0.10013078146278646,0.012388121463064204,-0.02108108977903571,-0.023939221802026237,-0.007524133772395768,-0.09415720540547569,-0.43493814398465935,-0.31960409265861095,-0.3124031372358781,-0.21900043265319227,0.453068173508124,-1.1663931667321055,0.06821914847212238,-0.6000919241819327,0.6980902141858236,0.193595941923608,-0.4748993529636604,0.6668398520189425,0.11760704115894693,-0.3599414284356217,0.36210820096363894,0.24108521546362727,-1.7555237717679173,2.8336625025454243,-0.0488105239058334,-0.2553819146000835,0.20855253704757937,-0.05251844543794959,-0.2952500282026693,0.19381172828007776,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.366666666666667,1.0,0.0,1.0,1.0,3.378695231117774,-0.0047382665646452035,0.5992427765779679,0.9960738964039121,0.019193349258178925,0.04383457452652553,0.07447777066387645,-0.10010732967380724,0.012153350164028586,-0.021329993673438963,-0.023845437917704708,-0.006503913478902293,-0.09483714682578981,-0.43395491090013216,-0.32260311837118993,-0.3093994104547003,-0.21694342223577134,0.43853204926551165,-1.1426749388449822,0.06781235444983955,-0.6022199382933422,0.6998203999320828,0.1931580120547799,-0.4773607195031989,0.6684454644400314,0.11835663233067395,-0.359528250171689,0.3584151134133373,0.25230784425626707,-1.7333574128733498,2.8583374231632686,-0.04881869784629622,-0.2552179781987429,0.20668189587802033,-0.05258167840567318,-0.29533704127382765,0.19150380501451236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.375,1.0,0.0,1.0,1.0,3.377842988958226,-0.004758308695729418,0.5991397233681706,0.9961063443424076,0.01907908331951887,0.04380991745092664,0.07408664166660062,-0.09996150594816995,0.011911826315344043,-0.021572462924028604,-0.023724430782544145,-0.005486564026776542,-0.09549252612910361,-0.4329655334458148,-0.32559623016147243,-0.30642955201232247,-0.21479530191558782,0.4241788832935682,-1.1187542096793843,0.06740550350801744,-0.6043455571519117,0.7015349124504573,0.19271958061684677,-0.4798216369848909,0.6700315821025177,0.11907756820623505,-0.3585497140966265,0.3540054929217684,0.26295535482679266,-1.7116407554184787,2.8822925280978007,-0.04882655442865674,-0.25482341990695767,0.20479362417578084,-0.052641145583185445,-0.2951613541613596,0.18914062396609088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.383333333333333,1.0,0.0,1.0,1.0,3.376992523135656,-0.0047794123221534405,0.5990344108274367,0.9961386265669684,0.018964941884159713,0.04378956618211053,0.07369288659149704,-0.09970751419301849,0.011665617818893036,-0.02181045275847919,-0.023575874370671192,-0.004468046970334882,-0.09612410250411521,-0.4319702847633616,-0.32857894693946704,-0.3034993189060042,-0.21256083298865813,0.41000470334187034,-1.0946367300433522,0.06699857854269527,-0.6064669952917915,0.7032336270016791,0.19228065962839347,-0.48228007540588824,0.6715978081727996,0.11976172005553787,-0.35706056717984547,0.3489297135765901,0.27303587800913687,-1.690425938646194,2.9055868224823067,-0.0488387726938147,-0.25423055232267844,0.20289251136543118,-0.05270144984264147,-0.29476071786081803,0.18673673208271957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.391666666666666,1.0,0.0,1.0,1.0,3.376144668309676,-0.004801483685673571,0.5989268036539047,0.9961707304040176,0.01885104500230934,0.04377354052371697,0.07329659704697113,-0.09935916020271975,0.011416646169293509,-0.022045978920456843,-0.023399396162525957,-0.0034439662864293036,-0.09673280571189845,-0.4309695047782225,-0.33154723961446986,-0.30061405678604597,-0.21024470394876887,0.39600511764946494,-1.0703277626380125,0.06659152396312053,-0.6085827330239564,0.7049164543065478,0.1918412231194694,-0.4847343156159045,0.673143860970563,0.12040119006996863,-0.3551142358583037,0.3432357416645182,0.2825586966136867,-1.669761473953928,2.928278272214362,-0.04885990239259619,-0.2534707236594169,0.20098228220000403,-0.0527670964667748,-0.29417184346365643,0.18430519980514815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4,1.0,0.0,1.0,1.0,3.3753001440623884,-0.004824432109096784,0.5988168598368347,0.996202642751279,0.018737512820344724,0.043761879387559426,0.07289786074463588,-0.09892973332955879,0.011166677110211257,-0.02228111060327479,-0.023194559177985775,-0.00240957779952344,-0.09731971869026296,-0.42996359826219543,-0.33449751753710544,-0.29777872321159554,-0.20785152137843002,0.3821753454426382,-1.0458320921731128,0.066184246836152,-0.6106915073527818,0.7065833317050125,0.1914012080206139,-0.48718293946361585,0.6746695615028854,0.12098830679200478,-0.35276226283026735,0.33696841263212485,0.29153412431953796,-1.6496922086409682,2.9504234629168336,-0.04889435290782507,-0.2525740987756575,0.19906561140955015,-0.052842479878892346,-0.29343015473367706,0.1818575990438398,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.408333333333333,1.0,1.0,1.0,1.0,3.374459559712393,-0.004848170257775523,0.5987045297552321,0.9962343500471419,0.018624465779240096,0.04375464225801234,0.07249676090323331,-0.09843191441825477,0.01091731526708075,-0.022517967037636193,-0.02296084296108307,-0.0013597910163347842,-0.0978860619506492,-0.42895303299835574,-0.337426610661641,-0.29499791657551055,-0.20538580187677657,0.3685102475054488,-1.0211540382560653,0.06577661808132344,-0.612792301336884,0.708234214496707,0.19096051512148787,-0.48962481819479914,0.676174820954627,0.12151560551433738,-0.3500538395737207,0.3301687894071448,0.29997337901255083,-1.6302593388218212,2.9720772719609623,-0.04894639177270399,-0.25156950185191596,0.19714415041794053,-0.052931879841260354,-0.292569612663105,0.17940401156953278,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.416666666666666,1.0,1.0,1.0,0.0,3.373623419783834,-0.0048726143469417,0.5985897552448156,0.9962658382308339,0.01851202489872156,0.04375191066930236,0.0720933757092066,-0.08368812495464414,0.010711667246700418,-0.013695404273562521,-0.03124463602373738,-0.02654399508886908,-0.08853019562639233,-0.4279383381702898,-0.34033174819666745,-0.2922759100548098,-0.20285196506155417,0.3550043564622745,-0.9962974709737634,0.06536847363994026,-0.614884332383647,0.7098690675453115,0.19051901002325955,-0.4920590996746676,0.6776596283623776,0.14049905682329777,-0.31645152710951363,0.3911722264173578,0.21280657344114828,-0.9371638064189292,1.6065605530120441,-0.034925717553133395,-0.205813326485198,0.20194204510572078,-0.03826267307146969,-0.23116273281992727,0.1663469164918019,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.425,1.0,1.0,1.0,0.0,3.3730387323740403,-0.004867261524145937,0.5986028864722124,0.9963020303777675,0.018348645720973628,0.043529183832710094,0.07176908543898346,-0.05802634644095761,0.009266723614354757,-0.00367849214598493,-0.03338325548738087,-0.03670064656647551,-0.07696229090134417,-0.4266113820513008,-0.3427008027801329,-0.2884783794685546,-0.20183902565275744,0.3528908507318,-0.9943780290391979,0.06519452278877122,-0.6162225234449706,0.711599915248469,0.19032280390363004,-0.4934775304084646,0.6789472695628237,0.1447026429206444,-0.23509190821951576,0.3542303485311904,0.11201536448203264,-0.21334981070622816,0.16578697140123388,-0.024432129993742224,-0.1312229093097561,0.16362794553094195,-0.0052892292823319975,-0.34747347581156607,0.5108837244448794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.433333333333334,1.0,1.0,1.0,0.0,3.372642622432218,-0.004857853630399267,0.5986166686193063,0.9963303177183837,0.018228932228626007,0.04343899503324362,0.07146088321455644,-0.03862115935387075,0.0073247337329421245,-0.004909865599647503,-0.02358836497984839,-0.025405787113113084,-0.07271712030790842,-0.42552662745494574,-0.3442499466669927,-0.2863720709126233,-0.20098504232018696,0.3514485262838374,-0.9935343547837429,0.0649612714733779,-0.617071380872143,0.7125961999708272,0.19043085620188735,-0.49785032427152703,0.6861743571031256,0.12538896565237323,-0.13925995403593183,0.19407974166467667,0.09734771719316804,-0.14087700622223864,0.08086704708407444,-0.02874302181520516,-0.09644822524464969,0.14288290255140002,0.011521102319355658,-0.5241542528256316,0.9025314135448892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.441666666666666,1.0,1.0,1.0,0.0,3.372379562959081,-0.004836724731366168,0.5985806508257114,0.9963581189732391,0.01814159184961873,0.04331523741164005,0.07117001996890644,-0.02420404660187224,0.006137311875972107,-0.007458039290494644,-0.019576656416512708,-0.03187110791787681,-0.06951699192680841,-0.42452156595709456,-0.34502180201406507,-0.28524371710747665,-0.20021656369953797,0.350542900628096,-0.99303024492113,0.06471547242518447,-0.6178299938657148,0.713981296957659,0.1905148222756193,-0.5022134346222251,0.6939894597885718,0.12129299092689338,-0.061028799625637564,0.09734833919779584,0.09240709399715386,-0.08822323539602883,0.050724967994923986,-0.02829096325098812,-0.08233379474222424,0.17451656884196254,0.009388285158764553,-0.513930485339692,0.9454437280826333,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.45,1.0,1.0,1.0,0.0,3.372219426015735,-0.004810786379343182,0.5985310225451584,0.9963860109533543,0.018060190756148856,0.043173267573514314,0.07088593519250319,-0.013447664277775526,0.0049778283768561835,-0.007547322610263949,-0.018867537033539068,-0.03523759089817015,-0.06831893225904265,-0.4235050776061642,-0.34526709332742,-0.28474959859266,-0.19944492408690107,0.3499781390272369,-0.9926889386504941,0.06448975541919476,-0.6184436107845134,0.7155048094515266,0.1905873276212001,-0.5064158323605219,0.7019317525711695,0.12333594688191285,-0.007127736571286292,0.0323969684776193,0.09355169291803911,-0.05368450753354237,0.03450623585491197,-0.02610628538419507,-0.0655448497231248,0.18537823475853976,0.007475369380003927,-0.4954114376111929,0.9543975905541147,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.458333333333334,1.0,1.0,1.0,0.0,3.3721357888507333,-0.00478290129411303,0.5984776156017103,0.9964139928299683,0.017981163359124183,0.04302178830734543,0.07060423895111242,-0.005557510871992424,0.004019679595174118,-0.007137363078842217,-0.01857701420771593,-0.03705336117215817,-0.06789391289806207,-0.422465966842396,-0.3451405976235865,-0.28470376763284966,-0.19865736881757065,0.3496481588358703,-0.9924551409902148,0.06428036766878122,-0.6189224080277669,0.7170709342036347,0.19063941176528604,-0.510470291915745,0.7098960862978071,0.12592138216721227,0.03125881331336733,-0.014049695844078336,0.09544577285143796,-0.029575112225799227,0.02340416240175003,-0.024417814473767785,-0.05103754862894716,0.18869586841004038,0.004648841639502965,-0.4795381120843656,0.9553539925300236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.466666666666667,1.0,1.0,1.0,0.0,3.3721082437968617,-0.0047541389037225835,0.598423097439152,0.9964420248990455,0.01790339583922523,0.042864839826733225,0.07032329003266567,0.00020414027135218834,0.0032846838543768575,-0.006713367549463652,-0.018417137555859914,-0.03813604593461595,-0.0677572439591283,-0.4214063879033773,-0.34474611310553055,-0.28498376019006133,-0.19785416120604377,0.34948522049014025,-0.9922988692771316,0.06408279184463196,-0.6192942365949958,0.718649740591694,0.1906648083151918,-0.5144081342285947,0.7178543191133365,0.12811765232230377,0.059024334565219716,-0.047882288158590525,0.09715070091837696,-0.01231230588276011,0.015338610360342564,-0.023204047932521288,-0.039764346438924125,0.18964829809920314,0.0011990140006690186,-0.4672099434857979,0.954157967588678,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.475,1.0,1.0,1.0,0.0,3.3721217169332895,-0.00472493348724891,0.5983682102680089,0.9964700702014501,0.017826377680307703,0.04270443453025641,0.07004249363136782,0.00441385723614044,0.0027366141581695496,-0.006372100341596603,-0.01831981661338418,-0.03883865282714594,-0.0677263803843777,-0.4203306726370243,-0.3441568587141662,-0.28550180576882617,-0.19703819046893103,0.3494429537378243,-0.9921994974842091,0.06389363353657253,-0.6195851471350823,0.7202317391719547,0.19065939533196385,-0.518257124307175,0.7257987190909517,0.12981288312263306,0.07923504198521947,-0.07259468495977472,0.09850249973614555,0.00020249357923773914,0.009415621298063392,-0.02234141272306117,-0.03128636210278035,0.18983851818406672,-0.002670879504835799,-0.4578093822898799,0.9523344881954632,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.483333333333333,1.0,1.0,1.0,0.0,3.3721652168983383,-0.004695486608005369,0.5983131667013492,0.9964980985795192,0.01774983677278506,0.042541694640261106,0.06976164589187996,0.007496722985106818,0.0023321114696308186,-0.006116066121566384,-0.018257474145908236,-0.03932055131715608,-0.0677327847229476,-0.4192428398513334,-0.34342552907244356,-0.2861936716060576,-0.196212452877108,0.34948859538312754,-0.9921419422554972,0.06371043496591428,-0.6198156759633755,0.7218137158947617,0.19062029365677788,-0.5220382906000927,0.7337265605832609,0.1310740171179603,0.09399223057288131,-0.09062867578931044,0.0995250492665467,0.009341281970646209,0.005064800409311232,-0.021732479443523633,-0.02496311833303677,0.18976215828829357,-0.006839674016450026,-0.4505741473082936,0.9502286700126672,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.491666666666667,1.0,1.0,1.0,0.0,3.3722307535536182,-0.004665906409084686,0.5982580305986803,0.9965260864385053,0.01767361107345422,0.04237731542600706,0.06948068696166138,0.009761426513816118,0.0020343069030503477,-0.005928769738573903,-0.01821677551790278,-0.039661473186744185,-0.06775093254895648,-0.4181461056850583,-0.3425903215379515,-0.287012283698648,-0.19537943964782192,0.3495986417706684,-0.9921150841440539,0.06353142554584713,-0.6200011991072996,0.7233944418100929,0.19054540076502302,-0.5257666934289799,0.7416358635911628,0.1319955826953434,0.1047920340677333,-0.10377311188599858,0.10028272283324036,0.01605059429458211,0.0018714928619290028,-0.021306346804426668,-0.020240988280535444,0.18957831965946026,-0.011229509978675778,-0.44486949166020917,0.9478663207014448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.5,1.0,1.0,1.0,0.0,3.3723125194340953,-0.004636258449271134,0.5982028231466936,0.9965540157432397,0.01759759572516345,0.04221176121013416,0.06919960805377239,0.011431574249819653,0.0018147349960052348,-0.005793215984516623,-0.018190445899480764,-0.039906450278101385,-0.06777157385026429,-0.4170429134730777,-0.34167899517131467,-0.2879232234708242,-0.19454107416322067,0.34975610528803724,-0.9921107507077984,0.0633553291858405,-0.6201530257680511,0.7249733545557527,0.19043313515713328,-0.5294527821277628,0.7495243325949517,0.13266160394922788,0.11271470169486708,-0.11334566398876977,0.10083862838117463,0.021001126997359787,-0.00047236515298587634,-0.02101206019759827,-0.016693359050292678,0.18934198559373616,-0.01578716160889837,-0.44021386313060296,0.9452000706468855,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.508333333333333,1.0,1.0,1.0,0.0,3.3724062910499346,-0.004606585915365184,0.5981475529696467,0.9965818729147029,0.01752171911331761,0.04204535630925413,0.06891841670854042,0.012669252185571429,0.0016522029876242879,-0.005695683612529509,-0.018174082786274127,-0.04008370987305421,-0.06779159793868593,-0.41593507895257115,-0.3407117431763704,-0.28890137809846084,-0.193698795841469,0.34994866055395774,-0.9921229568966037,0.06318122454255383,-0.6202794217581378,0.7265501415699885,0.19028228140487471,-0.5331035911478232,0.7573891981019443,0.13313853697174305,0.11854393943641961,-0.12031342340259488,0.10124445322779729,0.024674415697625296,-0.0021947281567857857,-0.02081304712702181,-0.014003419411792173,0.18907480110510244,-0.02047475291440226,-0.43625291402831223,0.942177314283652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.516666666666666,1.0,1.0,1.0,0.0,3.372508994642496,-0.00457691867674761,0.5980922248251291,0.9966096478276841,0.01744593075556518,0.041878332826041545,0.06863712413991829,0.01359209010320032,0.0015311696465084338,-0.005625835964332412,-0.018164809625131124,-0.040212236529602666,-0.0678101698550685,-0.414823937856882,-0.33970326284737434,-0.2899284471942008,-0.19285366660942405,0.35016734554966433,-0.9921473295104115,0.0630084450670568,-0.620386416091581,0.7281246012408378,0.19009188927522658,-0.5367236640282347,0.7652272878330125,0.13347664404402604,0.12284921061876508,-0.12538342313844875,0.10153987015130761,0.02741845090690198,-0.003463181184166775,-0.020683015623030043,-0.011938956740917828,0.18878700748090393,-0.025264574498934933,-0.43272885787239534,0.9387562130149574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.525,1.0,1.0,1.0,0.0,3.3726183915729364,-0.004547277944659588,0.5980368421575821,0.9966373329749895,0.017370194426728613,0.04171085902638807,0.06835574094367242,0.01428554269632689,0.0014403120242688072,-0.005576073635160997,-0.018160653164294417,-0.04030532316582402,-0.06782725645993372,-0.41371046821850405,-0.3386642563327243,-0.290991101817435,-0.19200646467228055,0.35040563473573944,-0.9921806765830065,0.06283650761550333,-0.6204784043704864,0.7296965916946703,0.1898612051632258,-0.5403157387790298,0.7730351349855269,0.13371318251301112,0.12604452439975655,-0.12907122451978115,0.10175447738656695,0.029485558762567532,-0.00440037035171148,-0.020603023668673004,-0.010330553161894684,0.1884844341738945,-0.03013589630764535,-0.42945511895134514,0.9349071513911422,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.533333333333333,1.0,1.0,1.0,0.0,3.3727328502306704,-0.004517678995467286,0.5979814078652627,0.9966649228048081,0.017294483863192406,0.04154305779876955,0.06807427591781738,0.014811740859662997,0.0013714032174569895,-0.005540860776892224,-0.018160221230324028,-0.040372473241234684,-0.06784307007473278,-0.41259538481499847,-0.33760252077404507,-0.2920796342695305,-0.19115775865298126,0.35065877152904046,-0.9922206690162734,0.06266506133924558,-0.6205585919776125,0.7312660084770694,0.18958962433676582,-0.5438812493440904,0.7808090736895316,0.1338754991862534,0.12843094492664298,-0.13175221418489924,0.10191005987256807,0.03105903493143325,-0.005095823432288427,-0.02055939823798758,-0.009054786405391368,0.18817086022051788,-0.035072875128511205,-0.42629712291392563,0.930610684358486,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.541666666666666,1.0,1.0,1.0,0.0,3.372851180513236,-0.004488132917584452,0.5979259245425166,0.9966924132119267,0.017218779897670483,0.04137501934819035,0.06779273598479395,0.015215886988126301,0.0013184723047735853,-0.00551617893868537,-0.018162516110751377,-0.04042055101049363,-0.06785786568400927,-0.41147920989873316,-0.3365237405839469,-0.29318697205384997,-0.19030796367440442,0.35092328531793,-0.9922656069735446,0.062493850978203536,-0.6206293174772429,0.7328327726983456,0.18927665724441728,-0.5474206908275953,0.7885453130581683,0.1339835659700117,0.13022744647019024,-0.13369951517272494,0.10202254409698797,0.03227217613448352,-0.005614809740277504,-0.02054225499076079,-0.00802176686232503,0.18784891070579013,-0.04006312392923761,-0.4231581487478242,0.925855104131621,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.55,1.0,1.0,1.0,0.0,3.372972513612096,-0.004458647797703053,0.597870394566764,0.9967198011550539,0.01714306847233772,0.04120681018725384,0.06751112645349319,0.015530885267229273,0.001277187204636803,-0.005499114992961297,-0.018166816320692947,-0.04045453953198871,-0.06787187365519715,-0.41036232538216494,-0.33543206333287523,-0.29430795952240923,-0.18945738291803146,0.35119664113128185,-0.9923142491786113,0.062322690422732904,-0.6206922880919846,0.7343968236554992,0.18892190560461186,-0.5509338851565542,0.7962399920917252,0.13405193112666747,0.1315933317632334,-0.13511178885526776,0.1021035339434706,0.033221990815416325,-0.006004888155153321,-0.020544441056518786,-0.0071660159635023035,0.18752046680637235,-0.04509670971268809,-0.41996900819419203,0.9206343965745711,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.558333333333334,1.0,1.0,1.0,0.0,3.3730962146422496,-0.004429229551680568,0.5978148201386396,0.9967470843727863,0.01706733923139798,0.041038479597592964,0.06722945134233911,0.01578069903121786,0.001244404965753303,-0.005487558110146232,-0.018172597093444303,-0.040478065900903894,-0.0678852831940741,-0.40924501104662203,-0.334330518387893,-0.29543883520143777,-0.1886062381086799,0.3514769851648536,-0.9923656884427972,0.062151443627261556,-0.6207487510766346,0.7359581138117851,0.18852504541587248,-0.5544201742974985,0.8038892196677445,0.1340911786366228,0.1326445229557549,-0.13613353171753495,0.10216146941289084,0.033979118190794466,-0.006300708485498241,-0.020560776955858284,-0.006439822012362928,0.18718689557625456,-0.050165441422942436,-0.4166805396089601,0.9149466819551133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.566666666666666,1.0,1.0,1.0,0.0,3.373221819104659,-0.004399882515852085,0.5977592033069384,0.9967742611745481,0.01699158451283551,0.040870064305232594,0.06694771367052853,0.01598278771033904,0.0012178451968247977,-0.005479979093275875,-0.018179475010518198,-0.04049377471264768,-0.06789824361238006,-0.4081274724048879,-0.33322132128361265,-0.2965768517177015,-0.18775469176114995,0.3517629597677951,-0.992419260986703,0.06198001080680193,-0.6207996184588573,0.7375166052484368,0.1880858149142295,-0.5578785608167035,0.8114891034576438,0.13410900423424077,0.13346539972134308,-0.13686985645160687,0.10220248415843902,0.034595020557851575,-0.0065275176091006415,-0.020587511199913477,-0.005808407663856485,0.18684919887675067,-0.05526235965810755,-0.41325815207597705,0.908793066207465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.575,1.0,1.0,1.0,0.0,3.3733489866561523,-0.004370609871189872,0.5977035459875181,0.9968013302875095,0.01691579862184712,0.04070159187443672,0.06666591569434828,0.016149877099479702,0.00119585323663633,-0.0054752702801263405,-0.018187168700139374,-0.0405035969051476,-0.06791087081459456,-0.40700986097605135,-0.33210609505920397,-0.2977199994756312,-0.18690286337270592,0.3520535688408178,-0.9924744804029488,0.06180831844059633,-0.6208455578710322,0.7390722671263976,0.18760400608823735,-0.5613078101654314,0.8190357707712023,0.1341110028940351,0.13411740176392573,-0.13739724248833185,0.10223103403116329,0.03510720538698053,-0.006703714637514846,-0.020621926887756797,-0.005246415706352536,0.1865081171353733,-0.06038136917971948,-0.40967785892456643,0.9021768060668811,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.583333333333334,1.0,1.0,1.0,0.0,3.3734774674561754,-0.004341413948764665,0.5976478499788451,0.9968282907448405,0.016839977305576265,0.040533083175184934,0.0663840590900684,0.016291246153941955,0.0011772284688194028,-0.005472629534231671,-0.01819547065927107,-0.040508944381723457,-0.0679232543948261,-0.40589228902332064,-0.3309860312542139,-0.2988668057591737,-0.1860508411939639,0.3523480798575781,-0.9925309895639949,0.06163631202533932,-0.6208870587206299,0.7406250738673597,0.18707945876123416,-0.564706525132113,0.8265253835587585,0.13410124284298108,0.13464528068473092,-0.1377713503391531,0.1022503555130777,0.03554302020410849,-0.00684271138667869,-0.020662057391025168,-0.00473535274643444,0.186164203534962,-0.06551697352126962,-0.4059233927699557,0.8951027055584793,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.591666666666667,1.0,1.0,1.0,0.0,3.3736070776578457,-0.004312296450177101,0.5975921169750832,0.9968551418042787,0.016764117372658247,0.04036455417874863,0.06610214509213609,0.01641366286692419,0.0011610998532327037,-0.005471476205232493,-0.018204226944165167,-0.040510851262724856,-0.06793546384224809,-0.40477484026200167,-0.3298620070477918,-0.30001618864795043,-0.1851986907808213,0.35264595251088626,-0.9925885255927268,0.06146395081741258,-0.6209244804168061,0.7421750038519803,0.18651205652954952,-0.5680732000449307,0.8339541491971769,0.13408268308067073,0.13508164431993985,-0.13803270048271643,0.10226279923772008,0.03592241209979141,-0.006954286631755124,-0.020706480577888375,-0.004261728827583688,0.1858178773226271,-0.07066408308321781,-0.40198410620388314,0.8875766807406027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.6,1.0,1.0,1.0,0.0,3.3737376815509843,-0.004283258606817909,0.5975363485771603,0.9968818828888342,0.016688216417302747,0.040196017265178866,0.06582017459625752,0.016522065266195277,0.0011468356637774906,-0.005471390239695034,-0.01821332249092257,-0.04051007652441684,-0.06794755352703166,-0.4036575776386428,-0.3287346705155482,-0.30116735076721896,-0.18434646120666856,0.35294678672590796,-0.9926468943411908,0.06129120401570785,-0.6209580875344229,0.7437220384894034,0.18590172404318053,-0.571406260235511,0.8413183282377685,0.1340574767461844,0.13545026071100086,-0.13821080043197154,0.10227007233692631,0.036259935419707956,-0.007045571899786385,-0.020754169714983922,-0.003815702834637502,0.18546946200935333,-0.07581787635926651,-0.39785344356155106,0.8796054462799274,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.608333333333333,1.0,1.0,1.0,0.0,3.373869178546371,-0.004254301295030798,0.5974805463021334,0.9969085135436213,0.01661227261898516,0.04002748217595431,0.06553814823574763,0.01662005717749664,0.001133978008008788,-0.005472068052366788,-0.018222670488798328,-0.040507178628840346,-0.06795956654860837,-0.4025405489828986,-0.32760450270260844,-0.3023197019884833,-0.18349418957520586,0.3532502847678814,-0.9927059517910566,0.06111804798882951,-0.6209880754640501,0.7452661615521362,0.18524842525689508,-0.5747040907709565,0.848614239968509,0.1340271914387725,0.13576846095987416,-0.13832714449766637,0.102273414445746,0.036566213165103445,-0.007121769184121884,-0.020804385339771025,-0.003390095676867322,0.18511921261666453,-0.08097369970668955,-0.39352782806860276,0.8711962901736192,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.616666666666667,1.0,1.0,1.0,0.0,3.374001493684997,-0.004225425119456249,0.5974247115911179,0.9969350334044206,0.016536284596885338,0.039858956708528216,0.06525606643786867,0.01671026930266412,0.0011221953049643852,-0.005473290533213707,-0.018232204680417256,-0.04050256981296042,-0.06797153764299141,-0.40142379111466325,-0.32647186283288365,-0.3034728031755134,-0.18264190429923946,0.353556223611993,-0.9927655904942595,0.060944464260044996,-0.6210145891290374,0.7468073586996812,0.18455216238140237,-0.5779650573699877,0.8558382664073289,0.133992969206298,0.13604888730638476,-0.13839739468998302,0.10227372551003033,0.03684900123156698,-0.007186673627954665,-0.020856596785934628,-0.002979671047538268,0.1847673350241541,-0.08612699515924582,-0.38900585130444476,0.8623569122736008,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.625,1.0,1.0,1.0,0.0,3.3741345707150896,-0.004196630473407271,0.5973688458160246,0.9969614421747679,0.016460251303996483,0.039690447223061864,0.06497392946533473,0.016794622318642923,0.001111247781244151,-0.005474899844527336,-0.018241873779482554,-0.04049655559827048,-0.06798349535142818,-0.4003073328294603,-0.325337021247502,-0.30462632523331634,-0.18178962748337202,0.3538644347884075,-0.9928257296848558,0.06077043804239727,-0.6210377366481757,0.7483456171358721,0.18381297533757432,-0.5811875216260306,0.8629868551730691,0.13395564273305238,0.13630076530943613,-0.13843296675804084,0.10227165860294984,0.037113963761746804,-0.007243054295775764,-0.02091042519136721,-0.0025806109583381698,0.18441399965888117,-0.09127324870075781,-0.38428768281871806,0.8530953090264237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.633333333333333,1.0,1.0,1.0,0.0,3.3742683670404254,-0.0041679175826649425,0.5973129502853096,0.99698773960924,0.016384171949996307,0.03952195901242433,0.06469173744689093,0.016874518668490664,0.001100962407723458,-0.005476782587538944,-0.01825163742238433,-0.040489363557600105,-0.06799546362484844,-0.3991911970691124,-0.3242001834110597,-0.3057800192881474,-0.18093737665585696,0.3541747896746888,-0.9928863080658558,0.06059595717352221,-0.6210575993116764,0.7498809253606625,0.18303094156972308,-0.584369852083633,0.8700565215577692,0.13391581973512645,0.13653083003554944,-0.13844218400268837,0.10226768734476588,0.03736523827926996,-0.007292931664497626,-0.020965602080808415,-0.0021901331286411363,0.1840593511579547,-0.09640795351524178,-0.37937464014962785,0.8434196917094461,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.641666666666666,1.0,1.0,1.0,0.0,3.374402850032985,-0.004139286537309813,0.5972570262489076,0.9970139255012416,0.016308045944976916,0.03935349657260237,0.0644094903998795,0.016950982432141375,0.0010912146853230215,-0.005478857586277559,-0.01826146323165926,-0.04048116427124843,-0.06800746300322916,-0.3980754025005415,-0.3230615074135762,-0.3069336949666945,-0.18008516602762592,0.3544871887597287,-0.9929472785459308,0.06042101134105046,-0.6210742388669864,0.7514132729885047,0.1822061761123203,-0.5875104322951911,0.8770438500348932,0.13387394427930688,0.1367440006202003,-0.1384311169533281,0.10226215488850943,0.037605847780473045,-0.007337779921965382,-0.0210219392473307,-0.001806211741885999,0.18370351518067096,-0.10152658424156358,-0.3742688757584367,0.8333384289450629,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.65,1.0,1.0,1.0,0.0,3.3745379943407428,-0.004110737314923592,0.5972010749024902,0.9970399996740631,0.01623187285831016,0.039185063800525145,0.06412718824695586,0.017024761376369373,0.00108191540174951,-0.005481067019697456,-0.01827132468600045,-0.04047208660235215,-0.06801951147709197,-0.39695996466445727,-0.3219211167340564,-0.3080872045707029,-0.17923300740771514,0.35480155380436335,-0.9930086043978885,0.06024559151940003,-0.6210877028407078,0.7529426506136737,0.18133883183236368,-0.590607666679607,0.8839454953735203,0.13383034134955007,0.13694387176350298,-0.13840419466425669,0.10225530952352957,0.03783800136444304,-0.007378674506217653,-0.02107930683450346,-0.0014273735537728705,0.18334660321200458,-0.10662457935354308,-0.36897314922035296,0.822860006807058,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.658333333333333,1.0,1.0,1.0,0.0,3.374673779921637,-0.004082269797574899,0.5971450973911666,0.9970659619743175,0.016155652388493563,0.039016664138958254,0.06384483082854944,0.017096401444199466,0.0010730009973543746,-0.005483369983002953,-0.01828119957574686,-0.04046222883926315,-0.06803162511255037,-0.39584489681138235,-0.32077910955085115,-0.3092404315444321,-0.17838091086890043,0.35511782211580273,-0.9930702564543678,0.060069689560475405,-0.621098028426216,0.7544690497087048,0.18042909978976124,-0.593659984782197,0.8907581834816775,0.13378524924836044,0.13713307199128777,-0.13836464991962116,0.1022473305614352,0.03806331364910598,-0.007416399750939107,-0.021137617373560708,-0.0010525489580048841,0.1829887159550947,-0.11169732957741263,-0.3634906616019884,0.8119930016578047,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.666666666666666,1.0,1.0,1.0,0.0,3.3748101906076804,-0.0040538837843338065,0.5970890948127161,0.9970918122671036,0.016079384340966466,0.03884830068276143,0.06356241791224836,0.017166301150797904,0.0010644265525766548,-0.005485737812162994,-0.018291068883592266,-0.040451666830018274,-0.06804381850069162,-0.3947302105103179,-0.3196355655342016,-0.31039328206936323,-0.17752888523169122,0.3554359423651818,-0.9931322110604042,0.05989329789650735,-0.6211052453233412,0.7559924625462586,0.17947720967274014,-0.5966658443729734,0.897478712067817,0.1337388431614439,0.13731352491158422,-0.1383148436039927,0.1022383471631666,0.038282964987520485,-0.007451527455117901,-0.02119681414664079,-0.0006809631515203307,0.18262994573504887,-0.1167401708302257,-0.3578249352052998,0.800746062177522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.675,1.0,1.0,1.0,0.0,3.374947213056268,-0.0040255790005802395,0.5970330682204255,0.9971175504324277,0.016003068611706976,0.03867997625692487,0.06327994919997447,0.01723475132404434,0.0010561606803088227,-0.005488150688346712,-0.018300915974349206,-0.040440459926348496,-0.06805610507666532,-0.39361591609202495,-0.31849055080232475,-0.31154567893783197,-0.17667693841618098,0.3557558715322614,-0.9931944485786197,0.05971640932469806,-0.6211093778120746,0.7575128821376222,0.17848343027592414,-0.5996237337022853,0.9041039511846362,0.13369125230150436,0.13748663981576592,-0.1382565011301573,0.10222845203727793,0.038497818516751714,-0.007484474255086138,-0.021256862693764672,-0.00031205657166966105,0.18227037821268555,-0.12174838057900761,-0.35197972641448416,0.7891278980039806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.683333333333334,1.0,1.0,1.0,0.0,3.375084835984416,-0.003997355105021621,0.5969770186255923,0.9971431763625365,0.015926705175022843,0.03851169347396463,0.06299742433358972,0.01730196415226263,0.0010481818029078683,-0.00549059517206294,-0.018310726009518104,-0.040428655332249,-0.06806849734209876,-0.3925020229719595,-0.31734412153727215,-0.3126975570881992,-0.1758250776977366,0.3560775726737943,-0.9932569522979889,0.059539016851611275,-0.6211104462662024,0.7590303021831367,0.17744806999642335,-0.6025321731465482,0.9106308437012167,0.13364257238467014,0.13765345079736035,-0.13819088483912334,0.10221771140987379,0.038708505712148344,-0.007515543535321356,-0.021317744605336003,5.457329028013547e-05,0.18191009361601562,-0.12671717682052996,-0.3459589626896986,0.7771472730964724,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.691666666666666,1.0,1.0,1.0,0.0,3.375223049609842,-0.003969211695084835,0.5969209469997383,0.9971686899599175,0.01585029407437891,0.038343454776204725,0.06271484289940418,0.017368094425755,0.0010404754361696164,-0.005493062412818904,-0.018320485525575927,-0.040416291289486705,-0.06808100701584616,-0.3913885398856138,-0.31619632662236874,-0.31384886035181736,-0.1749733098926831,0.35640101329413054,-0.9933197076375417,0.05936111358127579,-0.6211084682572366,0.7605447170312225,0.1763714773289153,-0.6053897164137803,0.917056405736244,0.1335928747126658,0.13781471834083292,-0.13811891976352797,0.1022061722836809,0.03891548895613273,-0.00754495605743255,-0.021379452976481444,0.0004192144598724745,0.18154916763474693,-0.13164171909902822,-0.3397666971715463,0.7648130024447553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7,1.0,1.0,1.0,0.0,3.3753618452433196,-0.0039411483111646385,0.596864854276572,0.9971940911357796,0.015773835415422162,0.038175262466974745,0.0624322044319343,0.017433255078245426,0.0010330322057725337,-0.0054955468496274635,-0.018330182131480587,-0.04040339941490418,-0.0680936451315807,-0.39027547506008176,-0.31504720956492493,-0.314999539084258,-0.17412164149300857,0.3567261641563965,-0.9933827015656128,0.059182692635336584,-0.6211034593585378,0.7620561216437158,0.17525404134477288,-0.6081949514327406,0.923377727075296,0.13354221278589207,0.13797100354233982,-0.13804128541036853,0.10219386772514882,0.03911910732434909,-0.007572872353867055,-0.02144198907028605,0.0007820716361250923,0.1811876720796568,-0.13651711113779663,-0.33340707611746456,0.7521339511075897,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.708333333333334,1.0,1.0,1.0,0.0,3.3755012149917514,-0.003913164440079254,0.5968087413537292,0.9972193798088876,0.015697329360590727,0.038007118733663976,0.0621495084171671,0.017497528563839244,0.001025846396744536,-0.00549804526833792,-0.01833980429329105,-0.04039000641858213,-0.0681064220959488,-0.38916283633918225,-0.3138968098966631,-0.31614954844199017,-0.1732700787639306,0.357052998416203,-0.9934459221767729,0.059003747096771024,-0.6210954337299679,0.7635645115658835,0.17409619214328537,-0.610946501015738,0.9295919715880372,0.1334906271195868,0.1381227223615078,-0.13795848277168954,0.10218082071673684,0.039319610112854564,-0.00759940910961987,-0.0215053598605576,0.0011432890024098974,0.18082567537752947,-0.14133840477375426,-0.3268843156799539,0.739119034838398,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.716666666666667,1.0,1.0,1.0,0.0,3.375641151542297,-0.0038852595179883933,0.5967526090943183,0.9972445559046494,0.015620776124860852,0.03783902566477908,0.06186675429552032,0.01756097518927653,0.0010189148910903167,-0.005500556118522474,-0.018349341182267772,-0.04037613536979039,-0.06811934771746236,-0.3880506312747553,-0.31274516419223314,-0.3172988471304528,-0.1724186278143963,0.35738149099161076,-0.9935093583841065,0.05882426997099396,-0.621084404541831,0.765069882900008,0.1728984012652103,-0.6136430233607398,0.9356963776559359,0.13343814875171223,0.13827018529995128,-0.13787088327209207,0.1021670469646363,0.039517181405204216,-0.007624651149285011,-0.02156957621490957,0.0015029669333954665,0.1804632429494668,-0.14610060496695776,-0.320202685470099,0.7257772217464553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.725,1.0,1.0,1.0,0.0,3.375781648005881,-0.00385743293295942,0.5966964583282879,0.997269619354391,0.015544175972305993,0.03767098526257482,0.06158394146463728,0.017623639220946844,0.001012236387974335,-0.00550307901881216,-0.01835878256955458,-0.04036180663202314,-0.0681324312137747,-0.3869388671933204,-0.31159230680833055,-0.31844739649652504,-0.17156729464785334,0.35771161810628976,-0.9935729996959276,0.058644254159855864,-0.621070384281078,0.7665722322817079,0.17166118206050274,-0.6162832124402396,0.9416882586171448,0.13338480179793777,0.13841362643612687,-0.13777876453637927,0.10215255694594305,0.039711958087140786,-0.00764866021277566,-0.02163465154373559,0.0018611742363483508,0.1801004375051929,-0.15079867571542338,-0.3133664970343264,0.7121175345862452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.733333333333333,1.0,1.0,1.0,0.0,3.375922697804244,-0.0038296840273173405,0.5966402898536397,0.9972945700947634,0.015467529213228517,0.037502999452408196,0.061301069282120035,0.017685553363270858,0.0010058108298592466,-0.005505614399562458,-0.018368118754950195,-0.04034703855573064,-0.06814568120297494,-0.3858275512447897,-0.3104382704182977,-0.3195951598727258,-0.17071608519863057,0.3580433569597298,-0.9936368360543194,0.05846369244526503,-0.6210533849712252,0.7680715568584279,0.17038509000328658,-0.6188657983113119,0.9475650032323734,0.1333306053121719,0.13855322468345532,-0.13768233653702722,0.1021373574019313,0.03990404307060991,-0.007671481385207457,-0.021700600788754354,0.0022179571222036287,0.17973731927838577,-0.15542754674858605,-0.30638009587912407,0.6981490533750256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.741666666666667,1.0,1.0,1.0,0.0,3.376064294588918,-0.0038020120998774037,0.5965841044374939,0.9973194080672487,0.01539083620169029,0.037335070089657474,0.06101813706827549,0.01774674204452874,0.0009996389788881677,-0.005508163245219728,-0.01837734052056522,-0.04033184799336028,-0.06815910568324426,-0.3847166904381175,-0.30928308639693963,-0.3207421021054755,-0.16986500535782115,0.35837668549079993,-0.9937008577190144,0.05828257748004329,-0.6210334183290412,0.769567854269681,0.1690707229480263,-0.6213895473715584,0.9533240761733952,0.13327557464105189,0.1386891193653661,-0.13758176071797412,0.10212145242769033,0.04009351500942504,-0.007693147808709444,-0.021767439659193116,0.0025733457814713923,0.17937394621756475,-0.15998212090247488,-0.2992478560352829,0.6838809181112149,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.75,1.0,1.0,1.0,0.0,3.3762064321836456,-0.0037744164081319957,0.5965279028170288,0.9973441332177342,0.015314097333313766,0.037167198964825454,0.06073514410892996,0.017807223830340013,0.0009937221027289385,-0.005510726908945428,-0.01838643910296731,-0.040316250683387664,-0.06817271200407816,-0.3836062916674388,-0.3081267850955416,-0.32188818921802537,-0.1690140609915024,0.35871158220988686,-0.9937650551844646,0.05810090178427848,-0.6210104958748673,0.7710611226287206,0.16771872132157867,-0.6238532625785667,0.9589630185342269,0.13321972240933233,0.13882142163053945,-0.1374771639843697,0.10210484426765976,0.04028043544333948,-0.007713684135974841,-0.02183518404801965,0.0029273592088507883,0.17901037414206566,-0.16445728210006616,-0.2919741764278472,0.6693223314263497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.758333333333333,1.0,1.0,1.0,0.0,3.3763491045440195,-0.0037468961704446926,0.5964716857003017,0.9973687454961385,0.01523731304325828,0.0369993878072851,0.06045208965835108,0.01786701319695031,0.000988061740500962,-0.0055133069800091025,-0.01839540617868803,-0.04030026153794647,-0.06818650683158389,-0.3824963617312953,-0.30696939603643064,-0.32303338817188165,-0.16816325795336015,0.35904802608152225,-0.9938294191212806,0.05791865774590963,-0.6209846290088937,0.7725513605053821,0.16632976824635853,-0.6262557836453558,0.9644794483638344,0.1331630592359323,0.13895022282626845,-0.1373686489419046,0.10208753389647496,0.040464854060247024,-0.007733109065679589,-0.02190384958069405,0.003280008740100815,0.1786466568721501,-0.16884790387612592,-0.28456347851169905,0.6544825610440252,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.766666666666666,1.0,1.0,1.0,0.0,3.376492305729778,-0.0037194505682882862,0.5964154537669644,0.9973932448560722,0.01516048380430418,0.03683163828800235,0.06016897294230527,0.017926121834790015,0.0009826595272990932,-0.005515905189276415,-0.018404233859591744,-0.040283894858936575,-0.06820049610979843,-0.38138690734683994,-0.3058109480484371,-0.32417766670039044,-0.16731260209322782,0.3593859964442243,-0.9938939403355592,0.057735837624600245,-0.6209558290625323,0.7740385669099231,0.1649045895903099,-0.6285959872204283,0.969871061218294,0.13310559425340984,0.1390756006423144,-0.13725630139173828,0.10206952144354908,0.040646812574246516,-0.007751437201655165,-0.02197345126053532,0.0036313006468580156,0.1782828463376651,-0.17314885839428362,-0.27702020477543554,0.6393709419505522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.775,1.0,1.0,1.0,0.0,3.376636029886409,-0.003692078748554388,0.5963592076688828,0.9974176312545248,0.015083610124991804,0.03666395202148978,0.059885793161268706,0.017984559608202718,0.0009775170615419653,-0.005518523342209461,-0.01841291469553661,-0.040267164500612664,-0.06821468501958909,-0.38027793516040514,-0.30465146935905874,-0.3253209931950773,-0.16646209926263433,0.3597254729577597,-0.9939586097413082,0.05755243355823404,-0.6209241073314461,0.7755227412776765,0.16344395393978714,-0.6308727870582798,0.9751356307296769,0.13304733548418435,0.13919762361758514,-0.1371401958136631,0.10205080650367626,0.04082634758845849,-0.00776868041819645,-0.022044003185072436,0.003981238041306234,0.1779189926672653,-0.17735502591094854,-0.26934881782394227,0.6239968782060012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.783333333333333,1.0,1.0,1.0,0.0,3.3767802712336095,-0.0036647798259524917,0.5963029480306742,0.9974419046515686,0.015006692547778842,0.03649633056717832,0.05960254949380366,0.018042335261552828,0.0009726358039501633,-0.005521163271817232,-0.018421441682111916,-0.040250083992327094,-0.06822907793633172,-0.37916945175543687,-0.3034909876548107,-0.32646333663061816,-0.16561175531816655,0.3600664355706986,-0.9940234183425292,0.057368437571515704,-0.6208894750951772,0.7770038834543775,0.1619486724917941,-0.6330851341841607,0.980271009188394,0.13298829011184288,0.13931635444800583,-0.1370203993792607,0.10203138836434644,0.041003492711102485,-0.007784848863479077,-0.022115518315742322,0.0043298222717669255,0.17755514426173402,-0.18146130464484655,-0.26155379982570226,0.6083698443426311,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.791666666666666,1.0,1.0,1.0,0.0,3.376925024058788,-0.003637552885511123,0.5962466754501669,0.9974660650100756,0.014929731647188648,0.03632877543034827,0.05931924110010562,0.01809945693862904,0.0009680169998794739,-0.00552382680595454,-0.018429808272066167,-0.040232666630952006,-0.06824367838735615,-0.3780614636585411,-0.30232953011825864,-0.32760466651806497,-0.16476157612322856,0.36040886450294474,-0.9940883572223662,0.057183841586305004,-0.6208519436269166,0.7784819936820387,0.16041959886237303,-0.6352320170553748,0.9852751281353874,0.13292846467595432,0.13943185241211853,-0.13689697488598496,0.10201126617202572,0.041178280117377675,-0.0077999516941851255,-0.022188008286827682,0.004677053947073073,0.17719134785346258,-0.1854626210119581,-0.25363965217101603,0.5924993863110717,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8,1.0,1.0,1.0,0.0,3.3770702827142736,-0.003610396985188083,0.5961903904987975,0.9974901122954434,0.01485272802792955,0.03616128806272857,0.05903586712572289,0.018155932564737774,0.0009636616189915019,-0.005526515744739089,-0.01843800838929202,-0.040214925550018224,-0.068258489010214,-0.37695397734417097,-0.30116712344794205,-0.3287449528787179,-0.16391156754863279,0.3607527402393216,-0.9941534175374322,0.05699863743340191,-0.6208115241960593,0.7799570725852686,0.15885762880826146,-0.6373124617203443,0.9901459989602452,0.13286786521133132,0.1395441751445603,-0.13676998289570141,0.10199043905416705,0.041350741704738736,-0.007813997614938284,-0.022261483244785524,0.005022933685503439,0.1768276485521003,-0.1893539401869082,-0.24561089522395996,0.5763951219445862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.808333333333334,1.0,1.0,1.0,0.0,3.377216041617254,-0.0035833111585934453,0.5961340937219527,0.9975140464753253,0.014775682322970737,0.03599386986284804,0.058752426705444206,0.01821177012699267,0.0009595703079500226,-0.0055292318454137745,-0.018446036444466136,-0.04019687377072549,-0.0682735115123542,-0.37584699923835224,-0.3000037938658493,-0.3298841662329933,-0.16306173547232578,0.36109804353135705,-0.9942185905159485,0.05681281686555858,-0.6207682280654916,0.7814291211579071,0.1572636998592579,-0.6393255319757741,0.9948817135011305,0.1328064973462484,0.13965337992630444,-0.13663948328751174,0.10196890620908838,0.04152090994634983,-0.00782699527460684,-0.02233595171118971,0.005367462662018152,0.17646408987740836,-0.19313027695157858,-0.23747206808738097,0.5600667409217341,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.816666666666666,1.0,1.0,1.0,0.0,3.3773622952517064,-0.0035562944178255955,0.5960777856392625,0.9975378675193659,0.014698595191564912,0.035826522176205,0.058468918967349785,0.018266977878966615,0.0009557433531213878,-0.005531976812067441,-0.018453887351389905,-0.040178524239026785,-0.06828874663273278,-0.3747405357217335,-0.298839567115837,-0.33102227760017644,-0.1622120857784813,0.3614447554050941,-0.9942838674586757,0.05662637157154875,-0.6207220664850257,0.7828981407498921,0.15563879085906848,-0.6412703295218006,0.9994804446422741,0.1327443663712835,0.13975952462377594,-0.13650553638490215,0.10194666697149024,0.04168881851517536,-0.007838953552667949,-0.022411420464426846,0.005710643007206251,0.1761007137810222,-0.19678670679076193,-0.22922772832426608,0.5435240042159384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.825,1.0,1.0,1.0,0.0,3.3775090381717816,-0.003529345756416915,0.5960214667448619,0.9975615753989387,0.014621467317213444,0.03565924629530489,0.05818534303701654,0.018321564488873187,0.0009521806509633734,-0.005534752288972292,-0.018461556543780143,-0.040159889851154575,-0.06830419410637094,-0.3736345931321642,-0.29767446845545303,-0.33215925850607503,-0.16136262435613427,0.36179285717327664,-0.9943492397418263,0.056439293191151464,-0.6206730506820382,0.7843641330542575,0.1539839214127452,-0.6431459941145119,1.0039404469047295,0.13268147728654367,0.13986266835740002,-0.13636820375920733,0.10192372086086865,0.04185450273957558,-0.00784988176800061,-0.022487894437238642,0.00605247809470244,0.1757375606571765,-0.20031837719305057,-0.22088245158699893,0.5267767430221437,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.833333333333334,1.0,1.0,1.0,0.0,3.3776562650062303,-0.003502464152385751,0.5959651375076208,0.9975851700868866,0.014544299405567365,0.035492043459612814,0.05790169804186369,0.018375539145398263,0.0009488816845257442,-0.00553755985638868,-0.018469039991877035,-0.040140983469641296,-0.06831985263203365,-0.37252917776695776,-0.29650852264321365,-0.33329508099616323,-0.16051335709746684,0.36214233045075367,-0.9944146988214757,0.056251573330928104,-0.620621191850114,0.7858271000941783,0.1523001512391843,-0.6449517037149173,1.0082600570259765,0.13261783483316303,0.13996287197041046,-0.1362275487951914,0.10190006761704506,0.042017999930265004,-0.007859789829218755,-0.022565376627620287,0.006392972746755987,0.17537466934329782,-0.20372051911377698,-0.21244083113148848,0.509834857160274,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.841666666666667,1.0,1.0,1.0,0.0,3.3778039704635656,-0.0034756485713866255,0.5959087983713582,0.9976086515572626,0.014467092182266226,0.035324914855453686,0.05761798311562766,0.018428911631626275,0.000945845504963089,-0.00554040102778284,-0.01847633421833867,-0.040121817931956925,-0.06833571984353809,-0.3714242958849448,-0.29534175392261286,-0.33442971765266155,-0.1596642898958502,0.3624931571721144,-0.99448023623898,0.056063203580691126,-0.6205665011362589,0.7872870442099791,0.15058857942751558,-0.64668667463337,1.0124376945240674,0.13255344351371656,0.14006019834970296,-0.13608363708158544,0.10187570722594574,0.042179349606408234,-0.007868688338874552,-0.022643868022000635,0.006732133379461214,0.17501207711109856,-0.2069884585556936,-0.20390747719378766,0.4927083129572063,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.85,1.0,1.0,1.0,0.0,3.377952149337732,-0.0034488979699509297,0.5958524497550448,0.997632019785075,0.01438984639071375,0.035157861615890004,0.05733419740294792,0.018481692373933104,0.0009430707173066271,-0.005543277248028849,-0.018483436313214203,-0.040102406052343886,-0.06835179228538321,-0.3703199537083958,-0.29417418600405193,-0.33556314161418965,-0.15881542864370107,0.3628453196108605,-0.9945458436271236,0.055874175530561426,-0.620508989627123,0.78874396804603,0.1488503435965894,-0.6483501616681471,1.01647186224193,0.1324883076047234,0.1401547126295355,-0.135936536665634,0.10185063993856658,0.04233859364600967,-0.007876588665007844,-0.022723367530137206,0.007069968099613355,0.17464981964937065,-0.21011762822066737,-0.19528701621683187,0.4754071406133109,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.858333333333333,1.0,1.0,1.0,0.0,3.3781007965140852,-0.003422211298807334,0.5957960920530065,0.9976552747460318,0.014312562789794144,0.034990884820604695,0.0570503400640467,0.01853389247221925,0.0009405554698556011,-0.005546189892169311,-0.018490343947667694,-0.04008276061797783,-0.06836806539291063,-0.3692161574248661,-0.29300584204545393,-0.3366953265970888,-0.1579667792302074,0.3631988003995479,-0.9946115127167301,0.05568448078852217,-0.6204486683345987,0.7901978745374686,0.14708661895717112,-0.6499414582369839,1.0203611468676226,0.13242243116350805,0.14024648230570702,-0.13578631820496012,0.1018248662843757,0.04249577637452928,-0.007883502987209301,-0.02280387193060812,0.007406486766898812,0.17428793103870577,-0.2131035791840713,-0.18658408992274111,0.45794143106415497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.866666666666667,1.0,1.0,1.0,0.0,3.378249906975563,-0.0033955875062710353,0.5957397256351328,0.9976784164162905,0.014235242151531364,0.0348239854958105,0.05676641027948205,0.018585523714921438,0.0009382974468864123,-0.005549140264463865,-0.018497055386110038,-0.04006289438029051,-0.0683845334773848,-0.368112913189004,-0.29183674463229015,-0.33782624691760565,-0.15711834753896148,0.36355358255043596,-0.9946772353435771,0.055494110998384624,-0.620385548181008,0.7916487668966751,0.1452986172768549,-0.6514598965001928,1.0241042194263326,0.1323558180309048,0.14033557728001855,-0.13563305504043055,0.10179838708046451,0.04265094460325858,-0.007889444322073391,-0.02288537582725944,0.007741701028967096,0.17392644371979404,-0.2159419925428735,-0.17780335422710847,0.4403213323491739,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.875,1.0,1.0,1.0,0.0,3.378399475808908,-0.0033690255416883716,0.5956833508471006,0.9977014447722089,0.014157885258698471,0.034657164614206,0.05648240725495403,0.01863659858152397,0.000936293864492968,-0.005552129597409327,-0.018503569496455655,-0.04004282004196756,-0.06840118971635716,-0.367010227124351,-0.2906669157574536,-0.3389558775144293,-0.156270139445533,0.36390964947626886,-0.9947430034554313,0.05530305785806785,-0.6203196399841159,0.7930966485994652,0.14348758574812323,-0.6529048474741024,1.0276998357401088,0.1322884718320405,0.14042206985047767,-0.13547682320846244,0.10177120343779433,0.04280414762918072,-0.007894426533530119,-0.02296787161678776,0.008075624333914178,0.17356538845497482,-0.2186286909865831,-0.1689494779979661,0.4225570455054495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.883333333333333,1.0,1.0,1.0,0.0,3.378549498210871,-0.0033425243589229547,0.59562696801062,0.9977243597901007,0.014080492902381926,0.03449042309499586,0.05619833022614009,0.018687130235965188,0.0009345414691920694,-0.005555159050732086,-0.018509885758432387,-0.04002255023999634,-0.06841802614972811,-0.3659081053251367,-0.28949637680144885,-0.34008419397108003,-0.15542216081499824,0.3642669850109223,-0.9948088091191359,0.05511131313810483,-0.6202509544421094,0.7945415233709247,0.14165480576041184,-0.6542757211334922,1.0311468368514234,0.13222039597504232,0.14050603465212586,-0.13531770140067234,0.10174331676476855,0.04295543719939232,-0.007898464331019817,-0.02305134946712667,0.008408271925173239,0.1732047942860837,-0.22115965023897954,-0.16002714166204024,0.40465882000366715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.891666666666666,1.0,1.0,1.0,0.0,3.3786999694943054,-0.0033160829198686658,0.5955705774237082,0.9977471614459961,0.014003065879508806,0.034323761803992436,0.0559141784635361,0.018737132510701006,0.0009330365394725911,-0.005558229710196277,-0.018516004269487064,-0.04000209752555808,-0.06843503368142784,-0.3648065538581003,-0.28832514851325153,-0.34121117253777383,-0.15457441749945353,0.36462557342959206,-0.994874644527615,0.054918868700282404,-0.6201795021186963,0.7959833951708999,0.13980159157747357,-0.655571966501803,1.0344441494068366,0.13215159364911577,0.14058754856574818,-0.1351557708879969,0.10171472876824517,0.04310486744498965,-0.007901573255451044,-0.023135797307261563,0.008739660820871187,0.17284468848801637,-0.2235310103187499,-0.15104103566746074,0.38663694875031407,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9,1.0,1.0,1.0,0.0,3.3788508850940877,-0.003289700197972595,0.5955141793609993,0.9977698497154074,0.013925604990345994,0.03415718155380967,0.055629951277279335,0.018786619884154882,0.0009317748899743384,-0.0055613425862509015,-0.01852192574844188,-0.039981474340670384,-0.06845220208732199,-0.3637055787643181,-0.2871532509920197,-0.34233679015254664,-0.1537269153355275,0.3649853994683388,-0.9949405020067268,0.054725716516317136,-0.6201052934284282,0.7974222681790583,0.137929288921766,-0.6567930717279499,1.037590785997262,0.1320820678226231,0.14066669058957593,-0.13499111540594133,0.10168544145330694,0.043252494790707585,-0.007903769658450521,-0.02322120082832918,0.00906980978234051,0.1724850965186886,-0.22573908656549402,-0.14199585880704912,0.36850176267833934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.908333333333333,1.0,1.0,1.0,0.0,3.3790022405728135,-0.003263375181752729,0.5954577740740931,0.9977924245731016,0.013848111035977976,0.033990683104167224,0.05534564802192491,0.018835607452028544,0.0009307518783460865,-0.005564498612386962,-0.01852765153643461,-0.03996069299241893,-0.06846952002922703,-0.3626051860610566,-0.28598070367009193,-0.3434610244612062,-0.1528796601418984,0.3653464483427705,-0.9950063740219225,0.05453184868647692,-0.620028338622324,0.7988581467795447,0.13603927346804867,-0.6579385641485872,1.0405858454514756,0.13201182124091826,0.14074354168572945,-0.13482382101398183,0.10165545712110646,0.043398377840790925,-0.00790507067340629,-0.023307543496664668,0.009398739269381728,0.17212604196866987,-0.2277803803787326,-0.13289631641431487,0.3502636249543478,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.916666666666666,1.0,1.0,1.0,0.0,3.3791540316262094,-0.003237106878291373,0.5954013617919526,0.9978148859928798,0.013770584815776695,0.0338242671623089,0.05506126810115289,0.018884110892410072,0.0009299624148406569,-0.0055676986434538235,-0.018533183595088373,-0.03993976562510356,-0.06848697507512858,-0.3615053817436361,-0.28480752529725756,-0.344583853836113,-0.15203265771684238,0.3657087057656853,-0.9950722531846169,0.05433725745803939,-0.6199486477739385,0.8002910355452028,0.13413294924878713,-0.6590080103348551,1.0434285130798344,0.1319408564249247,0.14081818460558782,-0.13465397593277584,0.10162477836508921,0.04354257724407229,-0.007905494179236694,-0.023394806578568017,0.009726471386266589,0.1717675465094448,-0.22965158961705534,-0.12374711844305164,0.3319329248322367,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.925,1.0,1.0,1.0,0.0,3.379306254088219,-0.0032108943166877435,0.595344942721348,0.9978372339473657,0.013693027124870737,0.03365793438355076,0.05477681097237649,0.018932146426531574,0.0009294009743840482,-0.005570943453653143,-0.01853852450201866,-0.03991870419017373,-0.06850455372589574,-0.3604061717873078,-0.28363373392666547,-0.3457052573934191,-0.1511859138358136,0.36607215796350506,-0.9951381322582431,0.054141935243500784,-0.6198662307658862,0.8017209392213688,0.13221174697443108,-0.6600010161226381,1.0461180608653462,0.13186917567040934,0.14089070369022183,-0.13448167035573944,0.10159340806627393,0.04368515554079799,-0.007905058759423156,-0.02348296917700804,0.010053029818142267,0.1714096298428136,-0.23134961860529935,-0.11455297744081161,0.3135200711823982,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.933333333333334,1.0,1.0,1.0,0.0,3.379458903935725,-0.003184736551451366,0.5952885170473586,0.9978594684078038,0.013615438751626376,0.033491685371963696,0.05449227615122642,0.018979730774582794,0.000929061611282435,-0.005574233734401585,-0.018543677443305703,-0.03989752041499843,-0.06852224144820884,-0.3593075621491293,-0.2824593469024205,-0.34682521500870866,-0.15033943424907115,0.3664367916913653,-0.9952040041639406,0.05394587463842259,-0.6197810972769695,0.8031478627092496,0.13027712227203214,-0.6609172266255353,1.048653847599541,0.1317967810480225,0.14096118465491636,-0.13430699624422449,0.10156134938688943,0.04382617699082547,-0.007903783654841234,-0.023572008280509094,0.010378439758662594,0.17105230965136498,-0.23287158769894512,-0.10531860642780888,0.29503548573044824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.941666666666666,1.0,1.0,1.0,0.0,3.37961197729286,-0.003158632665817706,0.5952320849339298,0.9978815893438672,0.01353782047515146,0.033325520681197415,0.054207663215883814,0.0190268811076701,0.0009289379763767185,-0.00557757009229806,-0.018548646203052743,-0.039876225770307604,-0.0685400227138266,-0.3582095587698408,-0.2812843808490835,-0.34794370733082286,-0.14949322467936543,0.3668025942466855,-0.9952698619858238,0.05374906843882563,-0.6196932567699085,0.8045718110488915,0.12833055384611533,-0.6617563262297682,1.0510353189608537,0.1317236744044603,0.14102971435602352,-0.13413004710395748,0.10152860576293721,0.04396570738734895,-0.007901688712854682,-0.02366189882373887,0.010702727830258496,0.17069560155201335,-0.2342148423561513,-0.09604871669711912,0.27648959604141155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.95,1.0,1.0,1.0,0.0,3.3797654704348865,-0.0031325817749684095,0.5951756465244886,0.9979035967234775,0.013460173062833621,0.033159440815451725,0.053922971811235725,0.019073614995436864,0.0009290233366952686,-0.005580953046835734,-0.018553435149921325,-0.03985483143698421,-0.06855788104496786,-0.3571121675757216,-0.28010885166315347,-0.3490607157937746,-0.14864729081968886,0.36716955348115443,-0.9953356989758215,0.05355150965802694,-0.6196027184797985,0.8059927894017832,0.1263735415660963,-0.6625180385704873,1.0532620075335646,0.13164985736497936,0.14109638054570217,-0.13395091774848877,0.10149518089551002,0.044103813856466445,-0.007898794330820635,-0.023752613760271435,0.011025921994642918,0.1703395190531598,-0.23537696166974154,-0.086748015545981,0.25789282828288407,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.958333333333334,1.0,1.0,1.0,0.0,3.3799193797915885,-0.0031065830291375023,0.5951192019426236,0.9979254905126371,0.013382497267925203,0.03299344623059659,0.053638201652827594,0.019119950350841925,0.0009293105973840138,-0.00558438302820348,-0.01855804922067128,-0.03983334827246057,-0.06857579906564917,-0.35601539448042446,-0.27893277450665516,-0.350176222626631,-0.14780163833110693,0.36753765781095993,-0.9954015085580041,0.05335319154282111,-0.6195094914033311,0.8074108030331109,0.12440760448495297,-0.6632021264888679,1.0553335327655684,0.1315753313365775,0.14116127161369452,-0.13376970404924915,0.1014610787407666,0.04424056464106263,-0.00789512139507842,-0.023844124146819023,0.011348051456701036,0.1699840735174818,-0.23635576631343969,-0.07742120395410668,0.23925559980691347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.966666666666667,1.0,1.0,1.0,0.0,3.3800737019501828,-0.0030806356165864503,0.5950627512928234,0.9979472706752748,0.01330479382718629,0.032827537335444384,0.053353352530587955,0.019165905371761247,0.0009297923258455606,-0.005587860375220183,-0.0185624939008937,-0.0398117867767322,-0.06859375855891381,-0.35491924538677866,-0.2777561638029252,-0.3512902108612621,-0.14695627284067608,0.36790689622517214,-0.9954672843324062,0.05315410758891329,-0.6194135842888535,0.8088258572937412,0.12243427879420563,-0.6638083919697224,1.0572496008636798,0.1315000975128633,0.14122447631499724,-0.13358650266951932,0.1014263034994034,0.04437602887736092,-0.007890691218912504,-0.023936399238457112,0.011669146561978927,0.16962927412897955,-0.23714932585945064,-0.06807297422356973,0.22058831158918046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.975,1.0,1.0,1.0,0.0,3.380228433657686,-0.0030547387664309564,0.5950062946612792,0.9979689371731049,0.013227063458596817,0.032661714493175696,0.0530684243123002,0.019211498479209985,0.0009304607780919317,-0.005591385333291591,-0.01856677520264587,-0.0397901570591118,-0.06861174052932856,-0.3538237261885434,-0.27657903323473854,-0.35240266433778966,-0.1461111999394502,0.3682772582922493,-0.9955330200783193,0.05295425155551349,-0.6193150056272981,0.8102379576019272,0.1204551157206288,-0.6643366760592607,1.059010004625388,0.1314241568800445,0.1412860834935259,-0.1334014107931203,0.10139085960438443,0.044510276358739054,-0.007885525474480293,-0.02402940659510175,0.011989238686052062,0.16927512786755639,-0.2377559654272826,-0.05870800759054218,0.2019013405616521,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.983333333333333,1.0,1.0,1.0,0.0,3.3803835718227413,-0.0030288917513025125,0.5949498321167488,0.9979904899655025,0.013149306859152226,0.03249597802291281,0.052783416946801845,0.019256748253847208,0.0009313079269679821,-0.005594958052604245,-0.018570899639378583,-0.03976846880532743,-0.06862972527069482,-0.35272884277211125,-0.2754013957446998,-0.3535135677078141,-0.145266425180603,0.36864873416448446,-0.9955987097569808,0.05275361747899493,-0.619213763644086,0.8116471094248672,0.11847167937041758,-0.6647868587628981,1.060614623206374,0.13134751022400915,0.1413461817973094,-0.1332145258433115,0.10135475170786667,0.044643377290275454,-0.007879646121908834,-0.024123112198163738,0.012308360118098438,0.1689216394910864,-0.23817427162717203,-0.0493309718280055,0.18320503188291148,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.991666666666667,1.0,1.0,1.0,0.0,3.3805391135168708,-0.0030030938898300027,0.5948933637114797,0.9980119290093934,0.013071524702750355,0.032330328201445054,0.05249833046688673,0.01930167337026685,0.0009323254921925132,-0.005598578586559953,-0.018574874198243357,-0.03974673124548932,-0.06864769243856574,-0.35163460101814326,-0.2742232635381167,-0.3546229064351782,-0.14442195407765243,0.36902131458042053,-0.9956643475136845,0.052552199685544095,-0.6191098662919965,0.813053318260112,0.1164855445268426,-0.6651588589230608,1.0620634218234366,0.13127015813886533,0.1414048593861239,-0.1330259451918936,0.1013179846674328,0.04477540203845942,-0.00787307533732573,-0.02421748057661363,0.012626543938836221,0.16856881152442327,-0.23840309776415658,-0.039946518850200174,0.16450969118404046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0,1.0,1.0,1.0,0.0,3.3806950559751474,-0.00297734454892602,0.5948368894821912,0.998033254259161,0.012993717638183619,0.03216476526509595,0.052213164991893914,0.019346292529446547,0.0009335049720375322,-0.005602246890375295,-0.018578706309787925,-0.039724953123508516,-0.06866562112691788,-0.35054100680313016,-0.2730446480882644,-0.3557306667943457,-0.14357779210281246,0.36939499086512545,-0.9957299276792696,0.052349992802718036,-0.6190033212451054,0.8144565896169409,0.11449829440768164,-0.6654526340770681,1.0633564513927747,0.1311921010365169,0.14146220363774442,-0.13283576586501367,0.10128056353128301,0.044906420874190056,-0.007865835437959046,-0.024312474942179002,0.012943823892459516,0.16821664425822114,-0.23844156827395518,-0.030559282332696114,0.14582557682955688,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.008333333333333,1.0,1.0,1.0,0.0,3.3808513965962614,-0.002951643145865395,0.594780409451112,0.998054465666569,0.012915886287244552,0.03199928941173106,0.051927920729964,0.019390624390114315,0.0009348376764089959,-0.005605962820039284,-0.018582403815300165,-0.03970314266790566,-0.06868348994875677,-0.349448066000868,-0.2718655601441543,-0.35683683586626175,-0.14273394468546438,0.3697697549283237,-0.9957954447709838,0.05214699176984111,-0.6188941358937888,0.815856928997749,0.11251151838894334,-0.6656681802952724,1.0644938481039292,0.13111333915741819,0.14151830085218475,-0.13264408424491725,0.10124249352248926,0.04503650371140866,-0.007857948804259607,-0.02440805733272433,0.01326023425457068,0.167865135755616,-0.23828908236499136,-0.021173875362479055,0.12716289223549282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.016666666666666,1.0,1.0,1.0,0.0,3.381008132941986,-0.0029259891501430056,0.5947239236270706,0.998075563180703,0.012838031242956712,0.03183390080289699,0.05164259797994881,0.01943468749901457,0.0009363147611739701,-0.005609726131695529,-0.018585974931982847,-0.03968130756453146,-0.06870127711989156,-0.34835578448383986,-0.270686009740728,-0.35794140153176096,-0.14189041721077097,0.3701455992603156,-0.9958608934926739,0.05194319184717263,-0.6187823173408625,0.8172543418795345,0.11052680970159845,-0.6658055319997761,1.065475832930033,0.13103387258246113,0.14157323595705984,-0.1324509957706943,0.10120378002270669,0.04516571984497508,-0.007849437802549541,-0.024504188762569518,0.013575809695069996,0.16751428186926542,-0.23794531684538517,-0.011794888132801162,0.10853177828319627,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.025,1.0,1.0,1.0,0.0,3.381165262736017,-0.0029003820851008695,0.5946674320066326,0.998096546747928,0.012760153067937872,0.03166859956608582,0.05135719713296132,0.019478500221171945,0.0009379272633996398,-0.00561353648121384,-0.01858942821624543,-0.039659454931195846,-0.06871896054558975,-0.3472641681244936,-0.26950600621153664,-0.35904435246244,-0.14104721501841927,0.37052251692573995,-0.9959262687343596,0.051738588623798286,-0.618667872398871,0.8186488336955701,0.10854576310818692,-0.6658647617641524,1.0663027110753158,0.13095370124596495,0.1416270922120988,-0.13225659463526496,0.10116442855554353,0.04529413768657564,-0.007840324705192803,-0.02460082937914082,0.01389058513889374,0.1671640762669413,-0.2374102281184079,-0.002426885692614622,0.08994230586795826,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.033333333333333,1.0,1.0,1.0,0.0,3.3813227838622146,-0.002874821529315266,0.5946109345752848,0.9981174163118642,0.01268225229290527,0.03150338579711528,0.051071718673554325,0.019522080669700362,0.0009396661374194112,-0.005617393424223131,-0.018592772525137465,-0.03963759129484193,-0.06873651790927995,-0.3461732227964071,-0.26832555820385967,-0.3601456781090154,-0.14020434340151192,0.37090050155509185,-0.9959915655710938,0.05153317802418695,-0.6185508075885476,0.8200404098173169,0.10656997256629165,-0.665845980094653,1.0669748713611655,0.1308728249494484,0.14167995092263075,-0.1320609734898759,0.10112444476866211,0.04542182450205989,-0.007830631610266092,-0.02469793862495545,0.014204595622901994,0.16681451046736795,-0.23668405333442055,0.00692559423468353,0.07140446862092809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.041666666666666,1.0,1.0,1.0,0.0,3.381480694362207,-0.0028493071177359735,0.5945544313086569,0.9981381718133816,0.012604329415330046,0.03133825956261337,0.050786163180521676,0.019565446636189313,0.0009415222913553571,-0.005621296416623682,-0.018596016976513686,-0.0396157225709201,-0.0687539267628462,-0.34508295437533615,-0.26714467369615946,-0.36124536868727125,-0.13936180760560823,0.3712795473341076,-0.9960567792611974,0.05132695631338236,-0.6184311291384893,0.8214290755366929,0.10460102888594658,-0.6657493351935744,1.0674927855523313,0.1307912433762748,0.14173189115445295,-0.1318642231472278,0.1010838344164694,0.045548846153526945,-0.00782038036310162,-0.024795475403309036,0.014517876151793896,0.16646557388551253,-0.23576731069174822,0.01625804335242398,0.05292817584003462,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.05,1.0,1.0,1.0,0.0,3.381638992432408,-0.0028238385425727163,0.5944979221737787,0.9981588131906111,0.012526384898245745,0.031173220902600624,0.05050053132731455,0.019608615522400494,0.0009434866238514953,-0.0056252448153278145,-0.018599170907936932,-0.03959385404546281,-0.06877116461789332,-0.34399336874013586,-0.2659633600179521,-0.3623434151614692,-0.1385196128279041,0.37165964899098397,-0.9961219052438122,0.051119920100798466,-0.6183088429860177,0.8228148360487421,0.10264051738809585,-0.665575012705446,1.067857007625166,0.13070895610735933,0.1417829894571021,-0.13166643229006847,0.10104260334209636,0.04567526684350676,-0.007809592476257787,-0.024893398247193,0.01483046155292378,0.16611725388710807,-0.23466079888430025,0.025565984800111075,0.034523245666511215,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.058333333333334,1.0,1.0,1.0,0.0,3.38179767642042,-0.0027984155539238884,0.5944414071303668,0.9981793403789734,0.012448419169218284,0.031008269833153936,0.05021482388207166,0.019651604272448962,0.0009455500609027515,-0.00562923787955311,-0.0186022438346231,-0.039571990360103074,-0.06878820903725949,-0.3429044717735468,-0.2647816238718744,-0.36343980922543906,-0.1376777642165733,0.3720408017814994,-0.9961869391358017,0.05091206634259581,-0.6181839547792739,0.8241976964348113,0.10069001557120824,-0.6653232354469059,1.0680681729801065,0.130625962637263,0.14183331959987555,-0.13146768719158652,0.10100075745905601,0.04580114886694853,-0.007798289051221818,-0.024991665489958043,0.015142386330091462,0.1657695358527489,-0.23336559569837517,0.03484497505879869,0.016199398541889565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.066666666666666,1.0,1.0,1.0,0.0,3.381956744820857,-0.0027730379601459154,0.5943848861321336,0.9981997533112269,0.01237043261948001,0.030843406349143385,0.049929041707262055,0.019694429307339976,0.0009477035923608889,-0.00563327477241792,-0.018605245406857835,-0.03955013549985284,-0.06880503772623865,-0.34181626936284815,-0.2635994713579542,-0.36453454328132895,-0.13683626687025316,0.3724230014720998,-0.9962518767279992,0.0507033923426325,-0.6180564698805162,0.8255776616462879,0.09875109079312293,-0.6649942631211326,1.0681269976008643,0.13054226239087252,0.1418829523162124,-0.13126807144140384,0.10095830273339435,0.045926552371036156,-0.007786490701737758,-0.025090235436482644,0.015453684519683986,0.16542240325011948,-0.2318830557650295,0.04409060574670054,-0.0020337490257604784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.075,1.0,1.0,1.0,0.0,3.382116196270599,-0.002747705627962264,0.5943283591281168,0.9982200519175303,0.012292425603231688,0.030678630427027023,0.04964318575894398,0.019737106461684865,0.0009499383079084494,-0.005637354562943881,-0.018608185367137643,-0.03952829278381162,-0.06882162862281607,-0.3407287674003656,-0.26241690799993755,-0.3656276104161291,-0.1359951258376834,0.37280624432101667,-0.9963167139808307,0.05049389575198777,-0.6179263933706125,0.82695473648898,0.09682529797512442,-0.6645883920177942,1.0680342771630105,0.13045785474083638,0.14193195506186695,-0.13106766568285577,0.10091524516562311,0.046051535123706744,-0.007774217479126211,-0.025189066533648774,0.015764389548249547,0.16507583771462997,-0.23021480748056183,0.053298505291159426,-0.02016669035354468,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.083333333333334,1.0,1.0,1.0,0.0,3.3822760295434966,-0.002722418482314352,0.594271826064018,0.9982402361255234,0.012214398437113135,0.030513942027693402,0.04935725708564431,0.01977965092281304,0.0009522454323024861,-0.005641476228406321,-0.018611073507250265,-0.039506464858794416,-0.06883795998642955,-0.3396419717838342,-0.26123393877358975,-0.3667190043760432,-0.13515434611749277,0.3731905270574949,-0.996381447019318,0.050283574567071686,-0.617793730054712,0.8283289256081984,0.09491417733511356,-0.6641059546996133,1.0677908860949719,0.13037273902521407,0.1419803917869944,-0.13086654736360392,0.10087159077330043,0.046176152294226114,-0.007761488799795657,-0.02528811753920973,0.01607453409154358,0.16472981913788542,-0.22836274911128468,0.06246434047101346,-0.03819003410607369,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.091666666666667,1.0,1.0,1.0,0.0,3.3824362435445567,-0.0026971765059564715,0.5942152868835506,0.998260305860423,0.01213635139984466,0.03034934109933693,0.04907125682686619,0.01982207717276354,0.0009546163596388481,-0.005645638657003959,-0.018613919625654077,-0.03948465369614284,-0.06885401048446563,-0.33855588841661205,-0.260050568136821,-0.36780871953885586,-0.13431393265812838,0.37357584685925377,-0.9964460721274939,0.05007242712633427,-0.6176584844690868,0.8297002334746114,0.093019252156603,-0.6635473196766106,1.067397776594576,0.13028691456524855,0.14202832272548593,-0.1306647905015701,0.10082734557374629,0.04630045624576473,-0.0077483233762176695,-0.025387347687631234,0.016384149938557524,0.16438432576296957,-0.22632904410298804,0.07158381782220502,-0.05609450942430705,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1,1.0,1.0,1.0,0.0,3.3825968373036273,-0.0026719797388004953,0.5941587415297868,0.9982802610451345,0.012058284732037225,0.03018482758035328,0.04878518621123599,0.01986439893401417,0.0009570426863294542,-0.005649840650883882,-0.018616733485487858,-0.0394628605913072,-0.0688697592760461,-0.33747052320774673,-0.2588668000614983,-0.3688967508844027,-0.13347389035793034,0.37396220132825764,-0.9965105857422549,0.049860452105611165,-0.6175206608890694,0.8310686643709145,0.09114202660006376,-0.6629128910692432,1.0668559776045667,0.13020038068351503,0.14207580420112387,-0.13046246546576157,0.10078251556751239,0.046424496341636035,-0.007734739150973002,-0.02548671685176626,0.016693267860270478,0.16403933428542405,-0.22411611562069889,0.08065268489707345,-0.07387097063550563,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.108333333333333,1.0,1.0,1.0,0.0,3.3827578099686235,-0.002646828277016367,0.5941021899464994,0.998300101600377,0.011980198636170676,0.03002040140224324,0.048499046554301116,0.019906629118683627,0.0009595162426617619,-0.0056540809293240905,-0.018619524773461904,-0.03944108616640943,-0.06888518609256658,-0.3363858820718868,-0.25768263806680225,-0.3699830939632852,-0.1326342240653365,0.3743495884649477,-0.9965749844466768,0.04964764851213817,-0.6173802633380823,0.8324342223793685,0.08928398356292469,-0.6622031082616594,1.0661665937506508,0.130113136722243,0.14212288845166232,-0.1302596387747157,0.10073710672254821,0.04654831876659604,-0.007720753235107569,-0.025586185699463526,0.017001917482990514,0.16369481995983648,-0.22172664034764145,0.08966673137592585,-0.09151040152714618,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.116666666666667,1.0,1.0,1.0,0.0,3.3829191607983216,-0.002621722271897079,0.5940456320794955,0.9983198274448228,0.011902093276735996,0.029856062492510396,0.04821283925599426,0.019948779781838056,0.0009620291226911772,-0.005658358132227099,-0.018622303059882703,-0.03941933037559129,-0.06890027131440046,-0.3353019709290427,-0.2564980852539706,-0.3710677448639813,-0.1317949385792212,0.37473800664103424,-0.99663926496284,0.04943401567728677,-0.6172372955976863,0.8337969113702451,0.08744658259426974,-0.6614184455463111,1.065330804245781,0.13002518206117197,0.14216962347354145,-0.1300563729149351,0.10069112495907473,0.04667196636447324,-0.007706381850598465,-0.025685715843903473,0.01731012716872371,0.16335075671051857,-0.21916354157626466,0.0986217900215336,-0.1090039191646408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.125,1.0,1.0,1.0,0.0,3.383080889154761,-0.0025966619284974388,0.5939890678779317,0.9983394384952491,0.011823968780538808,0.029691810777542363,0.047926565797780665,0.01999086207930449,0.0009645737122788271,-0.005662670823727765,-0.01862507776012012,-0.03939759251303476,-0.06891499604334647,-0.3342187957042006,-0.2553131443422432,-0.37215070017853413,-0.13095603864935193,0.37512745457102226,-0.9967034241441868,0.04921955324807311,-0.6170917612186035,0.8351567349912105,0.08563125786998695,-0.6605594117613005,1.0643498617645735,0.12993651613566026,0.14221605288687877,-0.129852726178874,0.10064457613561062,0.04679547849147925,-0.007691640276523692,-0.025785269986839943,0.017617923902297772,0.16300711724564154,-0.21642998162758192,0.10751373747506232,-0.12634277723869936,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.133333333333333,1.0,1.0,1.0,0.0,3.383242994495295,-0.0025716475040581457,0.5939324972956125,0.9983589346666999,0.01174582523715751,0.02952764618546199,0.047640227739507456,0.02003288622987606,0.0009671427151200539,-0.005667017495964322,-0.01862785809781254,-0.03937587122356355,-0.06892934217036362,-0.3331363623267817,-0.25412781770585596,-0.37323195696696254,-0.13011752897696102,0.3755179312825589,-0.9967674589674488,0.04900426117750611,-0.616943663532648,0.8365136966576725,0.08383941623381004,-0.6596265499217268,1.0632250912918026,0.12984713845447748,0.14226221582139043,-0.1296487525235812,0.10059746603595932,0.04691889088941359,-0.007676542802639297,-0.025884812053656725,0.01792533318699885,0.16266387317364295,-0.21352935363863873,0.11633849488970505,-0.1435183689308639,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.141666666666666,1.0,1.0,1.0,0.0,3.3834054763643273,-0.002546679306227526,0.5938759202922609,0.9983783158726601,0.01166766269955087,0.02936356864893872,0.047353826715975676,0.020074861482402635,0.0009697291766213713,-0.005671396572893169,-0.01863065306988554,-0.039354164515593495,-0.06894329243824403,-0.3320546767299593,-0.2529421074118867,-0.3743115127205938,-0.12927941421541927,0.3759094360858458,-0.9968313665242308,0.0487881397138455,-0.6167930056654869,0.8378677995441045,0.08207243530934297,-0.6586204368464721,1.061957888949059,0.129757048617114,0.14230814682484105,-0.1294445014525214,0.10054980035739014,0.04704223557638776,-0.0076611026866335585,-0.025984307319666528,0.018232378948901395,0.16232099512069276,-0.21046527276037202,0.12509202839953382,-0.16052222928798265,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.15,1.0,1.0,1.0,0.0,3.383568334384781,-0.0025217576910943713,0.5938193368347632,0.9983975820252374,0.01158948118480763,0.029199578107948453,0.04706736443325698,0.020116796088132032,0.000972326505449736,-0.0056758064141627556,-0.01863347141375656,-0.0393324697763479,-0.06895683049886586,-0.3309737448498298,-0.2517560152587753,-0.37538936532450456,-0.12844169897100452,0.37630196854216535,-0.996895144012226,0.048571189388845,-0.6166397905501663,0.8392190465763507,0.08033166168780384,-0.6575416827817345,1.0605497208036696,0.1296662463308873,0.14235387579353942,-0.12924001792011475,0.10050158469998183,0.04716554075515855,-0.007645332116950065,-0.026083722526693137,0.018539083450397342,0.16197845284869228,-0.2072415668105121,0.1337703494234299,-0.177346037099122,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.158333333333333,1.0,1.0,1.0,0.0,3.383731568249348,-0.0024968830610469024,0.5937627468983788,0.9984167330353515,0.011511280675029914,0.029035674512472704,0.04678084266477848,0.02015869727802553,0.0009749284926896687,-0.005680245318908912,-0.018636321576863537,-0.039310783788958956,-0.06896994096472811,-0.3298935726244445,-0.25056954281532773,-0.3764655130192624,-0.1276043878037529,0.3766955284317651,-0.9969587887261799,0.04835341100506728,-0.6164840209413136,0.840567440424916,0.07861840919583443,-0.6563909310227483,1.0590021216640737,0.12957473142733544,0.14239942792565574,-0.129035342259195,0.10045282455755311,0.04728883074352708,-0.007629242182798368,-0.026183025989522518,0.01884546721346414,0.16163621537256034,-0.20386226642891414,0.14236951480173454,-0.19398161627218524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.166666666666666,1.0,1.0,1.0,0.0,3.3838951777115565,-0.0024720558624732195,0.5937061504679177,0.9984357688129316,0.011433061118341708,0.028871857825128574,0.04649426324720065,0.020200571245637556,0.000977529328486826,-0.005684711529549677,-0.01863921168868342,-0.0392891027514314,-0.06898260945460409,-0.3288141659927075,-0.24938269146001435,-0.3775399543621578,-0.12676748522837863,0.37709011572122414,-0.997022298048606,0.04813480562235296,-0.6163256994299419,0.8419129834992267,0.07693395724732194,-0.655168857535039,1.0573166938657999,0.12948250387838756,0.14244482369704603,-0.12883051013250824,0.10040352530975238,0.04741212592162758,-0.007612842848720991,-0.026282187691529235,0.019151548953877384,0.1612942510749682,-0.20033159478379914,0.15088562676841777,-0.2104209367092924,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.175,1.0,1.0,1.0,0.0,3.384059162576716,-0.0024472765833196677,0.593649547538876,0.9984546892671177,0.011354822430012665,0.028708128023720338,0.04620762807611291,0.020242423134889,0.0009801236162028013,-0.0056892032354138354,-0.01864214953527746,-0.03926742229731875,-0.06899482263304144,-0.32773553089313806,-0.24819546242037696,-0.37861268818813754,-0.12593099571525704,0.3774857305304589,-0.9970856694403253,0.04791537454354179,-0.616164828458749,0.8432556779428322,0.07527954928277111,-0.653876170576608,1.0554951060522522,0.129389563811515,0.14249007886069254,-0.12862555250952146,0.10035369221568613,0.04753544270103216,-0.007596142937080774,-0.0263811793691264,0.019457345525855096,0.16095252781946234,-0.19665395687911202,0.15931483275881897,-0.22665611468355884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.183333333333334,1.0,1.0,1.0,0.0,3.3842235226927677,-0.0024225457505235473,0.593592938118535,0.9984734943064659,0.011276564493688223,0.02854448510370554,0.04592093910157392,0.020284257033766132,0.0009827063838880128,-0.005693718576148147,-0.01864514253670003,-0.039245737517429116,-0.06900656824368259,-0.3266576732625156,-0.24700785681233614,-0.37968371357064984,-0.12509492369145053,0.3778823730995747,-0.9971489004308907,0.04769511929953418,-0.6160014103378443,0.8445955256295511,0.07365639129933674,-0.652513610322392,1.0535390919544072,0.12929591152439301,0.14253520446735224,-0.12842049566607616,0.10030333040915024,0.04765879351221414,-0.007579150115377686,-0.026479974584684013,0.019762871878659105,0.1606110130596572,-0.1928339285140948,0.167653325056083,-0.2426794127234677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.191666666666666,1.0,1.0,1.0,0.0,3.3843882579411164,-0.002397863927338565,0.5935363222270155,0.9984921838391583,0.01119828716271316,0.028380929080572045,0.045634198323522064,0.02032607597335422,0.0009852730931615278,-0.00569825564506198,-0.018648197727231062,-0.039224042982836806,-0.06901783513629153,-0.3255805990343982,-0.24581987567925442,-0.38075302978257214,-0.1242592735417712,0.3782800437556625,-0.9972119886089149,0.04747404163379706,-0.6158354472607713,0.8459325281604931,0.07206565047420287,-0.6510819484923399,1.0514504491735277,0.12920154749893942,0.14258020690879059,-0.12821536120803279,0.10025244489519441,0.047782186811126115,-0.007561870891059641,-0.02657854878766963,0.020068141023894537,0.1602696739428855,-0.1888762449467682,0.17589734027866344,-0.2584832390110847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2,1.0,1.0,1.0,0.0,3.3845533682274587,-0.002373231710569238,0.59347969989829,0.998510757773211,0.011119990261539878,0.028217459992116643,0.04534740778708362,0.02036788193187295,0.000987819645520677,-0.005702812492043489,-0.01865132173839785,-0.039202332768820965,-0.06902861328748477,-0.3245043141375333,-0.24463152003052296,-0.3818206362574504,-0.12342404960986396,0.3786787428797601,-0.9972749316124083,0.047252143486406356,-0.6156669413207794,0.8472666868619325,0.07050845388355727,-0.6495819879844142,1.0492310379708891,0.12910647241428097,0.14262508798286444,-0.1280101661191857,0.10020104054849016,0.04790562710569879,-0.00754431061198213,-0.026676879364081335,0.020373164014086953,0.15992847740990523,-0.18478578931343914,0.18404315871520138,-0.27406014630705133,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.208333333333334,1.0,1.0,1.0,0.0,3.3847188534726813,-0.0023486497277332595,0.5934230711811511,0.9985292160166859,0.011041673587208693,0.02805407790062485,0.0450605695778042,0.020409675844321466,0.0009903423860101604,-0.005707387126320202,-0.018654520785049908,-0.03918060047930494,-0.06903889381518136,-0.32342882449416016,-0.24344279087954002,-0.38288653255122523,-0.12258925619929636,0.3790784708740908,-0.9973377271191146,0.047029426977729036,-0.6154958945272032,0.8485980027839916,0.06898588731897888,-0.6480145625137532,1.0468827800684102,0.12901068715913677,0.14266984497888546,-0.12780492283222977,0.10014912211297106,0.048029115000538525,-0.007526473473735695,-0.026774945673670447,0.020677949934682083,0.1595873902878986,-0.18056758085591318,0.19208710350853142,-0.28940283041313464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.216666666666667,1.0,1.0,1.0,0.0,3.384884713603856,-0.002324118634168535,0.5933664361401348,0.998547558477899,0.010963336910888983,0.02789078289494613,0.044773685816831166,0.020451457617309127,0.0009928381043606551,-0.005711977518832364,-0.018657800654334342,-0.039158839271803046,-0.06904866898687206,-0.32235413601821433,-0.24225368928087487,-0.3839507183046542,-0.12175489757464777,0.3794792281297691,-0.9974003728369706,0.04680589439184518,-0.615322308821868,0.8499264767000642,0.06749899420262538,-0.646380536259272,1.0444076574640035,0.12891419284323913,0.14271447078360033,-0.12759963932217566,0.10009669420309009,0.04815264725913426,-0.007508362533314994,-0.026872729075593932,0.020982505905797755,0.15924637937672292,-0.17622676300787093,0.20002553969650894,-0.3045041281894667,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.225,1.0,1.0,1.0,0.0,3.385050948545392,-0.0022996391101031653,0.5933097948564007,0.9985657850656277,0.010884979979469616,0.027727575092464155,0.04448675865607142,0.020493226148765354,0.0009953040336416101,-0.005716581604258236,-0.018661166697618612,-0.03913704188253579,-0.06905793222190665,-0.3212802546134395,-0.24106421636648,-0.38501319320659483,-0.1209209779625782,0.37988101499507637,-0.9974628664946699,0.04658154815980247,-0.6151461860954399,0.8512521091069369,0.06604877460218103,-0.6446808035188114,1.0418077112652524,0.12881699080792175,0.14275895400556127,-0.12739431922104805,0.10004376130668652,0.04827621688341721,-0.007489979728083629,-0.02697021294235699,0.02128683709603285,0.15890541152829396,-0.17176859139097111,0.20785487311831163,-0.31935701514512527,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.233333333333333,1.0,1.0,1.0,0.0,3.385217558210372,-0.00227521185770514,0.5932531474285676,0.9985838956893142,0.01080660251718694,0.027564454640959277,0.04419979027335079,0.020534979352335787,0.0009977378465358103,-0.0057211972827519025,-0.018664623825316765,-0.039115200651621086,-0.06906667808779793,-0.32020718617141564,-0.23987437338078219,-0.38607395695833835,-0.12008750155286967,0.3802838317444927,-0.9975252058324386,0.0463563908428059,-0.6149675282036008,0.8525749002255357,0.0646361843461092,-0.6429162883739669,1.0390850405449181,0.12871908263583198,0.14280327911807333,-0.12718896195386686,0.09999032778905265,0.04839981320996389,-0.007471325901819981,-0.0270673826622099,0.021590946748286655,0.15856445371817518,-0.16719842177039757,0.21557154918837362,-0.3339546026198015,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.241666666666667,1.0,1.0,1.0,0.0,3.3853845424921265,-0.0022508375981288263,0.5931964939735075,0.9986018902592659,0.010728204227278994,0.02740142172036367,0.04391278286759949,0.020576714186706462,0.0010001376492793685,-0.00572582242118809,-0.018668176504531533,-0.03909330754808077,-0.06907490229090875,-0.319134936569509,-0.23868416171451212,-0.3871330092391593,-0.11925447249942732,0.38068767854857577,-0.9975873885930335,0.046130425115432305,-0.6147863369829685,0.8538948500022399,0.06326213423934107,-0.6410879443656718,1.036241801221589,0.12862047015964717,0.1428474266200308,-0.126983562895302,0.09993639789852515,0.04852342202106397,-0.007452400835079587,-0.027164225630635225,0.021894836215430313,0.1582234731093335,-0.16252169801774088,0.2231720515498692,-0.34829013458086866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.25,1.0,1.0,1.0,0.0,3.3855519012560777,-0.002226517068574318,0.5931398346270977,0.9986197686868482,0.010649784793654733,0.02723847654440856,0.043625738654086504,0.020618426689217293,0.001002501973403403,-0.0057304548541055045,-0.018671828759555843,-0.03907135419434174,-0.06908260166178054,-0.31806351166875485,-0.237493582937115,-0.38819034967326005,-0.11842189492122758,0.3810925554448438,-0.9976494125130233,0.04590365374896198,-0.614602614266677,0.8552119581106913,0.06192748937914685,-0.639196754181469,1.0332802049685703,0.12852115546982845,0.1428913732099013,-0.1267781135421886,0.09988197577358943,0.048647025671968436,-0.00743320328317143,-0.027260731231042445,0.022198505007422487,0.15788243710715522,-0.15774394012752088,0.230652900616386,-0.36235698405976624,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.258333333333333,1.0,1.0,1.0,0.0,3.3857196343318976,-0.002202251019375672,0.593083169544933,0.9986375308846738,0.010571343882566375,0.027075619362166844,0.04333865985972571,0.02066011201337955,0.0010048297654341825,-0.005735092384258197,-0.018675584174963324,-0.03904933189042916,-0.06908977413522202,-0.3169929173116785,-0.23630263882768043,-0.38924597779819575,-0.11758977290320083,0.38149846230977524,-0.9977112753144197,0.04567607959491493,-0.6144163618995114,0.8565262239540258,0.06063306857054906,-0.6372437293553987,1.0302025181539263,0.12842114092187162,0.1429350919758704,-0.12657260170462425,0.09982706545083403,0.04877060322865612,-0.007413731016745473,-0.02735689080522033,0.022501950848450303,0.1575413134067749,-0.1528707323324155,0.23801065201078053,-0.37614864925319846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.266666666666666,1.0,1.0,1.0,0.0,3.3858877415060014,-0.002178040211132371,0.5930264989029997,0.998655176766783,0.01049288114427584,0.02691285045948901,0.04305154871847509,0.0207017644703642,0.0010071203746519425,-0.005739732782718401,-0.018679445901238177,-0.03902723163750571,-0.06909641872556775,-0.315923159320057,-0.23511133140418383,-0.3902998930350038,-0.11675811049704701,0.38190539883198804,-0.9977729746966357,0.04544770556887497,-0.6142275817525361,0.8578376466674709,0.05937964384027326,-0.6352299099812894,1.0270110608143503,0.12832042914212916,0.1429785526003513,-0.1263670117146587,0.09977167087420746,0.048894130620474874,-0.007393980868788397,-0.027452697614191585,0.02280516974322966,0.15720007003172443,-0.1479077113593283,0.24524189490916948,-0.3896587493168324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.275,1.0,1.0,1.0,0.0,3.386056222514425,-0.002153885411898554,0.5929698228983143,0.9986727062488167,0.010414396214703628,0.026750170160338507,0.04276440746684853,0.0207433775741385,0.0010093735390294641,-0.005744373788674954,-0.018683416662925945,-0.03900504416044787,-0.06910253549747951,-0.314854243492643,-0.2339196629510079,-0.39135209466010673,-0.11592691172196404,0.38231336448678316,-0.9978345083288995,0.045218534634678405,-0.6140362757371243,0.8591462251212212,0.058167940047893586,-0.6331563644402459,1.0237082056653124,0.1282190230329261,0.1430217215729812,-0.12616132464571495,0.09971579590554058,0.04901758080386731,-0.00737394878652875,-0.027548146789901917,0.023108156053290863,0.15685867536350928,-0.14286055486643995,0.2523432503041989,-0.40288101988115166,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.283333333333333,1.0,1.0,1.0,0.0,3.386225077036102,-0.002129787394443027,0.592913141749527,0.9986901192481816,0.01033588871705099,0.026587578828027408,0.042477238339558694,0.02078494408965569,0.001011589369564544,-0.0057490131088469235,-0.01868749876896478,-0.03898275992985353,-0.06910812553251543,-0.31378617560284155,-0.23272763604463415,-0.39240258177909904,-0.115096180565288,0.3827223585120525,-0.9978958738430779,0.044988569789043274,-0.6138424458183146,0.8604519579235294,0.05699863459249926,-0.631024189142886,1.0202963771496645,0.12811692577690326,0.14306456241695353,-0.12595551854758802,0.09965944433572349,0.049140923934586356,-0.007353629885600288,-0.0276432352784875,0.023410902580498494,0.15651709816467685,-0.13773497009907223,0.25931136919813635,-0.4158093083200809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.291666666666666,1.0,1.0,1.0,0.0,3.386394304686575,-0.0021057469335921592,0.5928564556974941,0.9987074156842064,0.010257358263386652,0.026425076866355233,0.04219004356530827,0.020826456083953834,0.0010137683331254074,-0.005753648416517895,-0.01869169412516095,-0.038960369182962425,-0.06911319089187361,-0.3127189613963613,-0.23153525357739202,-0.39345135330256653,-0.11426592098303531,0.38313237988569293,-0.9979570688269929,0.04475781404670361,-0.6136460940274493,0.8617548434239658,0.05587235721290905,-0.6288345082869436,1.0167780505266444,0.12801414084036122,0.1431070359235187,-0.1257495686924881,0.09960261989682834,0.0492641275504091,-0.007333018509774192,-0.02773796177572868,0.023713400659250983,0.15617530759251208,-0.1325366827996087,0.2661429307350849,-0.4284375688043296,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3,1.0,1.0,1.0,0.0,3.3865639050121596,-0.0020817648036670923,0.5927997650058212,0.9987245954782872,0.010178804456188932,0.026262664720656238,0.041902825362744575,0.020867904979845527,0.0010159112339660908,-0.00575827735038579,-0.01869600424867014,-0.03893786194357676,-0.06911773457574744,-0.31165260658883553,-0.23034251877924217,-0.39449840792397384,-0.11343613690034086,0.3835434273045593,-0.9980180908182408,0.04452627042611446,-0.6134472224739937,0.8630548797167379,0.054789689879172446,-0.6265884736306346,1.0131557510029257,0.12791067197583494,0.14314910039148754,-0.12554344782759852,0.099545326275019,0.049387156761367956,-0.0073121082934557435,-0.027832326655159584,0.02401564025598768,0.15583327320497942,-0.12727142640362316,0.2728346402893522,-0.4407598571727078,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.308333333333334,1.0,1.0,1.0,0.0,3.3867338774845845,-0.002057841776025346,0.592743069961377,0.9987416585540243,0.010100226889835579,0.026100342878757437,0.04161558593659143,0.02090928161186043,0.0010180191940977734,-0.005762897513030118,-0.01870043028413529,-0.03891522804120506,-0.06912176047948174,-0.3105871168634307,-0.2291494352375339,-0.3955437440996932,-0.112606832211785,0.38395549916504906,-0.9980789372985505,0.04429394193578429,-0.6132458333565162,0.8643520646440488,0.05375116677284866,-0.6242872642821211,1.0094320529070993,0.12780652322368913,0.143190711877636,-0.1253371264404035,0.0994875671237988,0.0495099744457006,-0.007290892226539114,-0.02792633189011462,0.024317610073698592,0.15549096496118242,-0.12194493155236297,0.2793832275197139,-0.45277032565564035,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.316666666666666,1.0,1.0,1.0,0.0,3.386904221496124,-0.0020339786167158625,0.5926863708747844,0.9987586048373485,0.010021625152035153,0.025938111871851053,0.04132832747397148,0.020950576284091728,0.0010200936326562305,-0.005767506469170624,-0.018704973021511223,-0.038892457129024754,-0.06912527334710017,-0.3095224978684407,-0.2279560069146149,-0.3965873600313139,-0.11177801078161088,0.384368593545321,-0.9981396056886831,0.04406083156127922,-0.6130419289727654,0.8656463957994243,0.05275727435329973,-0.6219320865053061,1.005609578908665,0.12770169891293093,0.1432318244482056,-0.12513057302725672,0.09942934607797771,0.04963254145221474,-0.007269362722326367,-0.02801998096979605,0.024619297663208695,0.1551483532139697,-0.11656291594816556,0.2857854444030927,-0.46446321748595754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.325,1.0,1.0,1.0,0.0,3.3870749363552406,-0.0020101760842558157,0.5926296680808852,0.9987754342566366,0.009942998825191672,0.025775972275287003,0.04104105214092804,0.02099177882943693,0.0010221362444708228,-0.005772101743806206,-0.018709632915237896,-0.038869538700958065,-0.06912827872249312,-0.30845875521488186,-0.22676223816339713,-0.39762925365014745,-0.1109496764438187,0.38478270818925264,-0.9982000933439226,0.04382694225295435,-0.612835511728796,0.8669378705309483,0.051808451507045904,-0.6195241735420696,1.0016909992823333,0.12759620366129987,0.14327239043479878,-0.12492375436718883,0.09937066676780265,0.04975481680726923,-0.007247511687458186,-0.028113278810447118,0.02492068953841242,0.15480540869649895,-0.1111310745768497,0.2920380632649078,-0.4758328614337537,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.333333333333334,1.0,1.0,1.0,0.0,3.38724602128274,-0.0019864349275356165,0.592572961939186,0.9987921467428174,0.009864347487699222,0.02561392470928692,0.040753762079157235,0.021032878670160578,0.0010241489779553054,-0.005776680820130969,-0.018714410104607997,-0.038846462107880925,-0.06913078289853676,-0.3073958944740857,-0.2255681337407016,-0.3986694226041004,-0.1101218330021475,0.3851978404921088,-0.9982603975501407,0.043592276914438434,-0.6126265841471252,0.8682264859443659,0.0509050897770189,-0.6170647854508909,0.9976790312181024,0.12749004237458506,0.14331236069373976,-0.12471663580017167,0.09931153283325944,0.04987675792376356,-0.007225330593396695,-0.02820623166235478,0.025221771295724782,0.1544621025040116,-0.10565507031863472,0.2981378748181629,-0.48687366630185025,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.341666666666667,1.0,1.0,1.0,0.0,3.3874174754084625,-0.0019627558838586586,0.5925162528342812,0.9988087422294649,0.009785670715159523,0.025451969839585212,0.04046645940295724,0.021073864879565907,0.0010261340124635924,-0.005781241137478086,-0.018719304435185,-0.038823216572850164,-0.06913279286469143,-0.30633392117530545,-0.22437369881850147,-0.399707864246817,-0.10929448422993104,0.38561398748798204,-0.9983205155204792,0.043356838391915106,-0.6124151488738673,0.8695122389060151,0.05004753366840199,-0.6145552089617669,0.9935764381773025,0.1273832202449099,0.14335168486374006,-0.12450918150455625,0.09925194793853787,0.04999832081395761,-0.0072028105492738526,-0.02829884701319535,0.025522527736963063,0.1541184060712708,-0.10014052496551712,0.3040816862263629,-0.4975801154191939,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.35,1.0,1.0,1.0,0.0,3.3875892977685007,-0.0019391396771201593,0.5924595411762587,0.9988252206528838,0.009706968081520108,0.025290108377999755,0.04017914619640072,0.021114726243824846,0.0010280937353582542,-0.00578578008911361,-0.01872431548095748,-0.038799791205789684,-0.06913431625324344,-0.3052728408033372,-0.2231789389929726,-0.4007445756291763,-0.10846763386983854,0.3860311458390081,-0.9983804443926286,0.04312062946421851,-0.6122012086848425,0.8707951260455538,0.049236081027593616,-0.6119967573471182,0.9893860292944492,0.12727574274853382,0.14339031162716953,-0.12430135477836446,0.09919191578612124,0.05011946030194503,-0.00717994237466657,-0.028391133488721854,0.02582294299338761,0.1537742911455231,-0.09459301066124623,0.30986631920763674,-0.5079467611713917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.358333333333333,1.0,1.0,1.0,0.0,3.387761487302959,-0.001915587016128922,0.5924028274010872,0.9988415819521815,0.009628239160128881,0.025128341082934196,0.039891824510735766,0.021155451324390156,0.0010300307188239584,-0.005790295020227344,-0.018729442567222063,-0.03877617501729289,-0.06913536128469125,-0.3042126587961632,-0.22198386029138198,-0.40177955349312305,-0.10764128563349569,0.3864493118263478,-0.9984401812267236,0.04288365283376974,-0.6119847664906441,0.8720751437584405,0.048470983490714555,-0.6093907703083062,0.9851106588244459,0.12716761564282808,0.14342818896511567,-0.1240931183144256,0.09913144013099423,0.05024013023816498,-0.007156716674510122,-0.02848310075111285,0.026123000651854245,0.15342972975717517,-0.08901804177638847,0.3154886081954622,-0.5179682196070456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.366666666666667,1.0,1.0,1.0,0.0,3.387934042854249,-0.0018920985930751795,0.5923461119709844,0.9988578260693326,0.009549483524702591,0.02496666875981735,0.03960449636201737,0.021196028520198158,0.0010319476966625149,-0.005794783225952534,-0.018734684793734392,-0.03875235693211797,-0.06913593671240359,-0.3031533805426234,-0.22078846917688733,-0.4028127942677501,-0.10681544320098864,0.3868684813429775,-0.9984997230038705,0.04264591111836663,-0.6117658253406449,0.8733522882081733,0.04775244699798714,-0.6067386138771939,0.9807532256343318,0.1270588449624055,0.14346526441473106,-0.12388443447749475,0.09907052479406042,0.0503602837121353,-0.007133123911886585,-0.02857475939615592,0.02642268388185931,0.1530846941886388,-0.08342106722895648,0.32094539857105975,-0.5276391651587953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.375,1.0,1.0,1.0,0.0,3.3881069631659178,-0.0018686750821455477,0.5922893953747699,0.9988739529492306,0.009470700750208904,0.024805092261477087,0.03931716372897357,0.021236446129594855,0.0010338475411586997,-0.005799241949525757,-0.01874004105822354,-0.038728325802327684,-0.06913605176696926,-0.3020950113801231,-0.21959277255113646,-0.40384429406774797,-0.10599011022026135,0.3872886498882167,-0.9985590666252551,0.04240740684383381,-0.6115443884259465,0.8746265553282512,0.047080632370231947,-0.6040416803321219,0.976316672738466,0.12694943701463401,0.1435014853219696,-0.12367526557558572,0.099009173675286,0.05047987326412651,-0.007109154481672597,-0.028666120849418636,0.026721975561905253,0.1527391569418568,-0.07780746325825066,0.32623354498644064,-0.5369543255193032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.383333333333333,1.0,1.0,1.0,0.0,3.3882802468820103,-0.0018453171382868025,0.5922326781281977,0.9988899625397321,0.00939189041365876,0.024643612488454546,0.03902982855110453,0.021276692411741082,0.0010357332401251518,-0.005803668380873645,-0.018745510079971717,-0.03870407041996294,-0.06913571610065407,-0.3010375565923795,-0.2183967777548545,-0.40487404869400984,-0.10516529030640054,0.3877098125640463,-0.9986182089118983,0.04216814243754299,-0.6113204590812799,0.875897940823871,0.046455655943682964,-0.6013013881274198,0.9718039868756767,0.12683939837433766,0.14353679908595596,-0.12346557412201475,0.09894739076621306,0.05059885109546025,-0.007084798783647539,-0.028757197262255924,0.027020858404680492,0.15239309070589568,-0.0721825266571291,0.3313499097967809,-0.5459084767139966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.391666666666666,1.0,1.0,1.0,0.0,3.3884538925469543,-0.0018220253961179298,0.5921759607742708,0.9989058547916901,0.009313052094811102,0.024482230389257273,0.038742492727015646,0.02131675564701627,0.001037607874337465,-0.005808059655345552,-0.018751090423063412,-0.03867957953015179,-0.06913493973184003,-0.2999810214072175,-0.21720049256637053,-0.4059020536364482,-0.10434098704082446,0.38813196407314104,-0.9986771466049825,0.04192812022279621,-0.6110940407858685,0.8771664401733494,0.045877590259279795,-0.5985191818355089,0.9672181981265661,0.1267287358776814,0.14357115340549675,-0.1232553230982536,0.09888518016129638,0.050717169274890894,-0.007060047292584137,-0.028848001408407764,0.02731931508078711,0.15204646832617685,-0.06655146846587731,0.33629136161585693,-0.5544964384097661,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.4,1.0,1.0,1.0,0.0,3.3886278986059586,-0.001798800468989316,0.5921192438835357,0.9989216296589785,0.009234185376790178,0.02432094696054943,0.03845515811298334,0.021356624196521522,0.0010394745953616442,-0.005812412853018319,-0.01875678051956131,-0.038654841844103977,-0.0691337329901093,-0.29892541099441816,-0.21600392519809622,-0.40692830407898073,-0.10351720397037893,0.3885550987186278,-0.9987358763667747,0.041687342414069524,-0.6108651371632667,0.8784320486293072,0.04534646480258501,-0.5956965321004889,0.9625623795688473,0.1266174566155931,0.14360449651450558,-0.12304447620326342,0.0988225460686723,0.05083477994253238,-0.007034890629078472,-0.028938546581391278,0.027617328339817337,0.15169926277543322,-0.06091940812787078,0.3410547740162384,-0.5627130695006444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.408333333333333,1.0,1.0,1.0,1.0,3.388802263405919,-0.0017756429481881753,0.5920625280543519,0.9989372870985087,0.009155289846615159,0.02415976324728261,0.03816782652174956,0.02139628656001819,0.0010413366039559563,-0.005816724998432149,-0.018762578692106707,-0.038629846052574746,-0.06913210646198531,-0.2978707304636243,-0.21480708429112877,-0.4079527949065026,-0.1026939446063466,0.3889792104055166,-0.9987943947821338,0.04144581111310636,-0.6106337519802049,0.8796947612196067,0.04486226679048195,-0.5928349356019049,0.957839646968222,0.12650556792616952,0.14363677741151937,-0.12283299809444537,0.0987594928196403,0.05095163550913884,-0.007009319627002686,-0.02902884649346238,0.02791488112841911,0.15135144712779658,-0.055291368106097916,0.3456370243941831,-0.570553264015019,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.416666666666666,0.0,1.0,1.0,1.0,3.3889769851968095,-0.001752553402286884,0.5920058139131392,0.998952827070237,0.00907636509564658,0.023998680342760394,0.03788049972154333,0.02184301230862973,0.0009562883068166626,-0.0037177592341271597,-0.020266120210173103,-0.0329717970770109,-0.07010348234797259,-0.29681698486231534,-0.21360997890790423,-0.40897552071388815,-0.10187121242338493,0.3894042926437801,-0.9988526983605581,0.04120352830584515,-0.6103998891444598,0.8809545727481038,0.04442494200081671,-0.5899359150272525,0.9530531585019303,0.12826572336651965,0.14046148387702684,-0.1266871019655469,0.10135646972238233,0.04605250196247912,-0.0074609632251032565,-0.028431929700040992,0.03578136336886972,0.12877491750780123,-0.04327490781398491,0.19454833186283382,-0.27997234685672723,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.425,0.0,1.0,1.0,1.0,3.389160636677879,-0.0017310316998837936,0.591983760160699,0.9989675466109874,0.008982985294811221,0.02388419460134875,0.03758579583657581,-0.0018361588047662025,0.006021487477844512,0.006791967735163985,-0.0051439623736935,-0.06757190646824522,-0.07104218992194647,-0.2957329684075156,-0.212466059559845,-0.4100642466059284,-0.10100467011097355,0.38974675210489124,-0.9989187441692189,0.040971945618105673,-0.610037395924057,0.8818410098447367,0.04414101832691553,-0.589592463404191,0.9531734411872765,0.05138558731363596,0.4441107425114288,-0.8846950285572597,0.08214793997632197,-0.03790538948789446,0.1496681752293494,-0.05434850932468732,0.020381088905703226,0.1371598665523277,-0.060274725926387634,0.007383632443851429,0.06495157321733558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.433333333333334,0.0,1.0,1.0,1.0,3.388944488914833,-0.0016566346294374084,0.5921222869748073,0.9989888216261741,0.009040470193971833,0.023439822196719678,0.03728510292339363,-0.02605604799724611,0.010939046567725694,0.010778636358707561,0.005962424467749898,-0.09875825097452454,-0.07078793057677094,-0.29596055840708807,-0.20620813319938042,-0.42372043785650915,-0.10050208009044623,0.3887725361523152,-0.9963582287734023,0.04029771981710036,-0.6100602043293647,0.883240570523976,0.043420363235376916,-0.5898128544865217,0.9541356847222192,-0.026203101093044134,0.7835782754135512,-1.7286637728910348,0.06395275270736633,-0.11169114311087358,0.27225840367531395,-0.07473165708418925,-0.018295081277184266,0.1788201498502806,-0.08034940864555182,-0.03880271587156203,0.12049173524746104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.441666666666666,0.0,1.0,1.0,1.0,3.388723083627227,-0.0015847165291275685,0.5921868341031832,0.9990084153431141,0.0090495008445866,0.02306924209994642,0.03698787202639207,-0.0244105814651319,0.010370549476526032,0.0053091348672033275,-0.00034440306404550335,-0.08623460964483337,-0.0705705665527173,-0.29616968675906635,-0.1994064216362858,-0.43887530948744563,-0.09993879089918412,0.38788523305304334,-0.9943811041079637,0.03972641800003585,-0.6103423139453434,0.8848213456755747,0.042801861516156336,-0.5902391753353837,0.9551816367747342,-0.022214970323782834,0.8318532126824324,-1.8482859028234688,0.06852221327411423,-0.09967284323884051,0.2223013834302745,-0.06710017978373825,-0.03333290863073879,0.18863834011501268,-0.07273873321410398,-0.050208711797146144,0.12364264875195374,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.45,0.0,1.0,1.0,1.0,3.3885306286040775,-0.0015159788278452607,0.5922325641711561,0.9990271880960646,0.00905062492784201,0.022727131382149976,0.036691158777389474,-0.020535649986725576,0.009728453339698491,0.004026690589527624,-0.0015221842027943442,-0.08145786809773166,-0.0706925359111955,-0.29633080791248445,-0.19234391298800654,-0.45452520290356696,-0.09936004320254432,0.38711132209833454,-0.9926532057162311,0.03917938348737139,-0.6106157528065437,0.8863845428592262,0.04220805101514185,-0.5906496663498074,0.9561963955347518,-0.01522338992405392,0.8602741878161185,-1.8938446148206944,0.07036246276049318,-0.08640720953433934,0.19978706581262218,-0.06486338418993237,-0.029012799740411044,0.18583254228302648,-0.07046475014299558,-0.04527225418132108,0.11952115741164615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.458333333333334,0.0,1.0,1.0,1.0,3.3883733700089516,-0.0014493727212661228,0.5922723825653782,0.9990455759878136,0.009048349797469398,0.022395954343147083,0.036393484227030364,-0.016250578333102162,0.009164172987456096,0.0036879456289218805,-0.0021590130418575296,-0.07947802222439189,-0.07105084578331304,-0.29642340992446725,-0.18506851850601716,-0.47043938640112387,-0.09876608318650923,0.3864451128941377,-0.9910513196777533,0.03864536159687031,-0.6108258606076836,0.8879185547136251,0.04162744901377308,-0.5909937129050724,0.9571736560649283,-0.00650953216110306,0.8848701216054333,-1.9212215429235246,0.07226159706595792,-0.07356234690089059,0.18664910436032134,-0.06348462064478741,-0.020782751833228197,0.1827471594477581,-0.06906789925117687,-0.03669543273780551,0.1153976545993296,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.466666666666667,0.0,1.0,1.0,1.0,3.388252521115081,-0.0013844880776917097,0.5923089101881941,0.9990637335665721,0.009043496109921782,0.022070150131745934,0.036094042767424575,-0.01189234291740448,0.008633820494004223,0.0035333941869823866,-0.0027056837490439,-0.07837551811606472,-0.07154372611493044,-0.2964393001151695,-0.177596077627916,-0.48654556195229237,-0.09815568325144503,0.3858852829833197,-0.9895423873102257,0.038121306476624935,-0.6109621320037641,0.8894303288500222,0.04105691936095557,-0.5912612568954375,0.9581196897780739,0.002920664918748539,0.9079407902914421,-1.9422939405773476,0.07427646701725632,-0.06082941775183315,0.17601377854554512,-0.062352050112488566,-0.011820650746330319,0.18034220618284413,-0.0679247034536179,-0.027426930278593442,0.111885126415463,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.475,0.0,1.0,1.0,1.0,3.3881681887659303,-0.0013212183181634907,0.5923426462239713,0.999081714264434,0.009036241257962437,0.021748015156111293,0.03579243499875568,-0.007538787515521033,0.008116298476265863,0.0034081106317715706,-0.0032367942113528062,-0.07753940557010158,-0.07210276643293327,-0.29637473217582144,-0.1699361720011598,-0.502810952077413,-0.09752814206955496,0.38543128926494047,-0.9881177567019942,0.03760616076166217,-0.6110228714534558,0.8909242581500059,0.040495370622879445,-0.5914508284097156,0.9590384081718527,0.012705863648416749,0.9299461867144432,-1.9600676714817222,0.07635107397533758,-0.04816629348502355,0.16603835957607727,-0.06130651717097896,-0.0027611471841004764,0.17831143933753957,-0.06687124729615912,-0.018086577733487097,0.10871157733880032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.483333333333333,0.0,1.0,1.0,1.0,3.3881201992282213,-0.0012595578069015906,0.5923736808964913,0.9990995364363319,0.009026609574543399,0.021429046550553114,0.03548848512168995,-0.003212619685073088,0.007605078825738537,0.0032827058278178663,-0.0037687114926861307,-0.07678051068774495,-0.07268928907108778,-0.2962275357210292,-0.1620969745160086,-0.5192133564769877,-0.09688316535185607,0.385082511425236,-0.9867750813172911,0.03709953119044195,-0.6110081511234992,0.8924021861723145,0.03994239857268625,-0.5915626998576623,0.9599315494003873,0.022713776594960322,0.9509977531983588,-1.9753668396441038,0.07844551703125147,-0.03558961706930486,0.15625356991946449,-0.06029439854977711,0.006265079181224653,0.17643040699847568,-0.06585180620790332,-0.00880239383737269,0.105688127751975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.491666666666667,0.0,1.0,1.0,1.0,3.3881082676440926,-0.0011995282071961219,0.5924020362262169,0.9991172060046807,0.00901459164777957,0.02111310771116111,0.03518213304510646,0.001074707174624634,0.0070990157208569386,0.0031524601547524545,-0.004304202101339602,-0.07604160405547242,-0.07328290689624761,-0.2959961692325721,-0.1540862094478538,-0.5357337327381481,-0.09622071678570077,0.38483812898045205,-0.9855135305366698,0.036601254119165885,-0.610918453467102,0.8938647649333138,0.03939784051941439,-0.5915975349736718,0.960799876967719,0.03288923693786083,0.9711376067586242,-1.9884526473113273,0.08053481557067421,-0.023124724577906486,0.1465542297170841,-0.05929751548323314,0.015222996869981298,0.1745992810930841,-0.0648470975522139,0.00039247422458643655,0.10273485950485606,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.5,0.0,1.0,1.0,1.0,3.388132027783231,-0.0011411553335558178,0.5924277292474648,0.999134724309836,0.009000175202484792,0.020800169859665797,0.034873377502675246,0.005313651012829991,0.006598660853437355,0.0030171110152720257,-0.004842709589774972,-0.07530618373503944,-0.07387300946580713,-0.2956793817720649,-0.1459113477366982,-0.5523542339321765,-0.09554091842567816,0.38469709934893753,-0.9843325108220063,0.0361112392657214,-0.6107544345089995,0.8953121741905326,0.038861613613482685,-0.5915561586205859,0.9616437970588015,0.043205188123557337,0.990393366222338,-1.9994363910845014,0.08260344783566687,-0.010798802935922946,0.1369323129322475,-0.05831052916630816,0.02409363537327902,0.1727789347964115,-0.06385118429042644,0.00948009989301335,0.09982340105272325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.508333333333333,0.0,1.0,1.0,1.0,3.3881910353200557,-0.0010844626140520841,0.5924507818441042,0.999152090898597,0.008983352408047344,0.020490233154080266,0.03456224786914004,0.009494916179659165,0.006105019859734519,0.0028770359629777,-0.005382997097574967,-0.0745700977333873,-0.07445387300552779,-0.29527608276384615,-0.13757965334414818,-0.5690576725895564,-0.09484399265510632,0.38465814893152,-0.9832313253211323,0.03562941196639408,-0.6105168928775474,0.8967444138465873,0.03833365411457395,-0.5914395333087883,0.9624636003185977,0.05364552905816167,1.0087889285383618,-2.0083881046183416,0.08464128282596323,0.00136035586141392,0.12740520279710177,-0.05733284166175162,0.03285995084520987,0.17095428977095928,-0.06286314651487379,0.0184437367874124,0.09694493789368819,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.516666666666666,0.0,1.0,1.0,1.0,3.3882847685631514,-0.0010294695466678042,0.5924712211932139,0.9991693045436311,0.008964121030747065,0.020183303325096977,0.03424879061852515,0.01360940263877263,0.005619160700304342,0.002732614353355568,-0.005923802552793999,-0.07383278291820629,-0.07502214566245123,-0.2947852896210955,-0.1290981989277255,-0.5858273690091489,-0.09413023037857877,0.38471977194662776,-0.982209090775388,0.035155691904692206,-0.6102067686615793,0.8981614123533819,0.037813894504901455,-0.5912487630074623,0.9632595460236963,0.0641985825067215,1.0263468289014164,-2.015366052110714,0.08664114661032674,0.01332528632170038,0.11799588444620923,-0.05636556513369306,0.04150506417132105,0.1691191136732395,-0.06188392221877073,0.027266367347855702,0.09409731507494801,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.525,0.0,1.0,1.0,1.0,3.388412630891081,-0.0009761915430639236,0.5924890788902805,0.999186363628803,0.008942484111681059,0.019879385338779205,0.033933062854916464,0.01764841376951852,0.005142094023042895,0.0025841562731785755,-0.006463979155558573,-0.07309458854542866,-0.07557562754300147,-0.2942061063887341,-0.1204738728624579,-0.6026471067914017,-0.0933999735449342,0.3848802370368817,-0.9812647272470288,0.03468998588083253,-0.6098251418080254,0.8995630657411413,0.03730225541092777,-0.5909850938529907,0.9640318889031801,0.07485446316616073,1.0430889950602371,-2.020425012579774,0.0885975285590157,0.025069687033354437,0.10872729184519647,-0.05541034450930196,0.050012516554993613,0.16727037633082587,-0.06091505955642701,0.03593122334833554,0.09128043103177275,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.533333333333333,0.0,1.0,1.0,1.0,3.3885739550288614,-0.0009246401133548697,0.5925043900533903,0.9992032663018048,0.00891844937663525,0.019578482183083896,0.03361512915234879,0.0216038408528199,0.00467473753237006,0.0024319145543150724,-0.007002510236620059,-0.0723559804278854,-0.07611269772448064,-0.29353771523499284,-0.11171338234338822,-0.6195011192188118,-0.09265360490259518,0.38513760006385034,-0.9803969692446347,0.034232186162870507,-0.6093732267189961,0.9009492519588956,0.03679864351229434,-0.5906499092849901,0.9647808865408926,0.08560397826107513,1.059037104498437,-2.023618647387535,0.09050593590943234,0.03656903952715784,0.09962063761653539,-0.054468887840457,0.058366671623011346,0.16540625762871963,-0.059958210574295595,0.04442235385384574,0.0884947004306369,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.541666666666666,0.0,1.0,1.0,1.0,3.3887680086027956,-0.0008748231085588345,0.5925171925484812,0.9992200105400263,0.008892028662043769,0.01928059511005511,0.033295059916848856,0.02546828230554222,0.004217906865093757,0.002276100949807995,-0.007538497533377497,-0.07161732426563466,-0.07663204919199147,-0.2927793734177162,-0.10282325445415062,-0.6363740842478606,-0.091891541279777,0.385489721029001,-0.9796043832867533,0.03378217108349158,-0.6088523639476419,0.90231983670162,0.03630295190135618,-0.5902447212887599,0.9655068005770241,0.09643815413164614,1.0742127499510379,-2.0250001103277238,0.09236257823044519,0.04780099604321131,0.09069492250618261,-0.05354277924970591,0.06655299323709452,0.16352546692287584,-0.05901492578271661,0.05272499209687087,0.0857405761282326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.55,0.0,1.0,1.0,1.0,3.3889940004228296,-0.0008267449517616064,0.5925275263229257,0.9992365941840883,0.008863237409565496,0.01898572421096675,0.032972930445920895,0.02923510500766781,0.003772315743736345,0.0021168978039037794,-0.008071146173407907,-0.07087884551815765,-0.077132566121615,-0.29193041266613207,-0.09380983651087092,-0.6532511210576072,-0.09111422859875443,0.3859342833312372,-0.978885387202865,0.03333980650870874,-0.6082640101650445,0.9036746764076102,0.03581506141591573,-0.5897711594167089,0.9662098961430298,0.10734802307324154,1.0886374671263779,-2.0246220847849217,0.09416420864804209,0.05874557876707209,0.08196682858978566,-0.05263340959668572,0.07455819869645719,0.16162702224727932,-0.05808657574029624,0.0608257506160248,0.08301842510728408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.558333333333334,0.0,1.0,1.0,1.0,3.3892510870666306,-0.0007804068451212117,0.5925354328298376,0.9992530149596821,0.008832094229850429,0.018693868988809023,0.032648820311463836,0.03289846193221477,0.0033385800549882204,0.001954466232439203,-0.008599750911631954,-0.07014064117807191,-0.0776132658596839,-0.29099023969982885,-0.08467929666871099,-0.6701177856609426,-0.09032213780230963,0.3864688140084522,-0.9782382694769235,0.032904947590213486,-0.6076097273027009,0.9050136204057413,0.03533484230568457,-0.5892309587784929,0.9668904409954788,0.11832451889910667,1.1023326617805007,-2.022536614878636,0.09590803626107536,0.06938524006112057,0.0734507585639399,-0.051741958057291704,0.08237031903091774,0.15971018943466975,-0.05717432810890877,0.06871269708240257,0.08032852113025069,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.566666666666666,0.0,1.0,1.0,1.0,3.3895383794577802,-0.0007358069528937663,0.5925409545327421,0.9992692704955566,0.008798620527531293,0.018405028835922415,0.03232281289801393,0.036453278637133414,0.0029172239263199153,0.0017889521427532046,-0.009123684022731351,-0.06940270489286836,-0.07807327011495517,-0.28995833735114696,-0.07543762548119591,-0.6869600646389178,-0.0895157613277365,0.38709070399892254,-0.977661207893466,0.03247744054108721,-0.6068911715145292,0.9063365128981881,0.034862155947433915,-0.5886259477986688,0.967548704828534,0.12935841795039815,1.1153194695532254,-2.0187948622034146,0.09759167002161451,0.07970482502685061,0.06515894251065246,-0.050869396367971,0.08997869395977798,0.15777447610728856,-0.056279149576640014,0.07637535050760702,0.07767107507863136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.575,0.0,1.0,1.0,1.0,3.389854949224174,-0.0006929405629702522,0.5925441344840041,0.9992853583405408,0.008762840179838057,0.01811920339938939,0.031994995020656454,0.03989521846578067,0.002508686886683641,0.0016204908822032079,-0.009642384580190694,-0.06866495363616326,-0.07851178943780006,-0.2888342660673222,-0.0660906388428239,-0.7037643666976662,-0.08869560996861606,0.3877972277588997,-0.977152287101746,0.03205712431741397,-0.6061100824033713,0.9076431950075294,0.03439685647940724,-0.5879580362700327,0.968184958913456,0.14044029936353342,1.1276185765452813,-2.013446845576059,0.09921307656780481,0.08969146789842952,0.057101580697886956,-0.05001650326233495,0.09737392235631415,0.15581964323633235,-0.05540181904587882,0.08380462530664046,0.07504627608834635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.583333333333334,0.0,1.0,1.0,1.0,3.390199834694257,-0.0006518002294644778,0.592545015971673,0.999301275980566,0.008724779262585695,0.017836392839118514,0.03166545658791199,0.04322063396166801,0.002113331543623676,0.00144921095738844,-0.010155348880725947,-0.06792725248107126,-0.07892811393526852,-0.28761766569508807,-0.056643982538774555,-0.7205175120651854,-0.08786221005160642,0.3885855617972297,-0.9767095148818346,0.03164383215338163,-0.6052682728085906,0.9089335069521269,0.03393879229666927,-0.5872292040435582,0.968799476096673,0.15156051408557913,1.139250022278317,-2.006541193484712,0.10077054471995583,0.09933444571944117,0.04928700624661664,-0.049183883321463756,0.10454778382066543,0.15384572068778413,-0.05454294577411298,0.09099274240917499,0.0724543337911343,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.591666666666667,0.0,1.0,1.0,1.0,3.3905720464428746,-0.0006123758986653707,0.5925436422296703,0.9993170208559099,0.008684465818252605,0.017556597989491114,0.0313342902928482,0.04642651017421654,0.0017314513719659925,0.0012752370886740826,-0.010662121872103098,-0.06718943663753758,-0.07932160713430687,-0.2863082574992292,-0.04710313847151862,-0.7372067199224114,-0.08701610088995013,0.3894528018542237,-0.9763308369976357,0.031237392928722907,-0.6043676193396935,0.9102072903523258,0.03348780738317202,-0.5864414905632132,0.9693925311433083,0.16270915871981262,1.1502330008169857,-1.9981249258756972,0.10226265385192918,0.10862500672424003,0.04172185739769185,-0.04837198740793969,0.11149314308933178,0.15185302169463677,-0.05370298938526516,0.09793312113143271,0.06989551784611026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.6,0.0,1.0,1.0,1.0,3.390970572339365,-0.0005746550205215664,0.592540056206253,0.9993325903786133,0.008641929661437148,0.017279820436308685,0.031001591323453988,0.049510404122117664,0.0013632783160511404,0.0010986927720929075,-0.011162289506759456,-0.06645133071964661,-0.07969170165075463,-0.2849058463830912,-0.037473432525158126,-0.7538195941631137,-0.0861578324874076,0.39039597857596703,-0.976014150591873,0.030837632363249302,-0.6034100537571018,0.9114643906470375,0.033043742473581515,-0.5855969853580343,0.9699644013941082,0.17387605299311604,1.1605856709955522,-1.988243274364514,0.10368824523115328,0.11755618636911436,0.03441125209496132,-0.047581133212860546,0.11820384608474566,0.14984215438367254,-0.05288228015859514,0.10462026175429351,0.06737019311925163,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.608333333333333,0.0,1.0,1.0,1.0,3.391394382081039,-0.000538622647755963,0.5925343003856799,0.9993479819499475,0.008597202217329456,0.017006062520130896,0.030667457086679003,0.05247038359001671,0.00100898999018089,0.0009197024661957042,-0.011655471973938514,-0.06571276544139497,-0.08003789607813494,-0.2834103232826773,-0.02776004395492608,-0.7703441078284866,-0.0852879634694309,0.3914120716270423,-0.9757573161293863,0.030444374041841898,-0.6023975552382811,0.9127046595920537,0.03260643604719544,-0.5846978195339749,0.9705153676952958,0.18505072069278872,1.1703249829412143,-1.9769395450703198,0.10504639613884509,0.12612262059224943,0.027358959520717985,-0.046811525107895297,0.12467461415055503,0.1478140297398456,-0.052081038724389045,0.11104962604263635,0.06487884979405223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.616666666666667,0.0,1.0,1.0,1.0,3.391842431217789,-0.000504261524673276,0.5925264166580578,0.9993631929777875,0.008550316389083067,0.016735327276073825,0.030331986942017768,0.05530496758398511,0.0006687163285744638,0.0007383934869439953,-0.01214131777397242,-0.06497359198848408,-0.08035975282995282,-0.28182166770487804,-0.017968016142804553,-0.7867685865809524,-0.08440705921842685,0.3924980222525045,-0.9755581679331944,0.030057440278117714,-0.6013321435212592,0.9139279578093683,0.032175725161508364,-0.5837461582573237,0.9710457155573424,0.19622237427848965,1.1794665252709717,-1.964255024972863,0.1063363968045114,0.13432036330665476,0.0205675646545056,-0.046063272842895436,0.13090094126229967,0.145769865906622,-0.05129939467260189,0.1172175209202031,0.062422128148049705,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.625,0.0,1.0,1.0,1.0,3.39231366468987,-0.0004715521676912187,0.5925164462324777,0.9993782208937733,0.008501306450183982,0.016467618319101044,0.029995281941220055,0.05801307010466519,0.0003425455899970205,0.000554897669005515,-0.012619498599704976,-0.06423369430713959,-0.08065689679905344,-0.2801399503780358,-0.008102268533743219,-0.8030816915780343,-0.08351569018935572,0.39365074434881986,-0.9754145233851446,0.02967665282779364,-0.6002158728839094,0.9151341573571641,0.031751446135985406,-0.5827441941853049,0.9715557364977633,0.20737990344819046,1.188024395291657,-1.9502289304871923,0.1075577302108699,0.14214671312855365,0.01403862306019521,-0.0453364088286317,0.13687899763391131,0.14371118893490742,-0.05053740379218796,0.12312098899288415,0.060000837978593236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.633333333333333,0.0,1.0,1.0,1.0,3.3928070199123126,-0.00044047293957923513,0.5925044295887154,0.9993930631701469,0.008450207958122517,0.016202939682883066,0.029657444571106414,0.06059394837655307,3.052966479186094e-05,0.0003693528336494924,-0.013089704988001582,-0.06349299952645839,-0.08092901474540952,-0.27836533598074154,0.0018323904453897294,-0.8192724020890723,-0.08261443038157902,0.3948671341379804,-0.9753241908821911,0.029301833464307186,-0.5990508268940273,0.9163231442916168,0.03133343509830523,-0.5816941417741089,0.9720457295236523,0.2185118679023501,1.1960110930885794,-1.934898395538689,0.10871005477599532,0.14960005279656463,0.0077728040042090996,-0.04463090386676055,0.14260554206609433,0.14163983017286164,-0.04979506378791097,0.12875770843490786,0.05761597280820707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.641666666666666,0.0,1.0,1.0,1.0,3.393321429447042,-0.0004110001193243783,0.5924904064629941,0.9994077173361836,0.00839705768588423,0.015941295619471,0.029318578496773426,0.06304715626386502,-0.0002673113346554419,0.00018190409009829632,-0.01355164270124179,-0.06275148670249667,-0.08117585533727938,-0.2764980859129966,0.011831249684399772,-0.8353299981703458,-0.08170385594308913,0.39614407856209594,-0.9752849766517411,0.028932804430014298,-0.5978391138494745,0.9174948211933784,0.03092152840618689,-0.5805982323780564,0.9725160027112334,0.22960649447951287,1.2034374393966953,-1.9182984955734605,0.10979318985290865,0.1566797035123968,0.0017700207358672948,-0.04394668126984809,0.14807784455302064,0.13955792050644567,-0.04907232840634525,0.13412590384962453,0.05526871908144049,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.65,0.0,1.0,1.0,1.0,3.3938558233083604,-0.0003831079694588773,0.592474415863533,0.9994221809941375,0.008341893567995319,0.01568269036630957,0.028978788302760215,0.0653725032870081,-0.0005509851934819448,-7.2950132590037485e-06,-0.014005029796126542,-0.06200919404508874,-0.08139722977155654,-0.27453856107274965,0.021889681102001318,-0.8512440436819633,-0.08078454388403054,0.3974784625298537,-0.9752946905365933,0.028569388776476384,-0.5965828628181437,0.9186491096333909,0.030515562958199478,-0.5794587100432819,0.9729668748416763,0.24065167875942595,1.2103125164903743,-1.9004623034928314,0.1108071039243469,0.16338579549107224,-0.00397045266940399,-0.0432836293696047,0.1532936200150914,0.1374678816485031,-0.048369119959389,0.1392242690264811,0.05296046060733417,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.658333333333333,0.0,1.0,1.0,1.0,3.3944091309497586,-0.0003567688025810503,0.5924564961118526,0.9994364518346409,0.008284754658078833,0.015427127886511653,0.028638179230048504,0.06757001940921774,-0.0008205243982138725,-0.0001980814795531716,-0.014449594335136783,-0.0612662247623071,-0.08159301289466023,-0.27248722460033953,0.03200312495923934,-0.8670043698952263,-0.07985707087768334,0.3988671751536138,-0.9753511508628978,0.028211410607187553,-0.5952842201825563,0.9197859525541868,0.03011537640686374,-0.5782778278942817,0.973398677054689,0.25163499115926635,1.2166436309291366,-1.8814209733483467,0.11175190531804435,0.1697191552850108,-0.009449878063880757,-0.04264161244909623,0.15825097352796247,0.1353724146526214,-0.0476853402732829,0.1440519019791453,0.05069277851956544,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.666666666666666,0.0,1.0,1.0,1.0,3.3949802829805362,-0.00033195304868111514,0.5924366849060376,0.9994505276514991,0.008225681095104041,0.015174611587812364,0.028296856907095106,0.06963992557633926,-0.0010759835850751832,-0.0003902819938627713,-0.014885072694652973,-0.06052275163443987,-0.08176314473993065,-0.27034464455342855,0.04216707495082026,-0.8826010599044357,-0.0789220121287298,0.4003071151179372,-0.9754521885043247,0.027858695235658114,-0.5939453465926776,0.9209053165442679,0.029720807286978096,-0.5770578450102961,0.9738117544836691,0.2625436874860665,1.2224362967924283,-1.8612038476877113,0.11262783522792502,0.17568120987367375,-0.014669963389850604,-0.04202048016099538,0.16294835703798194,0.1332744857955781,-0.047020880118367886,0.1486082522468135,0.04846744702933892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.675,0.0,1.0,1.0,1.0,3.395568212659882,-0.0003086293247487633,0.592415019402388,0.9994644063558276,0.008164714075734844,0.014925144025208701,0.027954927073443717,0.07158260985108973,-0.001317437582809239,-0.000583712195650616,-0.015311208423443102,-0.05977902040821215,-0.08190763239294994,-0.26811149647557175,0.05237706323911315,-0.8980244340233549,-0.07797994029055126,0.40179519531817504,-0.9755956502527287,0.027511069271170963,-0.5925684142319233,0.9220071939841131,0.02933169507155761,-0.5758010236901682,0.9742064678385113,0.27336472385397825,1.2276942379286606,-1.8398385845927434,0.11343526279785437,0.18127390709882563,-0.019632785812000453,-0.04142007551062095,0.16738453726114821,0.13117730994772314,-0.04637562719230881,0.15289308013590075,0.046286425238042384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.683333333333334,0.0,1.0,1.0,1.0,3.3961718572142154,-0.0002867645079923798,0.5923915363120973,0.9994780859894752,0.008101895830403799,0.014678726591961594,0.02761249529482951,0.07339860887780177,-0.00154497999315102,-0.0007781760993371277,-0.015727751604945044,-0.05903535208371849,-0.08202655209189123,-0.2657885658225289,0.0626286455829646,-0.9132650363143148,-0.07703142441543223,0.40332834690291763,-0.9757794016011914,0.02716836064381443,-0.5911556043049918,0.9230916050433966,0.028947880167106282,-0.5745096270080311,0.9745831949043031,0.284084775828366,1.2324194077449413,-1.817351300697565,0.11417468200459524,0.18649965171017913,-0.024340727197993406,-0.04084024149320395,0.1715585742422343,0.12908433153192345,-0.045749472741024935,0.15690642734979443,0.04415184526798788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.691666666666666,0.0,1.0,1.0,1.0,3.396790159021007,-0.00026632381384037395,0.5923662720097843,0.9994915647376863,0.008037269600957785,0.014435359203376562,0.027269666669076247,0.07508859433696229,-0.001758722247661354,-0.0009734656713006025,-0.01613445867699478,-0.05829214415099808,-0.08212005146675777,-0.26337675021176565,0.07291738670152884,-0.9283136223683143,-0.07607702892380801,0.404903522846678,-0.9760013290393619,0.026830398579617564,-0.5897091046612194,0.9241585995096452,0.028569203859207193,-0.5731859165676716,0.9749423319263111,0.2946902616183411,1.2366120251207968,-1.79376672676123,0.11484671006357805,0.19136125604111043,-0.02879642118215342,-0.04028082648023609,0.17546980988730088,0.12699920315030644,-0.04514231690762413,0.16064859828379685,0.0420659969611914,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.7,0.0,1.0,1.0,1.0,3.3974220666991584,-0.00024727087972646486,0.592339262650881,0.9995048409409416,0.00797087961793408,0.014195039977578296,0.026926545522481183,0.07665336399067725,-0.0019587930769078853,-0.001169360573128466,-0.016531092663064878,-0.05754987082042359,-0.08218835181909782,-0.2608770614622232,0.08323884600164455,-0.9431611484270019,-0.07511731258103926,0.4065177011702695,-0.9762593419542273,0.026497013535810496,-0.5882311074735368,0.925208258429235,0.02819550821864588,-0.5718321503699678,0.9752842948536563,0.3051673691034529,1.2402706250996864,-1.7691083726516976,0.115452087074909,0.19586190418993454,-0.033002710974381344,-0.03974168845160608,0.17911786565163235,0.12492576196010408,-0.044554072902239644,0.1641201511359891,0.04003130938946997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.708333333333334,0.0,1.0,1.0,1.0,3.398066536142476,-0.00022956785548158473,0.5923105442950264,0.9995179131059262,0.00790277107573673,0.013957764917339186,0.02658323509678963,0.07809383688108955,-0.0021453383269062526,-0.0013656280820688559,-0.01691742376939843,-0.056809082280191596,-0.08223175034236097,-0.25829062739337477,0.09358856378652361,-0.9577987619125092,-0.07415282747255952,0.40816788791651026,-0.9765513742222682,0.02616803710542413,-0.5867238069003589,0.9262406955423136,0.0278266359775032,-0.5704505807154051,0.9756095204161356,0.3155020864486324,1.2433921231015546,-1.743398698882077,0.11599167662509124,0.20000512845342322,-0.036962617011557786,-0.03922269816972995,0.18250264847265107,0.12286800387774077,-0.04398467008582249,0.1673218978894253,0.038050329419474505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.716666666666667,0.0,1.0,1.0,1.0,3.398722531528972,-0.0002131755009695346,0.5922801530327536,0.9995307799155616,0.00783299010418867,0.013723527596910968,0.026239837227270284,0.07941105221530485,-0.002318521057597018,-0.0015620231993522609,-0.017293230302748146,-0.05607040300705229,-0.08225062218230295,-0.255618693354746,0.10396204805333713,-0.9722177934083699,-0.07318411797062108,0.40985111997782653,-0.9768753855710866,0.02584330189964833,-0.5851893966656593,0.927256058493864,0.027462430383882172,-0.5690434520718107,0.9759184670106476,0.3256802360333255,1.245971891492263,-1.7166592921094903,0.11646646706045372,0.2037947966743625,-0.040679313514189186,-0.03872374138966336,0.18562436396243776,0.1208300557027453,-0.043434056058761564,0.17025491215681754,0.036125697580540184,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.725,0.0,1.0,1.0,1.0,3.3993890263347244,-0.00019805329140838007,0.5922481251128815,0.999543440238048,0.007761583735140119,0.013492318857712135,0.025896452012816533,0.08060617144898892,-0.0024785218587591506,-0.0017582889567024336,-0.017658299863583863,-0.055334529151468005,-0.08224542223701456,-0.252862623459486,0.11435476197806133,-0.9864097501143341,-0.07221171968821863,0.41156446786108297,-0.977229362780838,0.025522641415596407,-0.5836300675009849,0.928254529804026,0.027102735043190506,-0.5676129988461248,0.9762116153758112,0.3356875113954838,1.2480038474282635,-1.6889110422516063,0.11687757315327257,0.2072351091289859,-0.044156113006650344,-0.03824472019540788,0.18848353581464083,0.1188161452740566,-0.04290219784261584,0.17292054381688793,0.03426012149665869,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.733333333333333,0.0,1.0,1.0,1.0,3.400065004376857,-0.0001841595306203918,0.5922144970681316,0.9995558931348474,0.007688599863015096,0.013264126516653629,0.025553177479407493,0.08168048306908371,-0.0026255393202909106,-0.001954156930356477,-0.018012430769830536,-0.05460222501522546,-0.08221668659756884,-0.2500239014981546,0.12476211217714152,-1.00036631077923,-0.07123615841806653,0.4133050384633096,-0.9776113207878641,0.025205889896391533,-0.5820480044020819,0.929236327581765,0.026747393753171908,-0.5661614430081959,0.9764894690355919,0.34550951686899145,1.249480550942248,-1.660174319080161,0.11722623788840536,0.21033060353642385,-0.047396457851489604,-0.037785553548761314,0.1910810303353072,0.1168305697970462,-0.042389082240089984,0.17532043933806474,0.032456347158411614,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.741666666666667,0.0,1.0,1.0,1.0,3.400749460906018,-0.00017145147224826202,0.5921793058365991,0.999568137867553,0.007614087198378797,0.013038935090814724,0.025210109238666022,0.08263540956506334,-0.0027597905955229944,-0.0021493479700026834,-0.018355433666069364,-0.05387431864015223,-0.08216503353219769,-0.2471041315116695,0.1351794378270988,-1.0140793220990034,-0.0702579490567452,0.41506997792002337,-0.9780193037450295,0.024892882189783718,-0.5804453836620631,0.9302017059673101,0.026396250339189006,-0.5646909915238237,0.9767525544951181,0.3551318095733985,1.2503933122862079,-1.6304691463486565,0.11751383410694538,0.21308616675514425,-0.05040391785819498,-0.03734617713340847,0.19341808496839086,0.114877662517896,-0.0418947154540391,0.1774565666516792,0.030717128338815236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.75,0.0,1.0,1.0,1.0,3.4014414037643808,-0.000159885448767346,0.5921425888768135,0.9995801739035776,0.007538095213809437,0.012816725542105348,0.024867340143644046,0.08347251607359808,-0.0028815119986663703,-0.0023435731477685854,-0.018687133273059098,-0.053151696528532306,-0.08209116392051005,-0.24410503800526465,0.14560200071524498,-1.0275407965517076,-0.06927759451628411,0.41685647457589536,-0.9784513860855006,0.024583453610834725,-0.5788243696526088,0.9311509552903966,0.02604914849560459,-0.5632038335640013,0.9770014211745721,0.3645399433994745,1.2507323075703742,-1.599815371674036,0.11774186575454565,0.21550705172635243,-0.053182193036158676,-0.03692654257180905,0.19549633965554758,0.11296175795763475,-0.04141912204328253,0.17933124340730355,0.02904519448365228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.758333333333333,0.0,1.0,1.0,1.0,3.4021398546209323,-0.00014941700791468933,0.5921043842742354,0.9995920009206036,0.0074606740815581375,0.012597475045464122,0.024524959944339276,0.08419352017813417,-0.0029909595802625256,-0.0025365349299940583,-0.01900737023232041,-0.052435297520333546,-0.0819958610488834,-0.24102846578834491,0.15602497628660503,-1.040742911626904,-0.06829558462750278,0.4186617621154626,-0.9789056736289655,0.0242774398135869,-0.5771871113344706,0.9320844019332707,0.02570593163846763,-0.5617021374670353,0.9772366410698456,0.37371951462122577,1.2504867017265815,-1.5682328305317217,0.1179119684957583,0.2175988982267607,-0.05573512058323349,-0.036526616089292904,0.1973178698436251,0.11108715596753083,-0.0409623432897057,0.18094716742602435,0.02744321744035272,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.766666666666666,0.0,1.0,1.0,1.0,3.4028438502914207,-0.00014000105594769817,0.5920647308371499,0.9996036188097399,0.007381874602681206,0.01238115678402792,0.024183054945802616,0.08480010258982021,-0.0030884023810439374,-0.002727872614471564,-0.019315958984132728,-0.05172636793184304,-0.08188001925392863,-0.23787637942824422,0.16644344574402134,-1.053678010393903,-0.0673123950413548,0.4204831228796747,-0.9793803047618879,0.023974676676013176,-0.5755357384885483,0.9330024078898554,0.025366442774109495,-0.5601880474402342,0.9774588081319113,0.3826568951732645,1.2496448113227505,-1.5357413118748164,0.11802611195196933,0.21936731568362178,-0.058066110037857666,-0.03614627401316316,0.19888462946462626,0.10925898452881722,-0.04052435759152595,0.18230695068450986,0.02591454498497292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.775,0.0,1.0,1.0,1.0,3.4035524408393267,-0.00013159206109040382,0.5920236691953503,0.9996150278788984,0.0073017485445154495,0.012167737604102747,0.023841707409385474,0.08529465049957266,-0.0031741669397539005,-0.002917399710838488,-0.019612901023325337,-0.05102543520915263,-0.08174457672250787,-0.2346508508687905,0.17685238980865087,-1.066338600158151,-0.06632848276163662,0.42231788404352294,-0.9798734421295965,0.023675001913367515,-0.5738723675100602,0.933905385008751,0.025030525678608865,-0.5586636882889602,0.9776685501529285,0.39133656300292086,1.248193828598334,-1.5023611868239772,0.11808586619288464,0.22081945093669897,-0.060180324088980885,-0.035785716175270044,0.2002007083927504,0.1074796788264476,-0.040105391319081585,0.18341495424114784,0.024460210380781167,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.783333333333333,0.0,1.0,1.0,1.0,3.404264703201861,-0.00012414429171818113,0.5919812376365051,0.9996262280142435,0.007220346592913458,0.011957186304977678,0.023500995836301716,0.08567953564480166,-0.0032485449695001806,-0.003104786525442917,-0.01989804039558917,-0.050333450451292894,-0.08159046009326144,-0.23135410337819554,0.18724667622066024,-1.078717363507636,-0.0653442972714734,0.424163447061953,-0.9803833101633709,0.02337824807309201,-0.5721990600153358,0.9347937358702962,0.024698019585458135,-0.5571311315362151,0.9778664783049243,0.39974437196925283,1.2461211342890488,-1.468113719485773,0.11809308937315771,0.22196265730517917,-0.06208242506507977,-0.0354449447387168,0.20126997967563343,0.1057528853948364,-0.039705525696772104,0.18427557062340005,0.023082198713852975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.791666666666666,0.0,1.0,1.0,1.0,3.4049797273356046,-0.0001176111687019354,0.5919374787989027,0.9996372199808519,0.007137721790902519,0.01174946185153477,0.023160994753824174,0.0859568366258996,-0.00331185493115373,-0.0032895961987543555,-0.02017119218551353,-0.049652031183183606,-0.08141879346041932,-0.22798844466930296,0.19762107538013501,-1.0908071621495805,-0.06436026460541733,0.4260172616652759,-0.9809081492140145,0.0230842528343889,-0.5705178678487997,0.9356679330986649,0.024368766916995997,-0.5555924287785702,0.9780532534648261,0.40786800449313043,1.2434135170485279,-1.4330199566234425,0.11805032089322182,0.2228036485830398,-0.06377580257596716,-0.035123733760971665,0.2020954904499317,0.1040842135459985,-0.03932466704997757,0.18489245969171453,0.021784153882664636,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.8,0.0,1.0,1.0,1.0,3.405696625252068,-0.00011194673581655077,0.5918924350287689,0.9996480045386286,0.007053926461080979,0.011544519631819223,0.022821773246961483,0.08612923582114966,-0.0033644905948690016,-0.0034715851668463316,-0.02043240773150277,-0.04898211334498387,-0.08123081923635668,-0.22455630330331003,0.2079702348381357,-1.10260102945136,-0.06337679192325303,0.4278768412050037,-0.9814462402063037,0.022792852510409148,-0.5688308018411703,0.9365284727627295,0.02404260846795851,-0.5540495905413532,0.9782295475363021,0.41569348558485486,1.2400565945554838,-1.3971013948933342,0.11795981521069254,0.2233503326827424,-0.06526535968840896,-0.03482218637134764,0.20268222519776558,0.10247670959050437,-0.038962974072735274,0.1852707614082738,0.020567533693698348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.808333333333334,0.0,1.0,1.0,1.0,3.4064145320044745,-0.00010710505682406749,0.5918461496850143,0.9996585826489499,0.006969013157298241,0.01134231082573481,0.02248339549482601,0.08619957786272102,-0.0034068220952549054,-0.0036504382811586673,-0.020681647716123477,-0.04832473353645121,-0.08102774899428607,-0.22106021990955538,0.21828868528939308,-1.1140921853978027,-0.06239426768523912,0.4297397672099883,-0.9819959052088213,0.022503883061533107,-0.5671398307621702,0.9373758782585067,0.023719384015783742,-0.552504582755099,0.9783960456930544,0.4232075838535848,1.2360363079319299,-1.3603808057214328,0.11782389503819421,0.22361115168369916,-0.06655610678498736,-0.03454032720798146,0.20303552650742018,0.10093357613326193,-0.03862055080390461,0.18541609271586879,0.019433851893875254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.816666666666666,0.0,1.0,1.0,1.0,3.407132607405904,-0.00010304046713498293,0.5917986671175622,0.9996689554732322,0.006883034491502798,0.011142782214503282,0.02214592048250755,0.08617091553480272,-0.003439245574765489,-0.0038258472821169815,-0.020918910183913626,-0.047680950260633057,-0.08081085912294195,-0.21750284357241695,0.22857083997033453,-1.1252740428800505,-0.06141306033928313,0.43160369373306534,-0.9825555086527201,0.022217180390276123,-0.56544687639938,0.9382106990316172,0.023398932621226765,-0.550959322329422,0.9785534450678667,0.43039749719336995,1.2313385845139602,-1.322881776310063,0.11764501991881518,0.22359507025617287,-0.06765323539624779,-0.034278156958759964,0.20316133799481495,0.09945780557583772,-0.03829747649435708,0.1853346126315225,0.018384410475835722,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.825,0.0,1.0,1.0,1.0,3.4078500377861407,-9.970775663074304e-05,0.5917500326377838,0.9996791243675583,0.00679604299184484,0.010945876182810935,0.0218094017529413,0.08604651254365553,-0.0034621770551299404,-0.003997512387018634,-0.02114422502669471,-0.04705181023027563,-0.08058148069624575,-0.21388692828966588,0.2388109950312924,-1.1361402150029705,-0.060433517353258866,0.43346635171425785,-0.9831234591320921,0.021932580445553775,-0.5637538084622566,0.9390335083514373,0.02308109274087779,-0.5494156725445736,0.9787024525343183,0.43725086237835387,1.2259494637971358,-1.28462881002684,0.11742575376465433,0.22331157602005325,-0.06856216600167553,-0.03403566495315764,0.2030662160498875,0.09805209621281952,-0.03799381779930465,0.18503303612986466,0.01742022178654601,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.833333333333334,0.0,1.0,1.0,1.0,3.4085660377500093,-9.706233065126491e-05,0.5917002924738275,0.9996890908748948,0.00670809097024577,0.010751530809587998,0.021473887204448316,0.08582984211613859,-0.0034760496647923537,-0.004165144540044438,-0.021357652522541112,-0.04643833068221294,-0.08034098876567494,-0.21021532919944438,0.24900333103362013,-1.1466845230471645,-0.059455964443205556,0.43532555333339956,-0.9836982114194147,0.021649919307723496,-0.5620624394652152,0.9398449006351642,0.022765702324571688,-0.5478754383939243,0.9788437820976424,0.44375578750275313,1.2198552323475615,-1.2456473920622146,0.11716874441981648,0.22277067456132005,-0.06928856641933878,-0.033812828984362275,0.2027573269259486,0.09671880853428405,-0.03770962807523405,0.18451863475398955,0.016541971747106032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.841666666666667,0.0,1.0,1.0,1.0,3.4092798519075527,-9.506036045947688e-05,0.5916494937070931,0.999698856715541,0.006619230390819169,0.010559680017316928,0.021139418932479108,0.08552458198144189,-0.0034813115225624256,-0.004328467972745587,-0.021559283176395206,-0.0458414863550849,-0.08009079179251863,-0.20649099849795333,0.25914191557041844,-1.156901004870674,-0.058480704946261924,0.43717919629027985,-0.9842782685724144,0.021369033295814403,-0.5603745196801575,0.9406454884936754,0.02245259893962389,-0.5463403619653404,0.9789781520634367,0.44990088999954714,1.2130425565533693,-1.2059640328313836,0.11687670675621806,0.2219828763495646,-0.0698383593450913,-0.033609612236053035,0.20224243336615988,0.09545993645921458,-0.03744494375633678,0.18379922706510898,0.01574999769461405,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.85,0.0,1.0,1.0,1.0,3.4099907565460565,-9.365892461490693e-05,0.5915976841889251,0.9997084237760905,0.006529512737897502,0.010370253770920733,0.02080603311567798,0.085134605678192,-0.003478423550832794,-0.004487222842791074,-0.02174923766242787,-0.04526219793934536,-0.0798323208794299,-0.20271698103278527,0.2692207069761763,-1.1667839235943542,-0.05750801933060192,0.43902526793922564,-0.9848621840751662,0.02108975910378928,-0.5586917322424458,0.9414358995761511,0.02214161992863274,-0.5448121179428391,0.9791062820592193,0.4556753352132331,1.2054986101660892,-1.165606293628274,0.11655240591797733,0.2209591745630013,-0.07021772397207027,-0.03342595982167795,0.20152987111024645,0.094277086246497,-0.03719978036186039,0.1828831593057334,0.01504427378499651,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.858333333333333,0.0,1.0,1.0,1.0,3.4106980612128335,-9.281614028877298e-05,0.5915449124377538,0.9997177940970605,0.006438988884433269,0.010183178322924792,0.020473759947711383,0.08466397007105139,-0.0034678570518548372,-0.004641167845334324,-0.021927666540124888,-0.0447013211857868,-0.07956701858086156,-0.19889640957773277,0.2792335590731866,-1.1763277764311453,-0.05653816484762897,0.4408618491996632,-0.9854485639719489,0.020811933965453104,-0.5570156884949867,0.9422167732644503,0.02183260260025955,-0.5432923093102449,0.9792288899598534,0.4610688737972962,1.1972111948605113,-1.1246027958472204,0.11619863972518032,0.21971101332055265,-0.07043309276936638,-0.033261795448431,0.20062851512798074,0.09317146120381814,-0.036974128653345095,0.18177927618291623,0.014424402240096335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.866666666666667,0.0,1.0,1.0,1.0,3.4114011101767594,-9.249128300755205e-05,0.5914912275174998,0.9997269698593221,0.006347708962113451,0.0099983765027705,0.02014262361683399,0.08411689899948978,-0.0034500910238536475,-0.004790082732777201,-0.02209474965105958,-0.04415963654440824,-0.07929632723108489,-0.19503249980283033,0.28917422689051814,-1.1855273035251412,-0.05557137533518225,0.44268711816123485,-0.9860360689546557,0.02053539584631543,-0.5553479236569795,0.9429887572628814,0.02152538445107699,-0.5417824633397905,0.979346688763221,0.4660718772553979,1.1881688525107859,-1.0829832143569984,0.1158182200145276,0.21825024606518584,-0.07049114350748953,-0.033117018298210385,0.19954773543284787,0.09214385190323915,-0.03676795103588058,0.18049688165062472,0.013889610195474411,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.875,0.0,1.0,1.0,1.0,3.4120992837361928,-9.264489326047507e-05,0.5914366788984761,0.9997359533694541,0.006255722234700769,0.00981576804805325,0.019812642335148914,0.08349776305075926,-0.003425609235660807,-0.004933770692181901,-0.02225069516989367,-0.043637839404091945,-0.07902167683396123,-0.19112854495680948,0.2990363732816997,-1.1943774966704286,-0.054607861180720176,0.44449935330074963,-0.9866234163637404,0.02025998366048293,-0.5536898929044393,0.9437525041295043,0.021219803416328207,-0.5402840279494011,0.9794603834631113,0.47067537132500503,1.1783609681410379,-1.0407782555680756,0.11541395297557988,0.21658908405668087,-0.07039878642245645,-0.03299150014559708,0.1982973424928991,0.09119463204260603,-0.03658117822780041,0.1790456896880266,0.013438752269188114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.883333333333333,0.0,1.0,1.0,1.0,3.4127919993411675,-9.323886851289399e-05,0.5913813163023556,0.9997447470441612,0.006163076976157389,0.009635269974980102,0.019483828419166245,0.08281105553277202,-0.0033948970950753014,-0.005072060534066149,-0.02239573830679331,-0.04313653105953564,-0.07874447262188626,-0.1871879102807469,0.30881357635953544,-1.2028736077846092,-0.05364780945225592,0.4462969362288462,-0.9872093820616966,0.019985537510555478,-0.5520429679487645,0.9445086677969249,0.020915698147280316,-0.5387983685116567,0.9795706679677074,0.47487106706389837,1.1677778627170832,-0.9980196208762804,0.11498861866851465,0.21474003514824092,-0.07016314643037092,-0.03288508272803324,0.19688752246539876,0.09032376015779331,-0.03641370621881898,0.17743576526193516,0.013070318997576713,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.891666666666666,0.0,1.0,1.0,1.0,3.413478712498786,-9.423653934594835e-05,0.5913251895330979,0.9997533533939015,0.006069820355087642,0.009456796984768983,0.019156188422719076,0.08206136481266543,-0.0033584383556952506,-0.005204808649175304,-0.0225301396711925,-0.042656210544164956,-0.07846608242897114,-0.18321402717241117,0.31849933766031774,-1.2110111570183666,-0.0526913842029116,0.44807835388655365,-0.9877928021375799,0.019711898948349044,-0.5504084341966826,0.9452579001321342,0.020612908312681224,-0.5373267651950355,0.9796782221130709,0.47865138958305353,1.156410875150199,-0.9547399563475301,0.11454494997795425,0.21271583325106147,-0.06979154039991053,-0.03279757538452312,0.1953287627254352,0.08953078733785924,-0.03626539353919413,0.17567745587965478,0.012782451208690482,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.9,0.0,1.0,1.0,1.0,3.4141589174325033,-9.56027286673328e-05,0.5912683482959957,0.9997617750058925,0.0059759983269701234,0.009280261902130988,0.018829723322631827,0.08125334327651254,-0.003316711713796726,-0.005331900692749289,-0.022654183316142443,-0.04219726746368957,-0.07818782404709641,-0.17921038712102935,0.3280870909453721,-1.2187859403904013,-0.05173872695262335,0.4498422001163639,-0.9883725744016951,0.01943891125414676,-0.5487874885700073,0.9460008475858892,0.02031127492162708,-0.5358704109136625,0.9797837088211856,0.48200950441739165,1.1442524331145554,-0.910972789703064,0.11408561130236264,0.21052935912194704,-0.06929144959742173,-0.03272875297899193,0.19363176839359175,0.08881487099898777,-0.03613605886221054,0.17378131436678546,0.012572960294534585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.908333333333333,0.0,1.0,1.0,1.0,3.4148321474685166,-9.730379319774532e-05,0.5912108420072617,0.9997700145266687,0.005881655535549305,0.00910557614143681,0.018504428756795647,0.0803916085169834,-0.003270225091945632,-0.005453266645528707,-0.022768178900455637,-0.04175989429529449,-0.07791097808632348,-0.1751805354321213,0.33757021154556033,-1.226194036846751,-0.05078995734787222,0.4515871765385861,-0.9889476596308703,0.01916641973203251,-0.5471812380567894,0.9467381479821173,0.020010640664977715,-0.5344304099555891,0.9798877714513131,0.4849385829386549,1.1312951762290013,-0.8667517254140611,0.11361288202473507,0.20819276689955313,-0.06866967358499787,-0.03267845612851761,0.1918074278043158,0.08817448665406236,-0.03602556744115901,0.17175792009069601,0.012439235230432555,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.916666666666666,0.0,1.0,1.0,1.0,3.415497974066689,-9.93083126798261e-05,0.5911527193805256,0.9997780739531331,0.005786835169632871,0.008932650870412326,0.018180295094149507,0.07948091855831309,-0.003219357964920412,-0.005568832162311497,-0.022872447022444033,-0.04134433377753246,-0.07763661087416673,-0.1711280774053851,0.3469420105491888,-1.2332318024806357,-0.04984517891887776,0.4533120795646898,-0.9895170689614451,0.018894270318671465,-0.545590698106602,0.9474704223634569,0.019710848797607764,-0.5330077789121509,0.9799910294083595,0.4874345822746545,1.1175354267702808,-0.8221131906775536,0.11312966967270979,0.20572034276903461,-0.06793550459176512,-0.03264616981994678,0.18986638632181752,0.08760851743161435,-0.03593345673343011,0.16961806761807363,0.012378650227697907,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.924999999999999,0.0,1.0,1.0,1.0,3.4161560100431716,-0.0001015844040276933,0.5910940290186538,0.999785957286184,0.005691579053055113,0.00876139543342122,0.01785730918394045,0.078525993182924,-0.00316456301839393,-0.005678578103249513,-0.02296732900012396,-0.04095067997640664,-0.07736589595322851,-0.16705662572754373,0.3561958019917317,-1.2398959233580436,-0.04890446285332706,0.45501584891807,-0.990079918040733,0.018622316901700065,-0.5440167982847591,0.9481982899393109,0.019411749719420546,-0.5316034421619545,0.9800940822884414,0.4894933473613594,1.1029696641705433,-0.77709309895448,0.1126384911529757,0.20312518728429318,-0.0670968763393498,-0.03263156176493802,0.1878196186397041,0.08711522586478004,-0.03585942771156689,0.16737256751655272,0.01238827451900848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.933333333333334,0.0,1.0,1.0,1.0,3.4168059057348077,-0.00010410386489868796,0.591034818022396,0.9997936666510671,0.005595927350840029,0.008591720157643984,0.017535451697395805,0.07753128583254225,-0.0031063391137097635,-0.005782535913249395,-0.023053177518380166,-0.04057875314329343,-0.07709993570580219,-0.16296985494936245,0.3653248382853645,-1.246183354129877,-0.047967870732994834,0.4566974993527613,-0.9906353502337676,0.0183504109559225,-0.5424603711292736,0.9489223427945366,0.01911319166908165,-0.5302182361202084,0.980197500650343,0.49110995555564974,1.087593567871128,-0.731726247827309,0.1121410657246491,0.20041842332902626,-0.06615992904059675,-0.03263447419451969,0.18567792511176018,0.08669199485682677,-0.035803322468765456,0.16503178075675473,0.012464771825424492,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.941666666666666,0.0,1.0,1.0,1.0,3.417447348404908,-0.00010683917512706474,0.5909751327175218,0.9998012047550856,0.005499918726442562,0.008423535811717103,0.017214700366566513,0.07650118092724122,-0.0030450399982944127,-0.005880736114019183,-0.023130348061478814,-0.040228350771209745,-0.07683951175374437,-0.15887145980161624,0.3743223614562505,-1.252091360821832,-0.04703544509124957,0.4583561559735538,-0.991182583524743,0.01807840899845807,-0.5409221661995631,0.949643156520258,0.018815027678274455,-0.5288529124826753,0.9803018284855318,0.49228201704333063,1.0714061187844437,-0.686049756664926,0.11163951391017515,0.19761268442929913,-0.06513303116550961,-0.032654381990614226,0.18345134296525512,0.08633658983861814,-0.035764636592167456,0.16260579173104084,0.012604856276769993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.95,0.0,1.0,1.0,1.0,3.418080061597016,-0.00010976432526244148,0.5909150180944441,0.9998085742783765,0.005403590199711139,0.008256754338897063,0.01689502945190194,0.07543992932631326,-0.002981047355436911,-0.005973259486037561,-0.0231992132434953,-0.03989912167754614,-0.07658540658716328,-0.15476515466530694,0.3831816069317719,-1.2576175167409591,-0.04610721216782525,0.45999104409324965,-0.9917209007531927,0.017806171256078928,-0.5394028487465193,0.9503612859585135,0.018517114392545525,-0.5275081395913577,0.9804075815882891,0.4930075908513948,1.0544071632240304,-0.6401006120073216,0.11113568866709458,0.19471973546708043,-0.06402388518021995,-0.032690822542375125,0.1811497672528728,0.08604642522733297,-0.03574291589458711,0.16010439667354825,0.012805094956034324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.958333333333334,0.0,1.0,1.0,1.0,3.418703803555521,-0.00011285472273447658,0.59085451765875,0.9998157778576826,0.005306977126138148,0.008091289356078064,0.01657641026205846,0.07435157353263075,-0.0029147136680233087,-0.006060215127982756,-0.023260148478160717,-0.03959059393482128,-0.07633827582628289,-0.15065466662075966,0.391895814176651,-1.2627597043552874,-0.04518318361346466,0.4616014848980051,-0.9922496482777466,0.01753356195608515,-0.5379030034120152,0.9510772636073802,0.01821931241336467,-0.5261845058714495,0.9805152467347991,0.4932855825281762,1.036597828298701,-0.5939159844451147,0.1106312361376903,0.19175077882749636,-0.06284003169092056,-0.03274329635895558,0.17878258856383944,0.08581875571222586,-0.03573766331098613,0.15753692028491528,0.013061991001097617,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.966666666666667,0.0,1.0,1.0,1.0,3.4193183653071446,-0.0001160871038616745,0.5907936732596268,0.9998228180710745,0.005210113192313175,0.00792705665618209,0.01625881169421304,0.07323990812695913,-0.0028463617698112724,-0.0061417414500524875,-0.02331352911565356,-0.039302176265588205,-0.0760986437968177,-0.14654372828983733,0.4004582374034169,-1.267516116481711,-0.04426335823219708,0.46318689040704125,-0.9927682346147081,0.017260449650096335,-0.536423138937122,0.9517915985537173,0.017921486670695756,-0.5248825242532758,0.9806252814383074,0.4931157629279209,1.017980523435037,-0.5475331345185719,0.11012759066138245,0.18871636357697064,-0.061588827172653904,-0.03281126453181571,0.17635858030596196,0.08565073456009431,-0.0357483366404774,0.15491210624289709,0.013372045197308502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.975,0.0,1.0,1.0,1.0,3.419923568423275,-0.00011943943956207591,0.5907325249246301,0.9998296974239198,0.005113030420039402,0.007763974696197386,0.015942200790148263,0.0721084426361068,-0.0027762836763213948,-0.0062180049458175676,-0.023359728219743563,-0.039033162541755845,-0.07586690006872965,-0.14243607057196098,0.4088621562339016,-1.2718852565972636,-0.04334772376910829,0.46474675762428796,-0.9932761287306242,0.016986707547221556,-0.5349636937402492,0.9525047758500484,0.017623506802690047,-0.5236026374340679,0.9807381141547542,0.49249877833786593,0.9985589320706934,-0.500989306461137,0.10962596928880255,0.18562629085541293,-0.06027740027184647,-0.03289414839704123,0.17388579837576357,0.08553946619866304,-0.03577434851300791,0.1522380204781637,0.013731808828654213,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.983333333333333,0.0,1.0,1.0,1.0,3.4205192624838965,-0.00012289083172050652,0.5906711107081071,0.9998364183362012,0.0050157591816326775,0.007601965062655682,0.015626543304745395,0.07096036723437484,-0.002704739491084558,-0.006289198273756754,-0.023399114027992364,-0.038782737952369584,-0.07564329703642893,-0.13833541531753957,0.4171008862712618,-1.2758659382560633,-0.04243625874405037,0.46628066192129813,-0.9937728579525722,0.01671221384347898,-0.533525042297526,0.953217256323695,0.01732524752881229,-0.522345223911973,0.980854144918785,0.4914361563313524,0.9783379994973362,-0.45432162216000105,0.1091273672498895,0.18248952558858167,-0.05891260648049235,-0.0329913302140139,0.17137148921509748,0.08548205779154827,-0.035815067432381706,0.1495219626140143,0.014137934593518864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.991666666666667,0.0,1.0,1.0,1.0,3.4211053222697516,-0.0001264214010468274,0.5906094665560677,0.9998429831313052,0.004918328226601758,0.00744095290892756,0.015311804281507977,0.06979852196480382,-0.0026319566943737247,-0.006355537977978022,-0.023432047474385636,-0.03854998640917896,-0.07542794891175081,-0.13424546796643844,0.4251677895588572,-1.2794572836332636,-0.041528934314943464,0.467788249717431,-0.9942580055052991,0.016436852043654658,-0.5321075022533309,0.9539294768132409,0.017026589012150352,-0.5211106047238343,0.9809737463979795,0.4899303086042084,0.9573239186078741,-0.40756697858900015,0.10863255574768388,0.17931411707350908,-0.057500984779135234,-0.03310215416904079,0.16882200730809593,0.08547566989482336,-0.03586981919721281,0.14677038632306516,0.014587225688433847,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.0,0.0,1.0,1.0,1.0,3.4216816447149774,-0.00013001216833105853,0.5905476261892191,0.9998493940263932,0.004820764718970749,0.007280867359669912,0.014997948628711606,0.06862537012275467,-0.0025581299018415157,-0.006417261940243028,-0.023458879928007197,-0.03833389899269237,-0.07522083231016141,-0.1301699101741361,0.43305628491472636,-1.2826587212325467,-0.040625716148255636,0.46926923053918995,-0.9947312076988911,0.016160511273994968,-0.5307113421757244,0.9546418508219421,0.016727417208858744,-0.5198990508065886,0.9810972653469255,0.4879845311587866,0.9355241149410876,-0.3607619501795645,0.10814208256979804,0.17610713019958202,-0.056048717639276546,-0.0332259275467333,0.16624274369842373,0.08551756541744782,-0.03593788854032179,0.14398883005732,0.015076682217267656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.008333333333333,0.0,1.0,1.0,1.0,3.4222481456575546,-0.0001336449313389139,0.590485621005379,0.9998556531244498,0.0047230942841180405,0.007121641878430237,0.014684941689321494,0.06744297637734713,-0.0024834211178188835,-0.006474626618213531,-0.023479951216443317,-0.03813338327760589,-0.07502178849936345,-0.12611239244712533,0.44075985814120866,-1.285469982802923,-0.039726566272113496,0.4707233685540907,-0.995192150799287,0.015883086584542436,-0.5293367898583572,0.9553547695701984,0.01642762420314499,-0.5187107908895456,0.981225024434934,0.48560300187776934,0.9129472322245702,-0.31394269707506695,0.10765627567503377,0.17287458880984485,-0.05456159531446625,-0.033361922036238036,0.16363806702594408,0.08560515597995755,-0.03601852094878587,0.14118185958862606,0.015603544001208114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.016666666666666,0.0,1.0,1.0,1.0,3.4228047564293744,-0.00013730213970411645,0.5904234800020774,0.9998617624080836,0.004625341063792643,0.006963214595073527,0.014372749797710827,0.06625299012363642,-0.0024079604838534484,-0.006527904121952713,-0.02349558797411184,-0.03794727337291136,-0.07483052730950007,-0.1220765268095066,0.4482720721184692,-1.287891099517131,-0.03883144488700507,0.4721504736860207,-0.9956405676207989,0.015604479240057667,-0.5279840410586253,0.956068603421608,0.01612710852637898,-0.5175460198134448,0.9813573244136123,0.48279077540474113,0.8896031194365916,-0.26714487994401903,0.10717524976056408,0.1696214324756895,-0.053044985187489235,-0.03350937515844286,0.1610112783752693,0.08573604478468555,-0.03611092464488333,0.13835302361918878,0.016165328922956856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.025,0.0,1.0,1.0,1.0,3.423351420331433,-0.0001409667701883917,0.5903612297197387,0.9998677237351314,0.004527527777826832,0.006805528590399902,0.014061340816338872,0.06505663446059032,-0.0023318475085701887,-0.0065773791828247505,-0.02350610234182798,-0.03777434050375346,-0.07464663265591076,-0.11806587952371297,0.4555865767984852,-1.2899223974686567,-0.03794031210943743,0.4735503924286855,-0.9960762338857452,0.015324596998568389,-0.5266532685521027,0.9567837036499431,0.0158257754590636,-0.5164049071625592,0.9814944465836499,0.47955377519619646,0.8655028201788517,-0.22040358179479913,0.10669891572334944,0.1663514877269423,-0.051503806834458654,-0.03366749180292391,0.15836458097086226,0.08590806517479788,-0.03621427270836034,0.1355048234928069,0.01675986602891033,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.033333333333333,0.0,1.0,1.0,1.0,3.4238880890425003,-0.00014462220462967926,0.5902988942054338,0.9998735388360838,0.004429675790970844,0.006648532136051245,0.013750684645839225,0.06385470108511182,-0.002255152753420549,-0.006623346070191756,-0.023511791033675962,-0.03761330395551542,-0.07446956958747684,-0.11408396388957,0.46269711912145006,-1.2915644925470444,-0.03705312962494925,0.47492299848146974,-0.9964989644013732,0.015043354376675602,-0.5253446313757776,0.9575004045078547,0.015523537314572974,-0.5152876060885647,0.9816366555140942,0.47589878258790574,0.8406585649034348,-0.1737532370144157,0.10622699285731813,0.16306745449912174,-0.04994251334132782,-0.03383544586299886,0.15569906547366452,0.08611931414150398,-0.03632770531961982,0.13263869777065063,0.017385322721554797,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.041666666666666,0.0,1.0,1.0,1.0,3.4244147190115637,-0.00014825211279495814,0.5902364949967913,0.9998792093133274,0.004331805183222767,0.00649217888856304,0.013440753702409209,0.0626475512776951,-0.002177919938691864,-0.006666105511923088,-0.02351293477801911,-0.037462842197771525,-0.07429869274188489,-0.11013423314724788,0.4695975528802091,-1.2928182847522303,-0.036169862228482126,0.4762681833370042,-0.9969086091081006,0.014760672900851741,-0.5240582841275416,0.9582190255523015,0.015220313703736603,-0.514194262199715,0.9817842019623425,0.47183342271327866,0.81508376627488,-0.12722756765368715,0.10575902356774053,0.15977090826731488,-0.04836507928357214,-0.03401238195880337,0.15301471133545963,0.0863681801458549,-0.036450332104653385,0.12975502215223145,0.018040225496285256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.049999999999999,0.0,1.0,1.0,1.0,3.4249312678852717,-0.00015184034220275822,0.5901740511252739,0.9998847366421686,0.004233934822014389,0.006336428037172089,0.013131523356945434,0.06143512303609072,-0.0021001684249990354,-0.006705961673941017,-0.0235097981305023,-0.037321604007497615,-0.07413325606307446,-0.10622007351101535,0.47628184855936473,-1.2936849520079392,-0.035290479232153574,0.47758584695259165,-0.9973050490560994,0.01447648134402888,-0.5227943861868533,0.9589398741769523,0.014916031779495418,-0.5131250223860275,0.9819373259390323,0.46736614711914676,0.7887930176625102,-0.08085952678926756,0.10529439033302446,0.15646231803250643,-0.046774995641643,-0.03419741724115764,0.15031040435552923,0.086653364738003,-0.03658123456450134,0.12685312492479728,0.018723473812956026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.058333333333334,0.0,1.0,1.0,1.0,3.425437691021573,-0.00015537081678538073,0.5901115791376728,0.9998901221735758,0.004136082434639647,0.0061812444057350495,0.01282297233102682,0.06021694429430575,-0.0020218960177145686,-0.006743219251872594,-0.02350262964839559,-0.03718821941602091,-0.07397242361365888,-0.10234479736192877,0.48274410317458427,-1.2941659435320514,-0.03441495572293172,0.478875888637546,-0.9976881923687947,0.014190715946832447,-0.5215531107216161,0.9596632482979349,0.014610626460994914,-0.5120800434509684,0.9820962598592251,0.4625062129419333,0.7618020944871817,-0.03468124863168942,0.10483233459965241,0.1531410800091182,-0.04517527177523517,-0.03438964327156329,0.14758397027714532,0.08697389758215657,-0.03671946857542293,0.12393131782277411,0.019434346832065685,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.066666666666666,0.0,1.0,1.0,1.0,3.425933938139686,-0.00015882744603187937,0.5900490931343523,0.9998953671385536,0.004038264679374509,0.0060265985098258345,0.0125150830455861,0.05899215204514968,-0.001943082035339684,-0.006778180724527629,-0.0234916624077712,-0.03706131031335803,-0.07381528129765795,-0.0985116366286498,0.4889785501341511,-1.2942629728184674,-0.0335432736554927,0.48013819828607696,-0.9980579702523533,0.013903320622836158,-0.5203346533489008,0.9603894391366549,0.014304040636571702,-0.5110595004223146,0.9822612317195667,0.45726365853285933,0.7341279578741888,0.01127599509189281,0.1043719772610785,0.14980556656305932,-0.04356844443760943,-0.034588127976896005,0.14483222394942485,0.08732914463436492,-0.03686406694890128,0.12098694188139358,0.02017250289180872,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.075,0.0,1.0,1.0,1.0,3.4264199501545263,-0.00016219404599227238,0.5899866048224994,0.9999004726540367,0.003940497213831896,0.0058724665707487935,0.012207841918910948,0.05775951707117223,-0.0018636905779244755,-0.006811143814520192,-0.023477114837658162,-0.03693950055585496,-0.07366084929550211,-0.09472373638638111,0.4949795691391541,-1.2939780102805198,-0.03267542276858041,0.48137264808026364,-0.9984143331094215,0.013614247147217514,-0.5191392403224591,0.961118734041841,0.013996225345179893,-0.5100635944196118,0.9824324682407553,0.451649275455685,0.705788759826379,0.05698183305599791,0.10391234034428681,0.14645318963967924,-0.04195659365499704,-0.03479191768012917,0.14205103328678748,0.08771880935434906,-0.037014042043493796,0.1180164275813822,0.02093797174896883,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.083333333333334,0.0,1.0,1.0,1.0,3.426895656240768,-0.00016545427324266704,0.5899241235824024,0.9999054397301723,0.003842794759221914,0.005718830488816671,0.011901239611465626,0.05651747388152645,-0.0017836739284569259,-0.006842399196214988,-0.023459191839149435,-0.03682142543833441,-0.07350809500480539,-0.09098414870438838,0.5007416961312574,-1.2933132756008674,-0.03181140131642125,0.4825790847800716,-0.9987572468132699,0.013323455328167338,-0.5179671361274544,0.9618514192925607,0.013687139935846806,-0.5090925599626249,0.9826101979153828,0.4456745768214365,0.6768038489148176,0.1024068272064449,0.10345236951073443,0.14308047765146714,-0.0403413651604545,-0.0350000392104681,0.13923539698284415,0.08814292697529869,-0.03716838842417431,0.11501536831300951,0.021731139748881745,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.091666666666667,0.0,1.0,1.0,1.0,3.4273609711679303,-0.00016859157261499616,0.5898616565446009,0.9999102692788389,0.003745171159336743,0.005565677778784843,0.011595271215893314,0.0552641553557763,-0.0017029760185861915,-0.006872228484722867,-0.023438086152243416,-0.03670574040969438,-0.07335594627641324,-0.0872958267726905,0.5062596332877344,-1.292271229827079,-0.03095121661006817,0.4837573227077881,-0.9990866891954291,0.013030913160376379,-0.516818650372745,0.9625877828247626,0.013376752204776987,-0.508146671614395,0.9827946539032366,0.4393517619715709,0.6471937753149359,0.14752250127398447,0.10299095697028526,0.13968316453797147,-0.038723998933680726,-0.035211502097870356,0.1363795346876362,0.08860185198637183,-0.03732608556619239,0.11197860593733289,0.022552728227958063,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.1,0.0,1.0,1.0,1.0,3.4278157929433233,-0.00017158913919275266,0.5897992086756292,0.9999149621232395,0.003647639433252034,0.005413001470798685,0.011289936391441003,0.05399743151096311,-0.0016215358902803311,-0.006900902533265817,-0.02341397992904573,-0.03659112893034932,-0.07320330473616606,-0.08366161933819553,0.511528259053173,-1.290854567246301,-0.0300948853669165,0.48490713752237113,-0.999402646795498,0.0127365969598695,-0.5156941438826604,0.9633281168256669,0.013065038509743599,-0.5072262498636694,0.9829860767191821,0.4326936775725104,0.6169802938932523,0.1923013656263528,0.10252696440878638,0.13625628948272794,-0.037105363276566106,-0.035425300858122136,0.13347698813276354,0.08909623911637299,-0.03748610060299574,0.10890032701263763,0.023403765578295932,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.108333333333333,0.0,1.0,1.0,1.0,3.4282600007944946,-0.00017442989477335375,0.5897367828699969,0.9999195190083914,0.003550211820922451,0.0052607999805923894,0.010985239442909342,0.05271495173689242,-0.0015392910868688224,-0.006928680058944308,-0.023387046469276397,-0.036476309390914556,-0.07304905898807473,-0.08008426547981533,0.5165426381859552,-1.2890662070666399,-0.02924243386992173,0.48602826086583356,-0.9997051119167052,0.012440491479407676,-0.5145940339038656,0.9640727201433689,0.012751983861393725,-0.5063316661641843,0.9831847166628749,0.4257137752386142,0.5861863639767595,0.2367169391331414,0.10205924554081015,0.13279430559202554,-0.03548599375042594,-0.03564041737404714,0.13052073150856547,0.0896270182260106,-0.03764739111846802,0.10577416806614837,0.024285553522744863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.116666666666667,0.0,1.0,1.0,1.0,3.4286934535170834,-0.00017709647870511514,0.5896743800460396,0.9999239406123295,0.003452899821045448,0.005109076952968709,0.010681189345066695,0.05141418978923022,-0.0014561809103903606,-0.006955806609181685,-0.0233574520724003,-0.03636004103314767,-0.07289209750381291,-0.0765663897508853,0.521298031786119,-1.2869092849274153,-0.02839389794123633,0.4871203759489049,-0.9999940800246717,0.01214259000363538,-0.5135187983575177,0.9648219004627671,0.012437581991102465,-0.5054633470625669,0.9833908359445612,0.41842606585661135,0.5548361444231986,0.2807437686640002,0.10158666791834935,0.12929119568996006,-0.033866136210030096,-0.03585582337832939,0.1275032892543182,0.09019536362580682,-0.03780890798396955,0.10259332814920086,0.025199628245764494,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.125,0.0,1.0,1.0,1.0,3.4291159882078768,-0.00017957125273036892,0.5896119992433092,0.999928227557837,0.0033557142207679305,0.0049578410827914015,0.010377799714249914,0.0500924907918553,-0.0013721494870472131,-0.006982513874235302,-0.023325357960444684,-0.0362411288361894,-0.07273132101707706,-0.07311049771553847,0.5257899072596752,-1.2843871442555732,-0.02754932273794924,0.4881831141273329,-1.0002695475202057,0.011842894423102187,-0.5124689790829603,0.965575976203799,0.012121835394994233,-0.5046217773616977,0.983604710466971,0.4108450708394798,0.5229549826458579,0.3243574467591426,0.10110813365451755,0.12574059328236298,-0.03224579310579179,-0.03607048304130205,0.12441685931661839,0.09080265843540714,-0.037969598240535606,0.09935068680904768,0.026147717116669078,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.133333333333333,0.0,1.0,1.0,1.0,3.4295274193964986,-0.00018183631920998394,0.5895496377192544,0.9999323804245169,0.0032586651170096225,0.004807105917830363,0.010075088729596868,0.048747235163762344,-0.0012871109994172644,-0.0070089060000743135,-0.02329076858725478,-0.03611893382596548,-0.0725657660894252,-0.06971897190356063,0.53001394816355,-1.2815033274814296,-0.026708762380327704,0.48921605250361094,-1.0005315099097682,0.011541415286280346,-0.511445184035574,0.9663352781033572,0.011804755353760205,-0.5038075022824161,0.983826631229839,0.40298643434597964,0.4905702924360411,0.36753497013658265,0.10062286907262435,0.12213625305322995,-0.0306240309738115,-0.036283459929268604,0.12125387666523713,0.09145107896458393,-0.03812856023516196,0.09603941533623095,0.027132118244814762,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.141666666666666,0.0,1.0,1.0,1.0,3.4299275405159895,-0.00018387289874706163,0.5894872929177407,0.999936400183913,0.003161763247780459,0.004656885444793568,0.00977307805971679,0.047375556004653714,-0.0012011180699942848,-0.0070354226399519364,-0.023254177613039953,-0.03599141190278784,-0.07239425817429894,-0.06639405714310548,0.5339660788002759,-1.2782615614199635,-0.02587227492007217,0.49021871834488673,-1.0007799480364359,0.01123817009094771,-0.5104480811385397,0.9671001608532087,0.011486359391074867,-0.5030211204394271,0.9840569124377179,0.39486427488582637,0.45770830165249965,0.4102534282480885,0.10012945077093535,0.11847107435347559,-0.0290019742499803,-0.03649355879245187,0.11800577925809241,0.09214103496570925,-0.03828448949275431,0.09265145921221185,0.028153906757442115,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.15,0.0,1.0,1.0,1.0,3.430316118307299,-0.0001856642012231957,0.589424954883172,0.9999402864649564,0.0030650144821416404,0.004507210166044817,0.009471795733659787,0.04597454973742614,-0.0011141206714668588,-0.007062247636922228,-0.02321570050773831,-0.03585736224364124,-0.07221563648027977,-0.06313790065546353,0.5376424198577583,-1.2746657703439614,-0.025039938200812115,0.4911905704095022,-1.001014876147268,0.010933189306406148,-0.5094784210479392,0.9678709620194523,0.011166680528880967,-0.5022633112955459,0.9842958630091297,0.3864941276065201,0.4243973000850043,0.45249143051475205,0.09962679529640577,0.11473807945037828,-0.027379396289655134,-0.03669964512595131,0.11466406601640333,0.09287414436188524,-0.03843624968206189,0.08917909624036158,0.02921500865139315,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.158333333333333,0.0,1.0,1.0,1.0,3.4306928978106086,-0.00018719077043487584,0.5893626180494749,0.9999440402632425,0.002968428546302281,0.004358104030623955,0.009171273130540704,0.04454162776049254,-0.0010260222569028813,-0.007089316477069631,-0.023175168388047552,-0.03571682641916103,-0.07202913466107433,-0.05995248834966348,0.541039367135026,-1.270720037578051,-0.02421182833179874,0.4921310196690597,-1.0012362713079301,0.010626509338848521,-0.5085370133715996,0.9686480632592401,0.010845755229707169,-0.5015348021687545,0.9845438292485744,0.3778933746963058,0.3906685862643422,0.49422969772246805,0.09911463495261202,0.11093113453041092,-0.02575420186621713,-0.036900848731756704,0.11122141190958112,0.09365359279171814,-0.03858307128089603,0.08561581028142529,0.03031842490593295,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.166666666666666,0.0,1.0,1.0,1.0,3.431057602649985,-0.0001884341810148216,0.589300273509612,0.9999476621144405,0.0028720127717299063,0.004209597197186,0.008871544657233348,0.0430742513414963,-0.00093689088446805,-0.0071169106398816,-0.023132943267366573,-0.03556855093477592,-0.07183394647266629,-0.05683967774385843,0.544153562962164,-1.2664286087152536,-0.02338802761826858,0.4930394226516757,-1.0014441128450382,0.01031817516087687,-0.5076247308494461,0.9694318552326476,0.010523629340866033,-0.5008363811241888,0.9848011700908953,0.3690778451048811,0.3565525958661264,0.5354491834190878,0.09859225466977803,0.10704394208171819,-0.024126424833919025,-0.03709613618034308,0.10767033661283287,0.09448071099970923,-0.03872387410942136,0.08195459090552637,0.03146578510060616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.174999999999999,0.0,1.0,1.0,1.0,3.431409935578962,-0.0001893759391535411,0.5892379109037853,0.9999511525660136,0.002775773812829856,0.004061724012593922,0.008572648445085214,0.041569999862865685,-0.0008467426459397866,-0.007145187413482101,-0.023089189023651077,-0.03541159265589731,-0.0716292280781377,-0.05380119093124879,0.5469819103994614,-1.2617958845210662,-0.02256862408730244,0.49391508537042167,-1.0016383783884955,0.01000824040250947,-0.5067425077613857,0.970222741775902,0.01020035732788348,-0.500168892320329,0.9850682590002512,0.3600638945874987,0.3220810781024297,0.5761319215581606,0.098059052020694,0.10307064105471775,-0.022495803868372022,-0.03728447600983672,0.10400370411676185,0.0953570897295486,-0.038857633922194205,0.07818893732463361,0.032658814860169194,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.183333333333334,0.0,1.0,1.0,1.0,3.431749579905772,-0.00018999760250643967,0.589175518544943,0.9999545121905534,0.0026797176129494003,0.003914522468258446,0.008274625952095466,0.040026643937440515,-0.0007556146520362033,-0.0071742894849958685,-0.023044079516196664,-0.03524510985042372,-0.0714142269620767,-0.050838612834066786,0.5495215809305378,-1.2568264100226176,-0.021753710084590348,0.49475726666925435,-1.001819042909511,0.009696767227379591,-0.5058913357808335,0.9710211400614734,0.009876002108829463,-0.49953323216877826,0.9853454836718981,0.3508680371540032,0.2872866576259314,0.6162611941166274,0.09751458418839995,0.09900583183274247,-0.020862058370645364,-0.03746485322286063,0.10021491779062641,0.09628427936495099,-0.03898334752455025,0.07431285286954914,0.033899144201783304,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.191666666666666,0.0,1.0,1.0,1.0,3.432076201262865,-0.0001902808737926316,0.5891130834691467,0.9999577415966502,0.0025838493632743998,0.0037680339034946338,0.0079775215949064,0.038442184021314454,-0.0006635629548803388,-0.007204350688118524,-0.022997798641929933,-0.035068323623466846,-0.07118827719021635,-0.047953390312015405,0.5517700213598936,-1.2515248646191224,-0.020943381017495773,0.49556518256763404,-1.0019860793613395,0.00938382618212846,-0.505072259131542,0.9718274797653178,0.009550634869140975,-0.4989303447725032,0.9856332447369476,0.34150685648539764,0.25220273829640316,0.6558214582910438,0.09695855524581617,0.09484468333019747,-0.019225021603714865,-0.03763627212798947,0.09629800739984651,0.09726369418455061,-0.039100035047530714,0.07032093344296997,0.03518821290853458,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.2,0.0,1.0,1.0,1.0,3.432389449673242,-0.00019020768714189388,0.5890505914678662,0.9999608414383548,0.0024881734652570145,0.0036223027828807468,0.007681382391616761,0.036814883900283174,-0.0005706617385699358,-0.007235498031435805,-0.022950539921707716,-0.034880505375127574,-0.0709507979824266,-0.04514683189264349,0.5537249599021445,-1.2458960523844336,-0.020137734163826745,0.4963380113914243,-1.0021394599362397,0.009069496025246433,-0.504286368990836,0.972642201631216,0.009224334858037284,-0.49836121661139543,0.9859319538870404,0.33199693651839,0.2168634030124883,0.6947983340811392,0.0963908107434884,0.09058302040963029,-0.017584699602966047,-0.037797758583363976,0.0922477157869861,0.09829655017755679,-0.03920674193001388,0.06620845341343995,0.036527210708126034,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.208333333333334,0.0,1.0,1.0,1.0,3.4326889618767202,-0.0001897602931853102,0.5889880271085786,0.9999638124235681,0.002392693491955154,0.0034773765039199096,0.0073862576060607895,0.03514329976276948,-0.0004770027267573298,-0.007267853400046899,-0.022902506812345434,-0.03468097076562435,-0.07070129363124754,-0.042420108036708905,0.5553844114101018,-1.2399448923844367,-0.0193368675051043,0.4970748995744612,-1.0022791576880556,0.008753863539072393,-0.5035347972017589,0.9734657556016104,0.00889718917030741,-0.49782687054894587,0.986242031582083,0.32235479967172187,0.18130330706950692,0.7331786039051646,0.09581133509246276,0.08621739849256516,-0.015941309999525366,-0.037948362200538495,0.08805957648827967,0.09938381760084436,-0.03930254084802267,0.061971441576104125,0.03791703177716377,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.216666666666667,0.0,1.0,1.0,1.0,3.432974363879672,-0.00018892134352804373,0.5889253737441108,0.9999666553214426,0.0022974121473834327,0.003333305224463082,0.00709219839153715,0.03342630485257667,-0.0003826944272590847,-0.007301535297801137,-0.022853913105326393,-0.034469075187403976,-0.07043935349183596,-0.039774251898114794,0.5567466816866363,-1.2336764089860142,-0.018540878578952365,0.49777496803296706,-1.0024051484362317,0.008437023321904125,-0.502818709382698,0.97429859859123,0.00856929251057024,-0.4973283592517937,0.9865639044166598,0.312596849080702,0.14555756520449048,0.7709502126366763,0.09522024884758597,0.0817451664961022,-0.014295312927350423,-0.038087158866942916,0.0837299803064262,0.10052618093140175,-0.03938653394513464,0.057606745897235134,0.03935823675953909,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.225,0.0,1.0,1.0,1.0,3.433245273691072,-0.00018767397389052326,0.5888626135108626,0.9999693709688126,0.0022023312242179906,0.0031901417078793568,0.0067992574353572584,0.03166310963538601,-0.0002878611358347912,-0.007336660622498977,-0.02280498321274473,-0.03424420947918641,-0.07016465147822935,-0.03721016055203054,0.5578103708301766,-1.2270957221738255,-0.017749863357644533,0.4984373190160629,-1.0025174129035115,0.008119077557956678,-0.5021392975299851,0.9751411919504671,0.0082407469378885,-0.4968667581173253,0.986898002194742,0.30273931381155667,0.10966163322337019,0.8081022648889347,0.09461780492654774,0.07716451815165004,-0.012647436678467905,-0.038213253448280506,0.07925623025277995,0.10172400403995585,-0.03945785522629995,0.0531120867692636,0.04085102039844024,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.233333333333333,0.0,1.0,1.0,1.0,3.433501304207282,-0.00018600188492524534,0.5887997273163155,0.9999719602756567,0.0021074515605340512,0.003047941185975468,0.006507488606931894,0.02985327746324151,-0.00019264170431523606,-0.007373346433361958,-0.022755952290086114,-0.03400579560721643,-0.06987694485892185,-0.03472859666792218,0.5585743755736925,-1.220208037904532,-0.016963915163509903,0.49906104333549456,-1.0026159390475395,0.007800135764432783,-0.5014977722118183,0.9759939986585626,0.007911661590131907,-0.4964431578056393,0.9872447547566338,0.29279819690258835,0.07365118556366346,0.8446250183422288,0.09400438352131474,0.07247453175209473,-0.010998698717337163,-0.03832578251388429,0.07463658466432044,0.10297730015355278,-0.03951567296012443,0.04848609872419085,0.042395184426398114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.241666666666667,0.0,1.0,1.0,1.0,3.4337420662081626,-0.00018388941973328384,0.5887366948164656,0.9999744242295967,0.0020127729963202567,0.0029067612399393925,0.006216946612496588,0.02799673579439148,-9.71881024352749e-05,-0.00741171167572323,-0.022707066190367907,-0.033753282302597935,-0.06957607231491554,-0.032330190603654066,0.559037890589571,-1.2130186385347883,-0.016183123632289288,0.49964522787859783,-1.0027007245488004,0.0074803145160586065,-0.5008953544522464,0.9768574802863597,0.0075821523885530925,-0.4960586564719221,0.9876045886018486,0.2827892263691686,0.03756199038799535,0.8805098724179894,0.09338048573463574,0.06767519853786319,-0.009350422270419934,-0.03842391698035578,0.06987028855251598,0.10428570666157766,-0.03955919198815999,0.04372836071848352,0.043990115748471226,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.25,0.0,1.0,1.0,1.0,3.4339671714279056,-0.0001813216372127182,0.5886734943839819,0.9999767638994489,0.001918294330489226,0.0027666616994030395,0.00592768665950298,0.02609378310200096,-1.663810321633416e-06,-0.007451878833900658,-0.022658581259317977,-0.03348614071034547,-0.06926195130296232,-0.030015442895102707,0.5592004087468258,-1.205532873364232,-0.015407573734599308,0.5001889633111256,-1.0027717794187132,0.00715973714809352,-0.5003332674026097,0.9777320937695889,0.007252341723662574,-0.4957143517936646,0.9879779233524416,0.27272780939381613,0.0014297839292187753,0.91574935176721,0.09274672608632357,0.06276744012381319,-0.007704248686679627,-0.03850686460890103,0.06495759345216623,0.10564846490506152,-0.039587655881485766,0.03883941527089152,0.04563476999617455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.258333333333333,0.0,1.0,1.0,1.0,3.4341762356654266,-0.00017828438050679097,0.588610103068019,0.9999789804378574,0.0018240132790442137,0.002627704559436367,0.005639764133421273,0.024145091675975932,9.375791919685478e-05,-0.007493975488157122,-0.022610763987378706,-0.033203860118263484,-0.0689345748033588,-0.02778472711375713,0.5590617203217246,-1.1977561493386681,-0.014637344864183895,0.5006913518806614,-1.0028291286935784,0.006838533439243589,-0.4998127278947103,0.9786182880347774,0.006922358123861663,-0.4954113328840739,0.9883651681017849,0.26262898992666406,-0.034709854153287534,0.950337084136752,0.0921038240800904,0.05775311554156337,-0.00606214582154152,-0.038573872314867225,0.05989976624014126,0.10706440504223425,-0.0396003489074852,0.033820776914417205,0.04732766046604775,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.266666666666666,0.0,1.0,1.0,1.0,3.4343688819011216,-0.00017476433996602682,0.5885464965467003,0.9999810750830405,0.001729926434985483,0.002489953915001588,0.0053532342893201825,0.0221517065852061,0.0001888958892213413,-0.007538135755753013,-0.022563890537366307,-0.032905943830529215,-0.06859400754767116,-0.02563829306299164,0.5586219111776043,-1.189693921961953,-0.013872509999931134,0.5011515152368183,-1.0028728151824056,0.0065168392761790666,-0.49933493796527406,0.9795165005202928,0.006592335908537821,-0.4951506721784243,0.9887667176935424,0.2525074098921085,-0.07082162264908876,0.9842677722494786,0.09145259503842332,0.052635018633064856,-0.004426412765230481,-0.03862422826130342,0.05469908756131736,0.10853193600752986,-0.0395965977827501,0.02867493057846615,0.049066852374510805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.275,0.0,1.0,1.0,1.0,3.4345447433892877,-0.0001707491101852874,0.5884826490733479,0.9999830491596994,0.0016360292304541816,0.0023534759121403826,0.005068151960175703,0.02011504111943759,0.0002835628404628301,-0.007584501600724668,-0.022518246167969644,-0.032591905242979564,-0.06824038182748202,-0.02357627028222199,0.5578813599442398,-1.1813516864678435,-0.01311313494687684,0.5015686021912125,-1.0029029022396656,0.006194796301555199,-0.49890107643535503,0.9804271536349028,0.006262414827482495,-0.4949334173744328,0.9891829489746934,0.24237727415638108,-0.10687061620037408,1.017537159413191,0.09079394041511375,0.047416866661544876,-0.002799681293290668,-0.038657263716274995,0.04935884064318441,0.11004904049726427,-0.03957577319654376,0.02340532065632228,0.050849962274917004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.283333333333333,0.0,1.0,1.0,1.0,3.434703466698344,-0.00016622724081893269,0.5884185334175557,0.9999849040791374,0.0015423159015232751,0.0022183387149487545,0.004784571283433806,0.018036869071856795,0.0003775673502002371,-0.007633224000918001,-0.02247412457388085,-0.03226126416767974,-0.06787389298546709,-0.021598671827051955,0.5568407342409314,-1.1727349693050664,-0.012359277659679238,0.5019417963478441,-1.0029194765372937,0.005872551547574483,-0.498512290621221,0.9813506511952472,0.005932739688595425,-0.4947605835008189,0.989614217064791,0.23225231936361598,-0.14282243662246286,1.0501419886508812,0.09012883778852715,0.04210328110898054,-0.0011849144603237605,-0.038672354660399484,0.04388329139841218,0.11161327483214523,-0.03953729109439818,0.018016331631381943,0.05267416240451572,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.291666666666666,0.0,1.0,1.0,1.0,3.4348447146741634,-0.00016118828101335954,0.5883541208022128,0.9999866413386447,0.0014487794559537757,0.002084612487216737,0.004502545446935637,0.01591931425634199,0.0004707157155910001,-0.007684463964732979,-0.02243182716331028,-0.03191354344501737,-0.06749479468664359,-0.01970539829282839,0.5555009860005321,-1.1638493199903288,-0.011610987650401387,0.5022703235430288,-1.0029226508140043,0.005550257057215208,-0.4981696882453815,0.9822873748821053,0.005603459975909192,-0.49463314518057644,0.9900608516814353,0.22214578669986879,-0.17864329665275402,1.0820799552252147,0.08945833072658047,0.03669976170450395,0.00041459721052294896,-0.038668923136073854,0.03827766080792161,0.11322177347269369,-0.039480613716294334,0.01251326121587737,0.05453618966127838,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.299999999999999,0.0,1.0,1.0,1.0,3.434968169305223,-0.00015562281742096545,0.588289380837551,0.9999882625202093,0.0013554116441464336,0.001952369387469419,0.004222126454916524,0.013765213776720603,0.0005627867928437349,-0.007738374718586586,-0.02239166166431845,-0.03154831678517576,-0.06710355614745682,-0.01789624204872081,0.5538633459633855,-1.1547003033846461,-0.010868305480902897,0.5025534590429191,-1.002912566583785,0.005228069495306586,-0.49787432960775563,0.9832376807531255,0.005274729459990519,-0.49455202914722096,0.9905231535591457,0.21207041168669116,-0.21430010431987112,1.1133505998248427,0.0887835332665346,0.031212938234721488,0.001995833526646784,-0.038646703809901914,0.03254956581936863,0.1148700247104828,-0.039405510354835645,0.006903553543148311,0.05643125037144703,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.308333333333334,0.0,1.0,1.0,1.0,3.435073540744909,-0.00014952290371288097,0.5882242817388723,0.999989769046689,0.0012622029375728694,0.0018216831530491744,0.003943363562199321,0.011576883957410708,0.0006536413064323768,-0.007795157514107653,-0.022353937505776144,-0.031165010376665917,-0.06670027559748662,-0.016170891431383536,0.5519293175952009,-1.1452934766599148,-0.010131262095959144,0.5027905391802742,-1.0028893869218936,0.004906145327050176,-0.49762719548172535,0.9842018752939466,0.0049467014699952645,-0.4945180859548573,0.9910013725209594,0.20203835920427052,-0.24975999869169208,1.1439514806850415,0.0881055800959137,0.02564999664567802,0.003553608444466505,-0.03860478336597634,0.026703951101697543,0.11655630638619074,-0.039311117248009425,0.0011925083547970061,0.05835696217513231,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.316666666666666,0.0,1.0,1.0,1.0,3.4351605495906137,-0.00014288046958223566,0.5881587894265019,0.9999911631074624,0.0011691425418937308,0.001692630744348373,0.003666307933693915,0.009357097042532,0.0007430894808776437,-0.00785504323137995,-0.022318981759315834,-0.030763122952075943,-0.06628524608352107,-0.014528936061982967,0.549700679318524,-1.1356344453732288,-0.009399879145971003,0.5029809589870138,-1.0028533397763773,0.00458465643920698,-0.49742926375606067,0.985180285859562,0.004619544172523696,-0.49453215400797434,0.9914957695953979,0.19206120804758545,-0.28499221513773376,1.173882711742431,0.08742559500858092,0.020018238740688865,0.005083703016817154,-0.03854259092004413,0.020747663537272754,0.1182771656395265,-0.03919690252573509,-0.004612988721345301,0.060309478459172894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.325,0.0,1.0,1.0,1.0,3.435228952204784,-0.00013568981080665346,0.5880928679770618,0.9999924463200189,0.0010762182403383986,0.0015652900969535142,0.003391006357347384,0.007109704285881729,0.0008308934897305832,-0.00791820937175598,-0.022287122683001058,-0.030342262030814648,-0.06585918499899783,-0.012969871297257112,0.5471794473429054,-1.125728764797541,-0.008674168845816128,0.503124176492619,-1.00280465853828,0.004263768811716107,-0.49728140108943747,0.9861731613879388,0.004293419761233013,-0.49459496910021306,0.992006530495279,0.18215006575251239,-0.3199668334093908,1.2031471444069863,0.08674481780263224,0.014326263471871048,0.006582922254732004,-0.038460193141665586,0.014691489374811795,0.12002615361396796,-0.03906296239599552,-0.010502603600347493,0.06228218058735635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.333333333333334,0.0,1.0,1.0,1.0,3.435278533381509,-0.0001279459128074652,0.5880264800862771,0.9999936205822948,0.0009834165411772727,0.0014397414685326263,0.003117503989375544,0.004838300037041105,0.0009169005565548324,-0.00798485773105278,-0.022258682005080275,-0.02990189292683671,-0.06542251867525098,-0.011493101632774427,0.5443678987617008,-1.1155819929664457,-0.007954132182593799,0.5032197300448783,-1.002743624405465,0.00394365322017922,-0.4971844055998138,0.9871807217531281,0.003968494799257104,-0.49470719740131347,0.9925338059385205,0.17231547353091792,-0.354653665100928,1.231745441837755,0.0860645301274412,0.008583756872613257,0.008045849107429781,-0.03835713292184571,0.008544372231534814,0.12179911517769648,-0.038908883008342665,-0.016467385433673876,0.06427036156108512,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.341666666666667,0.0,1.0,1.0,1.0,3.435309109381605,-0.00011964490393984857,0.5879595863167122,0.9999946878618464,0.0008907225900481538,0.0013160672760203324,0.0028458440366389225,0.0025467829468074255,0.001000938287840887,-0.008055235178275576,-0.022233992422779274,-0.02944149877320257,-0.06497573231332666,-0.01009794673840848,0.5412685529245566,-1.105199674100245,-0.007239760010358775,0.5032672391071625,-1.002670561053156,0.0036244832630186784,-0.49713899488557856,0.9882031466409004,0.003644938377760635,-0.4948694255241076,0.9930777031879637,0.1625673265828256,-0.3890241752180845,1.2596795642806091,0.08538595638328529,0.0028007359748327687,0.009467306242174622,-0.03823310427920959,0.0023163358847999582,0.12359103075880729,-0.038734393604570413,-0.02249744843522139,0.06626861440226728,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.35,0.0,1.0,1.0,1.0,3.435320529965395,-0.0001107840558152336,0.5878921451793437,0.9999956501920643,0.0007981201704808996,0.0011943521107384166,0.002576067580581163,0.0002392864612115866,0.0010828430926047698,-0.008129591137291527,-0.022213387772704807,-0.028960555799700482,-0.06451934702404592,-0.008783646189727334,0.537884162508066,-1.0945873335617688,-0.006531032909539044,0.5032664089777922,-1.0025858359680955,0.0033064348155257273,-0.4971458000017338,0.9892405722657749,0.0033229215725142634,-0.4950821548752338,0.9936382828452249,0.15291494930520752,-0.42305088834010185,1.2869519803455587,0.08471033232968353,-0.0030122153237321925,0.010841911995864706,-0.03808786110187382,-0.003981923453003633,0.12539653818649965,-0.038539282500446324,-0.02858227462233187,0.06827119950756355,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.358333333333333,0.0,1.0,1.0,1.0,3.43531268026834,-0.00010136178180534414,0.587824113099187,0.9999965096678758,0.0007055916980666874,0.0010746827819893522,0.002308213451934369,-0.0020798395298734893,0.001162460975053325,-0.00820818596691225,-0.02219720358066523,-0.028458529090911996,-0.06405391019454103,-0.007549364249988355,0.5342177047855549,-1.083750474427819,-0.005827921138197383,0.5032170355184337,-1.0024898625198917,0.002989685577987448,-0.49720536027646195,0.9902930889440087,0.0030026170027531965,-0.49534579676781315,0.9942155565130898,0.1433670919260686,-0.4567073761063267,1.3135655116684086,0.08403889503682122,-0.00884396240894425,0.012164031344545911,-0.03792120944637764,-0.010339117465844039,0.12721000471163313,-0.03832338873558969,-0.03471078772592673,0.07027211942733036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.366666666666667,0.0,1.0,1.0,1.0,3.4352854825276404,-9.137763288579849e-05,0.5877554443613168,0.9999972684411148,0.0006131182165322375,0.0009571483673259274,0.0020423181349835907,-0.0044060461982360025,0.0012396483303113558,-0.008291292369820957,-0.022185776570815018,-0.02793487157692546,-0.0635799895394383,-0.00639419465762619,0.5302723729062939,-1.072694575033962,-0.005130384658925357,0.5031190096043098,-1.002383102112353,0.0026744146580861,-0.49731811862616454,0.9913607390109688,0.002684198426921102,-0.49566066800399927,0.9948094848356804,0.1339319321628561,-0.48996825175259495,1.3395232203123886,0.08337287497898868,-0.01468285543132497,0.013427772679750483,-0.037733004432076715,-0.016743421323183183,0.12902556352199834,-0.0380865987272103,-0.040871405974347574,0.07226515877249096,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.375,0.0,1.0,1.0,1.0,3.435238897666205,-8.083229047080777e-05,0.5876860910562278,0.9999979287156362,0.0005206793961534261,0.0008418402644419325,0.0017784156918454162,-0.0067346024105248625,0.0013142726648717904,-0.008379195392309672,-0.022179444143967934,-0.02738902385098741,-0.06309816888736719,-0.00531716538060742,0.5260515672563449,-1.0614250874226125,-0.004438373221880905,0.5029723212612449,-1.0022660663085625,0.0023608021707861694,-0.497484417298515,0.9924435150027087,0.0023678403572996915,-0.4960269868673856,0.9954199758259646,0.12461708086796858,-0.5228091542233937,1.364828299104941,0.08271349006644982,-0.020516766122851138,0.014626991476536233,-0.037523148498852354,-0.02318252322951131,0.13083714476133768,-0.03782884438302416,-0.04705208974844943,0.07424391763115823,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.383333333333333,0.0,1.0,1.0,1.0,3.4351729267422004,-6.972755654771814e-05,0.5876160030281943,0.9999984927422227,0.0004282535343050797,0.0007288522428739987,0.001516537701840189,-0.009060610288149735,0.0013862131960240612,-0.008472192101416816,-0.02217854390757965,-0.026820414353860452,-0.06260904491306009,-0.004317243309826714,0.5215588870025707,-1.0499474367155464,-0.0037518264911511933,0.5027770635022623,-1.0021393189210774,0.002049028849771894,-0.49770449401332306,0.9935413580903244,0.0020537176872040324,-0.49644486949980676,0.9960468834628664,0.11542959064065707,-0.5552067199927557,1.3894839584987562,0.0820619409940951,-0.026333122372350637,0.01575529396087294,-0.03729159014885066,-0.0296436706170633,0.13263850574624758,-0.03755010173330885,-0.05324038631295602,0.07620184355548787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.391666666666666,0.0,1.0,1.0,1.0,3.435087612273856,-5.806634156112695e-05,0.5875451278274754,0.9999989628133114,0.0003358175578921724,0.0006182804942814699,0.0012567132130004294,-0.011379019534433354,0.0014553613259821034,-0.008570591142049904,-0.022183413262464338,-0.02622845984030188,-0.06211322447918624,-0.0033933388699298023,0.5167981219231323,-1.0382670214476333,-0.0030706742053126534,0.5025334358883724,-1.0020034780758813,0.0017392756683053251,-0.49797847847546606,0.9946541567651461,0.0017420053284112108,-0.4969143266392682,0.9966900065518894,0.10637596680159016,-0.5871385426820352,1.4134933088755597,0.08141940757464361,-0.032118939576197825,0.016806039566730213,-0.03703832286144472,-0.03611371313896439,0.1344232609120244,-0.0372503897569382,-0.05942347160689421,0.07813226284481445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +13.4,0.0,1.0,1.0,1.0,3.434983039450376,-4.5852650513515105e-05,0.58747341066667,0.9999993412575578,0.00024334702741928628,0.0005102236801943017,0.000998968703595273,-0.013684640407945379,0.0015216209968394359,-0.008674712215509195,-0.02219438904167895,-0.025612566107785083,-0.061611322444163244,-0.0025443105298002112,0.5117732446245368,-1.0263892149009537,-0.002394836364907133,0.502241747842659,-1.001859218261632,0.0014317234687478153,-0.4983063892323058,0.9957817457721915,0.001432877857921729,-0.497435260693255,0.9973490878436133,0.09746218033321045,-0.6185831209303871,1.4368592381412792,0.08078704588602131,-0.037860848361830346,0.01777234200073252,-0.03676338407546915,-0.0425791422191768,0.13618491132598942,-0.03692976928990077,-0.06558818878624639,0.08002841105942293,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/LoadMotions.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/LoadMotions.h new file mode 100644 index 000000000..dceda785c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/LoadMotions.h @@ -0,0 +1,64 @@ +// +// Created by rgrandia on 05.10.21. +// + +#pragma once + +#include +#include +#include + +namespace switched_model { + +/** + * Struct to store the result of reading a csv file with 1 header and lines of floating point data + */ +struct CsvData { + std::vector header; + std::vector data; +}; + +/** + * Read a csv file with 1 header and lines of floating point data + */ +CsvData readCsv(const std::string& fileName); + +/** + * Convert csv data into a motion reference and gait + * + * Expects the following header: + * time, contactflag_LF, contactflag_RF, contactflag_LH, contactflag_RH, base_positionInWorld_x, base_positionInWorld_y, + * base_positionInWorld_z, base_quaternion_w, base_quaternion_x, base_quaternion_y, base_quaternion_z, base_linearvelocityInBase_x, + * base_linearvelocityInBase_y, base_linearvelocityInBase_z, base_angularvelocityInBase_x, base_angularvelocityInBase_y, + * base_angularvelocityInBase_z, jointAngle_LF_HAA, jointAngle_LF_HFE, jointAngle_LF_KFE, jointAngle_RF_HAA, jointAngle_RF_HFE, + * jointAngle_RF_KFE, jointAngle_LH_HAA, jointAngle_LH_HFE, jointAngle_LH_KFE, jointAngle_RH_HAA, jointAngle_RH_HFE, jointAngle_RH_KFE, + * jointVelocity_LF_HAA, jointVelocity_LF_HFE, jointVelocity_LF_KFE, jointVelocity_RF_HAA, jointVelocity_RF_HFE, jointVelocity_RF_KFE, + * jointVelocity_LH_HAA, jointVelocity_LH_HFE, jointVelocity_LH_KFE, jointVelocity_RH_HAA, jointVelocity_RH_HFE, jointVelocity_RH_KFE, + * contactForcesInWorld_LF_x, contactForcesInWorld_LF_y, contactForcesInWorld_LF_z, contactForcesInWorld_RF_x, contactForcesInWorld_RF_y, + * contactForcesInWorld_RF_z, contactForcesInWorld_LH_x, contactForcesInWorld_LH_y, contactForcesInWorld_LH_z, contactForcesInWorld_RH_x, + * contactForcesInWorld_RH_y, contactForcesInWorld_RH_z + * + * @param fileName : absolute path of the file + * @param dt : approximate sampling interval. Reference points closer than this dt will be dropped. Set to negative to load all points. + * @return reference motion and gait + */ +std::pair readMotion(const CsvData& csvData, scalar_t dt = -1.0); + +void verifyHeader(const std::vector& provided); + +/** + * Convert csv data into a cartesian motion reference and gait + * + * Expects the following header: + * + * @param fileName : absolute path of the file + * @param dt : approximate sampling interval. Reference points closer than this dt will be dropped. Set to negative to load all points. + * @return reference motion and gait + */ +std::pair readCartesianMotion(const CsvData& csvData, scalar_t dt = -1.0); + +void verifyCartesianHeader(const std::vector& provided); + +void verifyHeaderImpl(const std::vector& expected, const std::vector& provided); + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ModeSequenceKeyboard.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ModeSequenceKeyboard.h new file mode 100644 index 000000000..56d6e9765 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ModeSequenceKeyboard.h @@ -0,0 +1,41 @@ +/* + * ModeSequence_Keyboard_Quadruped.h + * + * Created on: Oct 11, 2018 + * Author: farbod + */ + +#pragma once + +#include +#include + +#include + +#include +#include + +namespace switched_model { + +/** This class implements ModeSequence communication using ROS. */ +class ModeSequenceKeyboard { + public: + ModeSequenceKeyboard(ros::NodeHandle nodeHandle, const std::string& gaitFile, const std::string& robotName, bool verbose = false); + + /** Prints the command line interface and responds to user input. Function returns after one user input. */ + void getKeyboardCommand(); + + private: + /** Prints the list of available gaits. */ + void printGaitList(const std::vector& gaitList) const; + + /** Publishes the mode sequence template. */ + void publishModeSequenceTemplate(const ModeSequenceTemplate& modeSchedule); + + std::vector gaitList_; + std::map gaitMap_; + + ros::Publisher modeSequenceTemplatePublisher_; +}; + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandController.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandController.h new file mode 100644 index 000000000..c6e25b26d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandController.h @@ -0,0 +1,29 @@ +// +// Created by rgrandia on 14.10.21. +// + +#pragma once + +#include "ocs2_anymal_commands/MotionCommandInterface.h" + +#include + +#include +#include +#include + +namespace switched_model { + +class MotionCommandController : public MotionCommandInterface { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + MotionCommandController(ros::NodeHandle& nodeHandle, const std::string& configFile, const std::string& controllerName); + ~MotionCommandController() override = default; + + void publishMotion(const std::pair& motion) override; + + private: + ros::ServiceClient client; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandDummy.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandDummy.h new file mode 100644 index 000000000..e8310b3f6 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandDummy.h @@ -0,0 +1,42 @@ +// +// Created by rgrandia on 14.10.21. +// + +#pragma once + +#include "ocs2_anymal_commands/MotionCommandInterface.h" + +#include + +#include +#include +#include + +namespace switched_model { + +class MotionCommandDummy : public MotionCommandInterface { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + MotionCommandDummy(ros::NodeHandle& nodeHandle, const std::string& configFile, const std::string& robotName); + ~MotionCommandDummy() override = default; + + void publishMotion(const std::pair& motion) override; + + private: + void observationCallback(const ocs2_msgs::mpc_observation::ConstPtr& msg); + + void terrainCallback(const visualization_msgs::Marker::ConstPtr& msg); + + ros::Publisher targetTrajectoryPublisher_; + ros::Publisher gaitSequencePublisher_; + + ros::Subscriber observationSubscriber_; + std::mutex observationMutex_; + std::unique_ptr observationPtr_; + + ros::Subscriber terrainSubscriber_; + std::mutex terrainMutex_; + TerrainPlane localTerrain_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandInterface.h new file mode 100644 index 000000000..1fe9b8f67 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/MotionCommandInterface.h @@ -0,0 +1,33 @@ +// +// Created by Timon Kaufmann in June 2021 +// + +#pragma once + +#include +#include + +#include + +#include +#include + +namespace switched_model { + +class MotionCommandInterface { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + explicit MotionCommandInterface(const std::string& configFile); + virtual ~MotionCommandInterface() = default; + + virtual void publishMotion(const std::pair& motion) = 0; + + void getKeyboardCommand(); + + private: + void printAnimationList() const; + + std::unordered_map> motionData_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/PoseCommandToCostDesiredRos.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/PoseCommandToCostDesiredRos.h new file mode 100644 index 000000000..f97c9fbdb --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/PoseCommandToCostDesiredRos.h @@ -0,0 +1,41 @@ +// +// Created by rgrandia on 04.05.20. +// + +#pragma once + +#include + +#include +#include + +#include +#include + +#include +#include + +namespace switched_model { + +class PoseCommandToCostDesiredRos { + public: + scalar_t targetDisplacementVelocity; + scalar_t targetRotationVelocity; + scalar_t comHeight; + joint_coordinate_t defaultJointState; + + PoseCommandToCostDesiredRos(::ros::NodeHandle& nodeHandle, const std::string& configFile); + + ocs2::TargetTrajectories commandLineToTargetTrajectories(const vector_t& commadLineTarget, const ocs2::SystemObservation& observation) const; + + private: + scalar_t desiredTimeToTarget(scalar_t dyaw, scalar_t dx, scalar_t dy) const; + + void terrainCallback(const visualization_msgs::Marker::ConstPtr& msg); + + TerrainPlane localTerrain_; + mutable std::mutex terrainMutex_; + ros::Subscriber terrainSubscriber_; +}; + +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ReferenceExtrapolation.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ReferenceExtrapolation.h new file mode 100644 index 000000000..6988f09e8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/ReferenceExtrapolation.h @@ -0,0 +1,60 @@ +// +// Created by rgrandia on 02.03.20. +// + +#pragma once + +#include + +#include + +namespace switched_model { + +struct BaseReferenceHorizon { + double dt; + size_t N; +}; + +struct BaseReferenceState { + double t0; + Eigen::Vector3d positionInWorld; + Eigen::Vector3d eulerXyz; +}; + +struct BaseReferenceCommand { + double headingVelocity; + double lateralVelocity; + double yawRate; + double baseHeight; +}; + +struct Base2dReferenceTrajectory { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + std::vector time; + std::vector yaw; + std::vector positionInWorld; +}; + +struct BaseReferenceTrajectory { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + std::vector time; + std::vector eulerXyz; + std::vector positionInWorld; + std::vector linearVelocityInWorld; + std::vector angularVelocityInWorld; +}; + +Eigen::Vector2d velocityCommand2dInWorld(double headingVelocity, double lateralVelocity, double yaw); + +Base2dReferenceTrajectory generate2DExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command); + +BaseReferenceTrajectory generateExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command, + const switched_model::TerrainPlane& projectedHeadingFrame); + +BaseReferenceTrajectory generateExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command, const grid_map::GridMap& gridMap, + double nominalStanceWidthInHeading, double nominalStanceWidthLateral); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/TerrainAdaptation.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/TerrainAdaptation.h new file mode 100644 index 000000000..8c27bc1f8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/include/ocs2_anymal_commands/TerrainAdaptation.h @@ -0,0 +1,76 @@ +// +// Created by rgrandia on 04.05.20. +// + +#pragma once + +#include +#include +#include +#include + +namespace switched_model { + +/** + * Creates a desired position at a height above the given terrain. The x-y coordinated remain the same + */ +vector3_t adaptDesiredPositionHeightToTerrain(const vector3_t& desiredPosition, const TerrainPlane& terrainPlane, scalar_t desiredHeight); + +/** + * Creates a desired position at a height above the given terrain. The x-y coordinated remain the same + */ +vector3_t adaptDesiredPositionHeightToTerrain(const vector2_t& desiredXYPosition, const TerrainPlane& terrainPlane, scalar_t desiredHeight); + +/** + * Return euler angles XYZ from a rotation matrix. When a reference yaw is given, the yaw angle is chosen as close as possible to the + * reference. + */ +vector3_t eulerXYZFromRotationMatrix(const matrix3_t& orientationTargetToWorld, scalar_t referenceYaw = 0.0); + +/** + * Return the x-axis of the body frame expressed in world coordinates. + */ +vector3_t getHeadingVectorInWorld(const vector3_t& eulerXYZ); + +/** + * Compute the yaw angle around the world Z that leads to the current heading projected to the XY plane + * + * @param eulerXYZ : current body eulerXYZ from which the heading vector is derived. + * @return Angle between the world X axis and the projected heading frame + */ +scalar_t getHeadingAngleInWorld(const vector3_t& eulerXYZ); + +/** + * Returns a rotation matrix from the "projected heading frame" to world. See definition below. + */ +matrix3_t getOrientationProjectedHeadingFrameToWorld(const vector3_t& headingVector, const TerrainPlane& terrainPlane); + +/** + * The heading of the robot refers to the x-axis of the body frame. + * + * The "projected heading frame" is defined as follows: + * - the x-Axis points in same direction as the given x-axis of the body frame in world when both are projected to the world XY plane. + * - z-Axis is the surface normal. + * - y-Axis is found from the right hand rule. + * - the origin is the same as to origin of the terrain projected to. + * + * @param eulerXYZ : current body eulerXYZ from which the heading vector is derived. + * @param terrainPlane : plane to project the heading on. + * @return projected heading frame + */ +TerrainPlane getProjectedHeadingFrame(const vector3_t& eulerXYZ, const TerrainPlane& terrainPlane); + +/** + * Modifies a desired orientation such that the body z-axis is aligned with the surface normal and the heading vector (x-axis) projected + * onto the terrain still points in the same direction. The orientation is the same as that of the projected heading frame defined above. + * @return adapted euler angles XYZ + */ +vector3_t alignDesiredOrientationToTerrain(const vector3_t& desiredEulerXYZ, const TerrainPlane& terrainPlane); + +/** + * Advances an orientation w.r.t world frame by applying a rotation around a given axis + * @return integrated eulerXYZ (continuous yaw) target to world + */ +vector3_t advanceOrientationInWorld(const vector3_t& eulerXYZ, const vector3_t& unitRotationAxisInWorld, double angle); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/package.xml new file mode 100644 index 000000000..861a2a4db --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/package.xml @@ -0,0 +1,21 @@ + + + ocs2_anymal_commands + 0.0.0 + The ocs2_anymal_commands package + + Farbod Farshidian + Jan Carius + Ruben Grandia + + TODO + + catkin + + roslib + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_interface + grid_map_filters_rsl + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalGaitNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalGaitNode.cpp new file mode 100644 index 000000000..53edffb85 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalGaitNode.cpp @@ -0,0 +1,28 @@ +/* + * AnymalModeSequenceCommand.cpp + * + * Created on: Oct 11, 2018 + * Author: farbod + */ + +#include + +#include "ocs2_anymal_commands/ModeSequenceKeyboard.h" + +int main(int argc, char* argv[]) { + const std::string robotName = "anymal"; + std::string gaitFile = ros::package::getPath("ocs2_anymal_commands") + "/config/gait.info"; + std::cerr << "Loading gait file: " << gaitFile << std::endl; + + ros::init(argc, argv, robotName + "_mpc_mode_sequence"); + ros::NodeHandle nodeHandle; + + switched_model::ModeSequenceKeyboard modeSequenceCommand(nodeHandle, gaitFile, robotName, true); + + while (ros::ok() && ros::master::check()) { + modeSequenceCommand.getKeyboardCommand(); + } + + // Successful exit + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalMotionCommandNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalMotionCommandNode.cpp new file mode 100644 index 000000000..102d6f6a7 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalMotionCommandNode.cpp @@ -0,0 +1,39 @@ + +#include + +#include "ocs2_anymal_commands/MotionCommandController.h" +#include "ocs2_anymal_commands/MotionCommandDummy.h" + +int main(int argc, char* argv[]) { + const std::string robotName = "anymal"; + std::string motionFile = ros::package::getPath("ocs2_anymal_commands") + "/config/motions.info"; + std::cerr << "Loading motion file: " << motionFile << std::endl; + + const std::string controllerName = [&] { + std::vector programArgs{}; + ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() <= 1) { + throw std::runtime_error("No operation mode specified. Aborting."); + } + return programArgs[1]; + }(); + + ros::init(argc, argv, robotName + "_mpc_motion_command"); + ros::NodeHandle nodeHandle; + + std::unique_ptr motionCommandInterface; + if (controllerName == "dummy") { + motionCommandInterface.reset(new switched_model::MotionCommandDummy(nodeHandle, motionFile, robotName)); + } else { + motionCommandInterface.reset(new switched_model::MotionCommandController(nodeHandle, motionFile, controllerName)); + } + + ros::Rate rate(10); + while (ros::ok() && ros::master::check()) { + motionCommandInterface->getKeyboardCommand(); + rate.sleep(); + } + + // Successful exit + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalPoseCommandNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalPoseCommandNode.cpp new file mode 100644 index 000000000..21681a770 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/AnymalPoseCommandNode.cpp @@ -0,0 +1,41 @@ +#include + +#include +#include +#include + +#include "ocs2_anymal_commands/PoseCommandToCostDesiredRos.h" + +int main(int argc, char* argv[]) { + const std::string robotName = "anymal"; + + const std::string filename = [&] { + std::vector programArgs{}; + ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() <= 1) { + throw std::runtime_error("No task file specified. Aborting."); + } + return programArgs[1]; + }(); + + // ros node handle + ::ros::init(argc, argv, robotName + "_mpc_pose_command_node"); + ::ros::NodeHandle nodeHandle; + + // PoseCommand To TargetTrajectories + switched_model::PoseCommandToCostDesiredRos targetPoseCommand(nodeHandle, filename); + auto commandLineToTargetTrajectoriesFun = [&](const ocs2::vector_t& commandLineTarget, const ocs2::SystemObservation& observation) { + return targetPoseCommand.commandLineToTargetTrajectories(commandLineTarget, observation); + }; + + // goalPose: [deltaX, deltaY, deltaZ, Roll, Pitch, deltaYaw] + const ocs2::scalar_array_t relativeBaseLimit{10.0, 10.0, 0.2, 45.0, 45.0, 360.0}; + ocs2::TargetTrajectoriesKeyboardPublisher targetTrajectoriesKeyboardPublisher( + nodeHandle, robotName, relativeBaseLimit, commandLineToTargetTrajectoriesFun); + + const std::string commandMsg = "Enter XYZ displacement and RollPitchYaw for the robot, separated by spaces"; + targetTrajectoriesKeyboardPublisher.publishKeyboardCommand(commandMsg); + + // Successful exit + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/LoadMotions.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/LoadMotions.cpp new file mode 100644 index 000000000..f60b62168 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/LoadMotions.cpp @@ -0,0 +1,361 @@ +// +// Created by rgrandia on 05.10.21. +// + +#include "ocs2_anymal_commands/LoadMotions.h" + +#include +#include +#include +#include + +namespace switched_model { + +CsvData readCsv(const std::string& fileName) { + CsvData result; + + // Create an input filestream + std::ifstream myFile(fileName); + std::string line; + + // Make sure the file is open + if (!myFile.is_open() || myFile.bad()) { + throw std::runtime_error("Could not open file: " + fileName); + } + + { // Read the column names + if (std::getline(myFile, line)) { + std::istringstream ss(line); + + std::string colname; + // Extract each column name + while (std::getline(ss, colname, ',')) { + // Remove additional endline marker generated in python or windows. + colname.erase(std::remove(colname.begin(), colname.end(), '\r'), colname.end()); + + result.header.push_back(colname); + ss >> std::ws; // remove white space + } + } + } + const size_t numCols = result.header.size(); + + while (std::getline(myFile, line)) { + std::istringstream ss(line); + result.data.emplace_back(vector_t::Zero(numCols)); + + int colIdx = 0; + scalar_t val; + while (ss >> val) { + // Add current value to the right column + result.data.back()[colIdx] = val; + colIdx++; + + // If the next token is a comma, ignore it and move on + if (ss.peek() == ',') { + ss.ignore(); + ss >> std::ws; // remove white space + } + } + } + + myFile.close(); + + return result; +} + +std::pair readMotion(const CsvData& csvData, scalar_t dt) { + verifyHeader(csvData.header); + + const auto numDataPoints = csvData.data.size(); + const scalar_t t0 = csvData.data.front()[0]; + const scalar_t duration = csvData.data.back()[0] - t0; + + const auto getMode = [](const vector_t dataLine) -> size_t { + const contact_flag_t contactFlags{dataLine[1] > 0.5, dataLine[2] > 0.5, dataLine[3] > 0.5, dataLine[4] > 0.5}; + return stanceLeg2ModeNumber(contactFlags); + }; + + ocs2::TargetTrajectories targetTrajectories; + targetTrajectories.timeTrajectory.reserve(numDataPoints); + targetTrajectories.stateTrajectory.reserve(numDataPoints); + targetTrajectories.inputTrajectory.reserve(numDataPoints); + + Gait gait; + gait.duration = duration; + gait.modeSequence.push_back(getMode(csvData.data.front())); + for (const auto& dataLine : csvData.data) { + const scalar_t t = dataLine[0]; + + // Extend gait if the mode changes + const size_t mode = getMode(dataLine); + if (mode != gait.modeSequence.back()) { + gait.eventPhases.push_back((t - t0) / duration); + gait.modeSequence.push_back(mode); + } else { + // Drop a point if dt is smaller than desired + if (!targetTrajectories.empty() && t < targetTrajectories.timeTrajectory.back() + dt) { + continue; + } + } + + // Time trajectory + targetTrajectories.timeTrajectory.push_back(t); + + // Read the test of the line + size_t colId = 5; // after time and 4 contact flags + const vector3_t basePositionInWorld = dataLine.segment(colId, 3); + colId += 3; + const Eigen::Quaterniond quaternion = + Eigen::Quaterniond(dataLine[colId], dataLine[colId + 1], dataLine[colId + 2], dataLine[colId + 3]).normalized(); + colId += 4; + const vector3_t baseLinearvelocityInBase = dataLine.segment(colId, 3); + colId += 3; + const vector3_t baseAngularvelocityInBase = dataLine.segment(colId, 3); + colId += 3; + const joint_coordinate_t jointPositions = dataLine.segment(colId, JOINT_COORDINATE_SIZE); + colId += JOINT_COORDINATE_SIZE; + const joint_coordinate_t jointVelocities = dataLine.segment(colId, JOINT_COORDINATE_SIZE); + colId += JOINT_COORDINATE_SIZE; + const vector_t contactForces = dataLine.segment(colId, 3 * NUM_CONTACT_POINTS); + + // Convert orientation to ocs2 convention + auto newOrientation = eulerAnglesFromQuaternionBaseToOrigin(quaternion); + ocs2::makeEulerAnglesUnique(newOrientation); + const auto prevYaw = targetTrajectories.stateTrajectory.empty() ? 0.0 : targetTrajectories.stateTrajectory.back()[2]; + const auto newYaw = ocs2::moduloAngleWithReference(newOrientation[2], prevYaw); + const vector3_t eulerXYZ(newOrientation[0], newOrientation[1], newYaw); + const matrix3_t o_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + + assert(o_R_b.isApprox(quaternion.toRotationMatrix())); + + vector_t contactForcesInBase(3 * NUM_CONTACT_POINTS); + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + contactForcesInBase.segment<3>(3 * i) = o_R_b.transpose() * contactForces.segment<3>(3 * i); + } + + // State trajectory + targetTrajectories.stateTrajectory.push_back(vector_t(STATE_DIM)); + targetTrajectories.stateTrajectory.back() << eulerXYZ, basePositionInWorld, baseAngularvelocityInBase, baseLinearvelocityInBase, + jointPositions; + + // Input trajectory + targetTrajectories.inputTrajectory.push_back(vector_t(INPUT_DIM)); + targetTrajectories.inputTrajectory.back() << contactForcesInBase, jointVelocities; + } + return {targetTrajectories, gait}; +} + +void verifyHeader(const std::vector& provided) { + const std::vector expectedHeader = {"time", + "contactflag_LF", + "contactflag_RF", + "contactflag_LH", + "contactflag_RH", + "base_positionInWorld_x", + "base_positionInWorld_y", + "base_positionInWorld_z", + "base_quaternion_w", + "base_quaternion_x", + "base_quaternion_y", + "base_quaternion_z", + "base_linearvelocityInBase_x", + "base_linearvelocityInBase_y", + "base_linearvelocityInBase_z", + "base_angularvelocityInBase_x", + "base_angularvelocityInBase_y", + "base_angularvelocityInBase_z", + "jointAngle_LF_HAA", + "jointAngle_LF_HFE", + "jointAngle_LF_KFE", + "jointAngle_RF_HAA", + "jointAngle_RF_HFE", + "jointAngle_RF_KFE", + "jointAngle_LH_HAA", + "jointAngle_LH_HFE", + "jointAngle_LH_KFE", + "jointAngle_RH_HAA", + "jointAngle_RH_HFE", + "jointAngle_RH_KFE", + "jointVelocity_LF_HAA", + "jointVelocity_LF_HFE", + "jointVelocity_LF_KFE", + "jointVelocity_RF_HAA", + "jointVelocity_RF_HFE", + "jointVelocity_RF_KFE", + "jointVelocity_LH_HAA", + "jointVelocity_LH_HFE", + "jointVelocity_LH_KFE", + "jointVelocity_RH_HAA", + "jointVelocity_RH_HFE", + "jointVelocity_RH_KFE", + "contactForcesInWorld_LF_x", + "contactForcesInWorld_LF_y", + "contactForcesInWorld_LF_z", + "contactForcesInWorld_RF_x", + "contactForcesInWorld_RF_y", + "contactForcesInWorld_RF_z", + "contactForcesInWorld_LH_x", + "contactForcesInWorld_LH_y", + "contactForcesInWorld_LH_z", + "contactForcesInWorld_RH_x", + "contactForcesInWorld_RH_y", + "contactForcesInWorld_RH_z"}; + verifyHeaderImpl(expectedHeader, provided); +} + +std::pair readCartesianMotion(const CsvData& csvData, scalar_t dt) { + verifyCartesianHeader(csvData.header); + + const auto numDataPoints = csvData.data.size(); + const scalar_t t0 = csvData.data.front()[0]; + const scalar_t duration = csvData.data.back()[0] - t0; + + const auto getMode = [](const vector_t dataLine) -> size_t { + const contact_flag_t contactFlags{dataLine[1] > 0.5, dataLine[2] > 0.5, dataLine[3] > 0.5, dataLine[4] > 0.5}; + return stanceLeg2ModeNumber(contactFlags); + }; + + ocs2::TargetTrajectories targetTrajectories; + targetTrajectories.timeTrajectory.reserve(numDataPoints); + targetTrajectories.stateTrajectory.reserve(numDataPoints); + targetTrajectories.inputTrajectory.reserve(numDataPoints); + + Gait gait; + gait.duration = duration; + gait.modeSequence.push_back(getMode(csvData.data.front())); + for (const auto& dataLine : csvData.data) { + const scalar_t t = dataLine[0]; + + // Extend gait if the mode changes + const size_t mode = getMode(dataLine); + if (mode != gait.modeSequence.back()) { + gait.eventPhases.push_back((t - t0) / duration); + gait.modeSequence.push_back(mode); + } else { + // Drop a point if dt is smaller than desired + if (!targetTrajectories.empty() && t < targetTrajectories.timeTrajectory.back() + dt) { + continue; + } + } + + // Time trajectory + targetTrajectories.timeTrajectory.push_back(t); + + // Read the test of the line + size_t colId = 5; // after time and 4 contact flags + const vector3_t basePositionInWorld = dataLine.segment(colId, 3); + colId += 3; + const Eigen::Quaterniond quaternion = + Eigen::Quaterniond(dataLine[colId], dataLine[colId + 1], dataLine[colId + 2], dataLine[colId + 3]).normalized(); + colId += 4; + const vector3_t baseLinearvelocityInBase = dataLine.segment(colId, 3); + colId += 3; + const vector3_t baseAngularvelocityInBase = dataLine.segment(colId, 3); + colId += 3; + const auto feetPositions = dataLine.segment(colId, 3 * NUM_CONTACT_POINTS); + colId += 3 * NUM_CONTACT_POINTS; + const auto feetVelocities = dataLine.segment(colId, 3 * NUM_CONTACT_POINTS); + colId += 3 * NUM_CONTACT_POINTS; + const vector_t contactForces = dataLine.segment(colId, 3 * NUM_CONTACT_POINTS); + + // Convert orientation to ocs2 convention + auto newOrientation = eulerAnglesFromQuaternionBaseToOrigin(quaternion); + ocs2::makeEulerAnglesUnique(newOrientation); + const auto prevYaw = targetTrajectories.stateTrajectory.empty() ? 0.0 : targetTrajectories.stateTrajectory.back()[2]; + const auto newYaw = ocs2::moduloAngleWithReference(newOrientation[2], prevYaw); + const vector3_t eulerXYZ(newOrientation[0], newOrientation[1], newYaw); + const matrix3_t o_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + + assert(o_R_b.isApprox(quaternion.toRotationMatrix())); + + vector_t contactForcesInBase(3 * NUM_CONTACT_POINTS); + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + contactForcesInBase.segment<3>(3 * i) = o_R_b.transpose() * contactForces.segment<3>(3 * i); + } + + // State trajectory + targetTrajectories.stateTrajectory.push_back(vector_t(2 * BASE_COORDINATE_SIZE + 6 * NUM_CONTACT_POINTS)); + targetTrajectories.stateTrajectory.back() << eulerXYZ, basePositionInWorld, baseAngularvelocityInBase, baseLinearvelocityInBase, + feetPositions, feetVelocities; + + // Input trajectory + targetTrajectories.inputTrajectory.push_back(vector_t(3 * NUM_CONTACT_POINTS)); + targetTrajectories.inputTrajectory.back() << contactForcesInBase; + } + return {targetTrajectories, gait}; +} + +void verifyCartesianHeader(const std::vector& provided) { + const std::vector expectedHeader = {"time", + "contactflag_LF", + "contactflag_RF", + "contactflag_LH", + "contactflag_RH", + "base_positionInWorld_x", + "base_positionInWorld_y", + "base_positionInWorld_z", + "base_quaternion_w", + "base_quaternion_x", + "base_quaternion_y", + "base_quaternion_z", + "base_linearvelocityInBase_x", + "base_linearvelocityInBase_y", + "base_linearvelocityInBase_z", + "base_angularvelocityInBase_x", + "base_angularvelocityInBase_y", + "base_angularvelocityInBase_z", + "footPositionInWorld_LF_x", + "footPositionInWorld_LF_y", + "footPositionInWorld_LF_z", + "footPositionInWorld_RF_x", + "footPositionInWorld_RF_y", + "footPositionInWorld_RF_z", + "footPositionInWorld_LH_x", + "footPositionInWorld_LH_y", + "footPositionInWorld_LH_z", + "footPositionInWorld_RH_x", + "footPositionInWorld_RH_y", + "footPositionInWorld_RH_z", + "footVelocityInWorld_LF_x", + "footVelocityInWorld_LF_y", + "footVelocityInWorld_LF_z", + "footVelocityInWorld_RF_x", + "footVelocityInWorld_RF_y", + "footVelocityInWorld_RF_z", + "footVelocityInWorld_LH_x", + "footVelocityInWorld_LH_y", + "footVelocityInWorld_LH_z", + "footVelocityInWorld_RH_x", + "footVelocityInWorld_RH_y", + "footVelocityInWorld_RH_z", + "contactForcesInWorld_LF_x", + "contactForcesInWorld_LF_y", + "contactForcesInWorld_LF_z", + "contactForcesInWorld_RF_x", + "contactForcesInWorld_RF_y", + "contactForcesInWorld_RF_z", + "contactForcesInWorld_LH_x", + "contactForcesInWorld_LH_y", + "contactForcesInWorld_LH_z", + "contactForcesInWorld_RH_x", + "contactForcesInWorld_RH_y", + "contactForcesInWorld_RH_z"}; + verifyHeaderImpl(expectedHeader, provided); +} + +void verifyHeaderImpl(const std::vector& expected, const std::vector& provided) { + // Check header + if (provided.size() != expected.size()) { + throw std::runtime_error("Incorrect amount of columns. Expected: " + std::to_string(expected.size()) + ", but got " + + std::to_string(provided.size())); + } + for (size_t i = 0; i < expected.size(); ++i) { + if (provided[i] != expected[i]) { + throw std::runtime_error("Incorrect header of column " + std::to_string(i) + ", expected: " + expected[i] + ", but got " + + provided[i]); + } + } +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ModeSequenceKeyboard.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ModeSequenceKeyboard.cpp new file mode 100644 index 000000000..ba37e3e70 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ModeSequenceKeyboard.cpp @@ -0,0 +1,66 @@ +// +// Created by rgrandia on 18.03.20. +// + +#include "ocs2_anymal_commands/ModeSequenceKeyboard.h" + +#include +#include + +#include + +namespace switched_model { + +ModeSequenceKeyboard::ModeSequenceKeyboard(ros::NodeHandle nodeHandle, const std::string& gaitFile, const std::string& robotName, + bool verbose) { + ROS_INFO_STREAM(robotName + "_mpc_mode_schedule node is setting up ..."); + ocs2::loadData::loadStdVector(gaitFile, "list", gaitList_, verbose); + + modeSequenceTemplatePublisher_ = nodeHandle.advertise(robotName + "_mpc_mode_schedule", 1, true); + + gaitMap_.clear(); + for (const auto& gaitName : gaitList_) { + gaitMap_.insert({gaitName, loadModeSequenceTemplate(gaitFile, gaitName, verbose)}); + } + ROS_INFO_STREAM(robotName + "_mpc_mode_schedule command node is ready."); +} + +void ModeSequenceKeyboard::getKeyboardCommand() { + const std::string commadMsg = "Enter the desired gait, for the list of available gait enter \"list\""; + std::cout << commadMsg << ": "; + + auto shouldTerminate = []() { return !ros::ok() || !ros::master::check(); }; + const auto gaitCommand = ocs2::getCommandLineString(shouldTerminate); + + if (gaitCommand.empty()) { + return; + } + + if (gaitCommand == "list") { + printGaitList(gaitList_); + return; + } + + try { + ModeSequenceTemplate modeSequenceTemplate = gaitMap_.at(gaitCommand); + publishModeSequenceTemplate(modeSequenceTemplate); + } catch (const std::out_of_range& e) { + std::cout << "Gait \"" << gaitCommand << "\" not found.\n"; + printGaitList(gaitList_); + } +} + +void ModeSequenceKeyboard::printGaitList(const std::vector& gaitList) const { + std::cout << "List of available gaits:\n"; + size_t itr = 0; + for (const auto& s : gaitList) { + std::cout << "[" << itr++ << "]: " << s << "\n"; + } + std::cout << std::endl; +} + +void ModeSequenceKeyboard::publishModeSequenceTemplate(const ModeSequenceTemplate& modeSchedule) { + modeSequenceTemplatePublisher_.publish(createModeSequenceTemplateMsg(modeSchedule)); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandController.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandController.cpp new file mode 100644 index 000000000..3eabc2b8e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandController.cpp @@ -0,0 +1,31 @@ +// +// Created by Timon Kaufmann in June 2021 +// + +#include "ocs2_anymal_commands/MotionCommandController.h" + +#include +#include +#include +#include + +namespace switched_model { + +MotionCommandController::MotionCommandController(ros::NodeHandle& nodeHandle, const std::string& configFile, + const std::string& controllerName) + : MotionCommandInterface(configFile), + client(nodeHandle.serviceClient(controllerName + "/trajectory_request")) {} + +void MotionCommandController::publishMotion(const std::pair& motion) { + Gait stance; + stance.duration = 1.0; + stance.modeSequence = {15}; + + ocs2_switched_model_msgs::trajectory_request srv; + srv.request.trajectory = ocs2::ros_msg_conversions::createTargetTrajectoriesMsg(motion.first); + srv.request.gaitSequence = switched_model::ros_msg_conversions::toMessage({motion.second, stance}); + + client.call(srv); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandDummy.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandDummy.cpp new file mode 100644 index 000000000..25f02c6b7 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandDummy.cpp @@ -0,0 +1,72 @@ +// +// Created by Timon Kaufmann in June 2021 +// + +#include "ocs2_anymal_commands/MotionCommandDummy.h" + +#include + +#include +#include +#include + +#include "ocs2_anymal_commands/TerrainAdaptation.h" + +namespace switched_model { + +MotionCommandDummy::MotionCommandDummy(ros::NodeHandle& nodeHandle, const std::string& configFile, const std::string& robotName) + : MotionCommandInterface(configFile), localTerrain_() { + // Publishers + targetTrajectoryPublisher_ = nodeHandle.advertise(robotName + "_mpc_target", 1, false); + gaitSequencePublisher_ = + nodeHandle.advertise(robotName + "_mpc_gait_schedule", 1, true); + + // Subsribers + observationSubscriber_ = nodeHandle.subscribe(robotName + "_mpc_observation", 1, &MotionCommandDummy::observationCallback, this); + terrainSubscriber_ = nodeHandle.subscribe("/ocs2_anymal/localTerrain", 1, &MotionCommandDummy::terrainCallback, this); +} + +void MotionCommandDummy::observationCallback(const ocs2_msgs::mpc_observation::ConstPtr& msg) { + std::lock_guard lock(observationMutex_); + observationPtr_.reset(new ocs2::SystemObservation(ocs2::ros_msg_conversions::readObservationMsg(*msg))); +} + +void MotionCommandDummy::terrainCallback(const visualization_msgs::Marker::ConstPtr& msg) { + Eigen::Quaterniond orientationTerrainToWorld{msg->pose.orientation.w, msg->pose.orientation.x, msg->pose.orientation.y, + msg->pose.orientation.z}; + + std::lock_guard lock(terrainMutex_); + localTerrain_.positionInWorld = {msg->pose.position.x, msg->pose.position.y, msg->pose.position.z}; + localTerrain_.orientationWorldToTerrain = orientationTerrainToWorld.toRotationMatrix().transpose(); +} + +void MotionCommandDummy::publishMotion(const std::pair& motion) { + ros::spinOnce(); // Trigger callback + ocs2::SystemObservation observation; + { + std::lock_guard lock(observationMutex_); + if (observationPtr_) { + observation = *observationPtr_; + } else { + std::cout << "No observation is received from the MPC node. Make sure the MPC node is running!" + << "\n"; + return; + } + } + const scalar_t startTime = observation.time + 1.0; + + Gait stance; + stance.duration = 1.0; + stance.modeSequence = {15}; + + const auto gaitMessage = switched_model::ros_msg_conversions::toMessage(startTime, {motion.second, stance}); + auto mpcTargetTrajectoriesMsg = ocs2::ros_msg_conversions::createTargetTrajectoriesMsg(motion.first); + for (auto& t : mpcTargetTrajectoriesMsg.timeTrajectory) { + t += startTime; + } + + gaitSequencePublisher_.publish(gaitMessage); + targetTrajectoryPublisher_.publish(mpcTargetTrajectoriesMsg); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandInterface.cpp new file mode 100644 index 000000000..226367267 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/MotionCommandInterface.cpp @@ -0,0 +1,67 @@ +// +// Created by Timon Kaufmann in June 2021 +// + +#include "ocs2_anymal_commands/MotionCommandInterface.h" + +#include + +#include +#include + +#include "ocs2_anymal_commands/LoadMotions.h" + +namespace switched_model { + +MotionCommandInterface::MotionCommandInterface(const std::string& configFile) { + bool verbose = false; + + scalar_t dt = 0.0; + ocs2::loadData::loadCppDataType(configFile, "dt", dt); + + std::vector motionList; + ocs2::loadData::loadStdVector(configFile, "motionList", motionList, verbose); + + const std::string motionFilesPath = ros::package::getPath("ocs2_anymal_commands") + "/config/motions/"; + for (const auto& motionName : motionList) { + const auto csvData = readCsv(motionFilesPath + motionName + ".txt"); + motionData_.insert({motionName, readMotion(csvData, dt)}); + } + printAnimationList(); +} + +void MotionCommandInterface::getKeyboardCommand() { + const std::string commandMsg = "Enter the desired motion, for the list of available motions enter \"list\""; + std::cout << commandMsg << ": "; + + auto shouldTerminate = []() { return !ros::ok() || !ros::master::check(); }; + const std::string motionCommand = ocs2::getCommandLineString(shouldTerminate); + + if (motionCommand.empty()) { + return; + } + + if (motionCommand == "list") { + printAnimationList(); + return; + } + + try { + const auto& motion = motionData_.at(motionCommand); + std::cout << "Executing \"" << motionCommand << "\" \n"; + publishMotion(motion); + } catch (const std::out_of_range& e) { + std::cout << "Motion \"" << motionCommand << "\" not found.\n"; + printAnimationList(); + } +} + +void MotionCommandInterface::printAnimationList() const { + std::cout << "\nList of available motions:\n"; + for (const auto& s : motionData_) { + std::cout << " * " << s.first << "\n"; + } + std::cout << std::endl; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/PoseCommandToCostDesiredRos.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/PoseCommandToCostDesiredRos.cpp new file mode 100644 index 000000000..9607a84d2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/PoseCommandToCostDesiredRos.cpp @@ -0,0 +1,83 @@ +// +// Created by rgrandia on 04.05.20. +// + +#include "ocs2_anymal_commands/PoseCommandToCostDesiredRos.h" + +#include + +#include "ocs2_anymal_commands/TerrainAdaptation.h" + +namespace switched_model { + +PoseCommandToCostDesiredRos::PoseCommandToCostDesiredRos(::ros::NodeHandle& nodeHandle, const std::string& configFile) { + boost::property_tree::ptree pt; + boost::property_tree::read_info(configFile, pt); + targetDisplacementVelocity = pt.get("targetDisplacementVelocity"); + targetRotationVelocity = pt.get("targetRotationVelocity"); + comHeight = pt.get("comHeight"); + ocs2::loadData::loadEigenMatrix(configFile, "defaultJointState", defaultJointState); + + // Setup ROS communication + terrainSubscriber_ = nodeHandle.subscribe("/ocs2_anymal/localTerrain", 1, &PoseCommandToCostDesiredRos::terrainCallback, this); +} + +ocs2::TargetTrajectories PoseCommandToCostDesiredRos::commandLineToTargetTrajectories(const vector_t& commadLineTarget, + const ocs2::SystemObservation& observation) const { + auto deg2rad = [](scalar_t deg) { return (deg * M_PI / 180.0); }; + + // Command to desired Base + // x, y are relative, z is relative to terrain + default offset; + vector3_t comPositionDesired{commadLineTarget(0) + observation.state[3], commadLineTarget(1) + observation.state[4], commadLineTarget(2) + comHeight}; + // Roll and pitch are absolute, yaw is relative + vector3_t comOrientationDesired{deg2rad(commadLineTarget(3)), deg2rad(commadLineTarget(4)), deg2rad(commadLineTarget(5)) + observation.state[2]}; + const auto desiredTime = + desiredTimeToTarget(comOrientationDesired.z() - observation.state[2], comPositionDesired.x() - observation.state[3], + comPositionDesired.y() - observation.state[4]); + + { // Terrain adaptation + std::lock_guard lock(terrainMutex_); + comPositionDesired = adaptDesiredPositionHeightToTerrain(comPositionDesired, localTerrain_, comPositionDesired.z()); + comOrientationDesired = alignDesiredOrientationToTerrain(comOrientationDesired, localTerrain_); + } + + // Desired time trajectory + const ocs2::scalar_array_t tDesiredTrajectory{observation.time, observation.time + desiredTime}; + + // Desired state trajectory + ocs2::vector_array_t xDesiredTrajectory(2, ocs2::vector_t::Zero(STATE_DIM)); + xDesiredTrajectory[0].segment<12>(0) = observation.state.segment<12>(0); + xDesiredTrajectory[0].segment<12>(12) = defaultJointState; + + xDesiredTrajectory[1].segment<3>(0) = comOrientationDesired; + // base x, y relative to current state + xDesiredTrajectory[1].segment<3>(3) = comPositionDesired; + // target velocities + xDesiredTrajectory[1].segment<6>(6).setZero(); + // joint angle from initialization + xDesiredTrajectory[1].segment<12>(12) = defaultJointState; + + // Desired input trajectory + const ocs2::vector_array_t uDesiredTrajectory(2, ocs2::vector_t::Zero(INPUT_DIM)); + + return {tDesiredTrajectory, xDesiredTrajectory, uDesiredTrajectory}; +} + +void PoseCommandToCostDesiredRos::terrainCallback(const visualization_msgs::Marker::ConstPtr& msg) { + Eigen::Quaterniond orientationTerrainToWorld{msg->pose.orientation.w, msg->pose.orientation.x, msg->pose.orientation.y, + msg->pose.orientation.z}; + + std::lock_guard lock(terrainMutex_); + localTerrain_.positionInWorld = {msg->pose.position.x, msg->pose.position.y, msg->pose.position.z}; + localTerrain_.orientationWorldToTerrain = orientationTerrainToWorld.toRotationMatrix().transpose(); +} + +scalar_t PoseCommandToCostDesiredRos::desiredTimeToTarget(scalar_t dyaw, scalar_t dx, scalar_t dy) const { + scalar_t rotationTime = std::abs(dyaw) / targetRotationVelocity; + scalar_t displacement = std::sqrt(dx * dx + dy * dy); + scalar_t displacementTime = displacement / targetDisplacementVelocity; + + return std::max(rotationTime, displacementTime); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ReferenceExtrapolation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ReferenceExtrapolation.cpp new file mode 100644 index 000000000..7d609006e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/ReferenceExtrapolation.cpp @@ -0,0 +1,163 @@ +// +// Created by rgrandia on 02.03.20. +// + +#include "ocs2_anymal_commands/ReferenceExtrapolation.h" + +#include +#include +#include +#include + +namespace switched_model { + +namespace { +void addVelocitiesFromFiniteDifference(BaseReferenceTrajectory& baseRef) { + auto N = baseRef.time.size(); + if (N <= 1) { + return; + } + + baseRef.linearVelocityInWorld.clear(); + baseRef.angularVelocityInWorld.clear(); + baseRef.linearVelocityInWorld.reserve(N); + baseRef.angularVelocityInWorld.reserve(N); + + for (int k = 0; (k + 1) < baseRef.time.size(); ++k) { + auto dt = baseRef.time[k + 1] - baseRef.time[k]; + baseRef.angularVelocityInWorld.push_back(rotationErrorInWorldEulerXYZ(baseRef.eulerXyz[k + 1], baseRef.eulerXyz[k]) / dt); + baseRef.linearVelocityInWorld.push_back((baseRef.positionInWorld[k + 1] - baseRef.positionInWorld[k]) / dt); + } + + auto dt = baseRef.time[N - 1] - baseRef.time[N - 2]; + baseRef.angularVelocityInWorld.push_back(rotationErrorInWorldEulerXYZ(baseRef.eulerXyz[N - 1], baseRef.eulerXyz[N - 2]) / dt); + baseRef.linearVelocityInWorld.push_back((baseRef.positionInWorld[N - 1] - baseRef.positionInWorld[N - 2]) / dt); +} +} // namespace + +Eigen::Vector2d velocityCommand2dInWorld(double headingVelocity, double lateralVelocity, double yaw) { + Eigen::Vector2d commandInBase{headingVelocity, lateralVelocity}; + rotateInPlace2d(commandInBase, yaw); + return commandInBase; +} + +Base2dReferenceTrajectory generate2DExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command) { + const double dt = horizon.dt; + + Base2dReferenceTrajectory baseRef; + baseRef.time.reserve(horizon.N); + baseRef.yaw.reserve(horizon.N); + baseRef.positionInWorld.reserve(horizon.N); + + baseRef.time.push_back(initialState.t0); + + // Project position and orientation to horizontal plane + baseRef.positionInWorld.emplace_back(initialState.positionInWorld.x(), initialState.positionInWorld.y()); + baseRef.yaw.emplace_back(alignDesiredOrientationToTerrain(initialState.eulerXyz, TerrainPlane()).z()); + + for (int k = 1; k < horizon.N; ++k) { + baseRef.time.push_back(baseRef.time.back() + dt); + + // Express command in world + const auto commandedLinearVelocityInWorld = + velocityCommand2dInWorld(command.headingVelocity, command.lateralVelocity, baseRef.yaw.back() + 0.5 * dt * command.yawRate); + + // Advance position + baseRef.positionInWorld.push_back(baseRef.positionInWorld.back() + dt * commandedLinearVelocityInWorld); + + // Advance orientation + baseRef.yaw.push_back(baseRef.yaw.back() + dt * command.yawRate); + } + + return baseRef; +} + +BaseReferenceTrajectory generateExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command, const TerrainPlane& projectedHeadingFrame) { + auto reference2d = generate2DExtrapolatedBaseReference(horizon, initialState, command); + + BaseReferenceTrajectory baseRef; + baseRef.time = std::move(reference2d.time); + baseRef.eulerXyz.reserve(horizon.N); + baseRef.positionInWorld.reserve(horizon.N); + + // Adapt poses + for (int k = 0; k < horizon.N; ++k) { + baseRef.positionInWorld.push_back( + adaptDesiredPositionHeightToTerrain(reference2d.positionInWorld[k], projectedHeadingFrame, command.baseHeight)); + baseRef.eulerXyz.emplace_back(alignDesiredOrientationToTerrain({0.0, 0.0, reference2d.yaw[k]}, projectedHeadingFrame)); + } + + addVelocitiesFromFiniteDifference(baseRef); + return baseRef; +} + +BaseReferenceTrajectory generateExtrapolatedBaseReference(const BaseReferenceHorizon& horizon, const BaseReferenceState& initialState, + const BaseReferenceCommand& command, const grid_map::GridMap& gridMap, + double nominalStanceWidthInHeading, double nominalStanceWidthLateral) { + const auto& baseReferenceLayer = gridMap.get("smooth_planar"); + + // Helper to get a projected heading frame derived from the terrain. + auto getLocalHeadingFrame = [&](const vector2_t& baseXYPosition, scalar_t yaw) { + vector2_t lfOffset(nominalStanceWidthInHeading / 2.0, nominalStanceWidthLateral / 2.0); + vector2_t rfOffset(nominalStanceWidthInHeading / 2.0, -nominalStanceWidthLateral / 2.0); + vector2_t lhOffset(-nominalStanceWidthInHeading / 2.0, nominalStanceWidthLateral / 2.0); + vector2_t rhOffset(-nominalStanceWidthInHeading / 2.0, -nominalStanceWidthLateral / 2.0); + // Rotate from heading to world frame + rotateInPlace2d(lfOffset, yaw); + rotateInPlace2d(rfOffset, yaw); + rotateInPlace2d(lhOffset, yaw); + rotateInPlace2d(rhOffset, yaw); + // shift by base center + lfOffset += baseXYPosition; + rfOffset += baseXYPosition; + lhOffset += baseXYPosition; + rhOffset += baseXYPosition; + + auto interp = [&](const vector2_t& offset) -> vector3_t { + auto projection = grid_map::lookup::projectToMapWithMargin(gridMap, grid_map::Position(offset.x(), offset.y())); + + try { + auto z = gridMap.atPosition("smooth_planar", projection, grid_map::InterpolationMethods::INTER_NEAREST); + return vector3_t(offset.x(), offset.y(), z); + } catch (std::out_of_range& e) { + double interp = gridMap.getResolution() / (projection - gridMap.getPosition()).norm(); + projection = (1.0 - interp) * projection + interp * gridMap.getPosition(); + auto z = gridMap.atPosition("smooth_planar", projection, grid_map::InterpolationMethods::INTER_NEAREST); + return vector3_t(offset.x(), offset.y(), z); + } + }; + + vector3_t lfVerticalProjection = interp(lfOffset); + vector3_t rfVerticalProjection = interp(rfOffset); + vector3_t lhVerticalProjection = interp(lhOffset); + vector3_t rhVerticalProjection = interp(rhOffset); + + const auto normalAndPosition = estimatePlane({lfVerticalProjection, rfVerticalProjection, lhVerticalProjection, rhVerticalProjection}); + + TerrainPlane terrainPlane(normalAndPosition.position, orientationWorldToTerrainFromSurfaceNormalInWorld(normalAndPosition.normal)); + return getProjectedHeadingFrame({0.0, 0.0, yaw}, terrainPlane); + }; + + auto reference2d = generate2DExtrapolatedBaseReference(horizon, initialState, command); + + BaseReferenceTrajectory baseRef; + baseRef.time = std::move(reference2d.time); + baseRef.eulerXyz.reserve(horizon.N); + baseRef.positionInWorld.reserve(horizon.N); + + // Adapt poses + for (int k = 0; k < horizon.N; ++k) { + const auto projectedHeadingFrame = getLocalHeadingFrame(reference2d.positionInWorld[k], reference2d.yaw[k]); + + baseRef.positionInWorld.push_back( + adaptDesiredPositionHeightToTerrain(reference2d.positionInWorld[k], projectedHeadingFrame, command.baseHeight)); + baseRef.eulerXyz.emplace_back(alignDesiredOrientationToTerrain({0.0, 0.0, reference2d.yaw[k]}, projectedHeadingFrame)); + } + + addVelocitiesFromFiniteDifference(baseRef); + return baseRef; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/TerrainAdaptation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/TerrainAdaptation.cpp new file mode 100644 index 000000000..81150e021 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/src/TerrainAdaptation.cpp @@ -0,0 +1,78 @@ +// +// Created by rgrandia on 14.05.20. +// + +#include "ocs2_anymal_commands/TerrainAdaptation.h" + +namespace switched_model { + +vector3_t adaptDesiredPositionHeightToTerrain(const vector3_t& desiredPosition, const TerrainPlane& terrainPlane, scalar_t desiredHeight) { + return adaptDesiredPositionHeightToTerrain(vector2_t{desiredPosition.x(), desiredPosition.y()}, terrainPlane, desiredHeight); +} + +vector3_t adaptDesiredPositionHeightToTerrain(const vector2_t& desiredXYPosition, const TerrainPlane& terrainPlane, + scalar_t desiredHeight) { + const auto adaptedHeight = projectPositionInWorldOntoPlaneAlongGravity(desiredXYPosition, terrainPlane).z() + desiredHeight; + return {desiredXYPosition.x(), desiredXYPosition.y(), adaptedHeight}; +} + +vector3_t eulerXYZFromRotationMatrix(const matrix3_t& orientationTargetToWorld, scalar_t referenceYaw) { + vector3_t eulerXYZ = orientationTargetToWorld.eulerAngles(0, 1, 2); + ocs2::makeEulerAnglesUnique(eulerXYZ); + eulerXYZ.z() = ocs2::moduloAngleWithReference(eulerXYZ.z(), referenceYaw); + return eulerXYZ; +} + +vector3_t getHeadingVectorInWorld(const vector3_t& eulerXYZ) { + return rotationMatrixBaseToOrigin(eulerXYZ).col(0); // x-axis in world frame +} + +scalar_t getHeadingAngleInWorld(const vector3_t& eulerXYZ) { + // Align to a horizontal terrain. Return the yaw + return alignDesiredOrientationToTerrain(eulerXYZ, TerrainPlane()).z(); +} + +matrix3_t getOrientationProjectedHeadingFrameToWorld(const vector3_t& headingVector, const TerrainPlane& terrainPlane) { + // Construct desired axis system + // x-Axis points in same direction as the original x axis in world when both are projected to the world XY plane + // z-Axis is the surface normal + const vector3_t xAxisProjectedHeadingFrame = projectVectorInWorldOntoPlaneAlongGravity(headingVector, terrainPlane).normalized(); + const vector3_t zAxisProjectedHeadingFrame = surfaceNormalInWorld(terrainPlane); + const vector3_t yAxisProjectedHeadingFrame = zAxisProjectedHeadingFrame.cross(xAxisProjectedHeadingFrame); + + // Construct rotation matrix from desired axis system + matrix3_t o_R_projectedheading; + o_R_projectedheading.col(0) = xAxisProjectedHeadingFrame; + o_R_projectedheading.col(1) = yAxisProjectedHeadingFrame; + o_R_projectedheading.col(2) = zAxisProjectedHeadingFrame; + return o_R_projectedheading; +} + +TerrainPlane getProjectedHeadingFrame(const vector3_t& eulerXYZ, const TerrainPlane& terrainPlane) { + const vector3_t xAxisInWorld = getHeadingVectorInWorld(eulerXYZ); + return {terrainPlane.positionInWorld, getOrientationProjectedHeadingFrameToWorld(xAxisInWorld, terrainPlane).transpose()}; +} + +vector3_t alignDesiredOrientationToTerrain(const vector3_t& desiredEulerXYZ, const TerrainPlane& terrainPlane) { + // Construct rotation matrix from desired orientation projected to terrain + const vector3_t xAxisInWorld = getHeadingVectorInWorld(desiredEulerXYZ); + matrix3_t o_R_adapted = getOrientationProjectedHeadingFrameToWorld(xAxisInWorld, terrainPlane); + + // Convert rotation matrix back to euler angles with the yaw close to the desired one + return eulerXYZFromRotationMatrix(o_R_adapted, desiredEulerXYZ.z()); +} + +vector3_t advanceOrientationInWorld(const vector3_t& eulerXYZ, const vector3_t& unitRotationAxisInWorld, double angle) { + const matrix3_t world_R_curr = rotationMatrixBaseToOrigin(eulerXYZ); + + // Get rotation around the surface normal in the current frame + const matrix3_t delta_R = Eigen::AngleAxis(angle, unitRotationAxisInWorld).toRotationMatrix(); + + // Concatenate rotations + const matrix3_t world_R_new = delta_R * world_R_curr; + const vector3_t advancedEulerXYZ = eulerXYZFromRotationMatrix(world_R_new, eulerXYZ.z()); + + return advancedEulerXYZ; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/animatedMotion.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/animatedMotion.txt new file mode 100644 index 000000000..a235a1a60 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/animatedMotion.txt @@ -0,0 +1,752 @@ +time,contactflag_LF,contactflag_RF,contactflag_LH,contactflag_RH,base_positionInWorld_x,base_positionInWorld_y,base_positionInWorld_z,base_quaternion_w,base_quaternion_x,base_quaternion_y,base_quaternion_z,base_linearvelocityInBase_x,base_linearvelocityInBase_y,base_linearvelocityInBase_z,base_angularvelocityInBase_x,base_angularvelocityInBase_y,base_angularvelocityInBase_z,jointAngle_LF_HAA,jointAngle_LF_HFE,jointAngle_LF_KFE,jointAngle_RF_HAA,jointAngle_RF_HFE,jointAngle_RF_KFE,jointAngle_LH_HAA,jointAngle_LH_HFE,jointAngle_LH_KFE,jointAngle_RH_HAA,jointAngle_RH_HFE,jointAngle_RH_KFE,jointVelocity_LF_HAA,jointVelocity_LF_HFE,jointVelocity_LF_KFE,jointVelocity_RF_HAA,jointVelocity_RF_HFE,jointVelocity_RF_KFE,jointVelocity_LH_HAA,jointVelocity_LH_HFE,jointVelocity_LH_KFE,jointVelocity_RH_HAA,jointVelocity_RH_HFE,jointVelocity_RH_KFE,contactForcesInWorld_LF_x,contactForcesInWorld_LF_y,contactForcesInWorld_LF_z,contactForcesInWorld_RF_x,contactForcesInWorld_RF_y,contactForcesInWorld_RF_z,contactForcesInWorld_LH_x,contactForcesInWorld_LH_y,contactForcesInWorld_LH_z,contactForcesInWorld_RH_x,contactForcesInWorld_RH_y,contactForcesInWorld_RH_z +0.0,0.0,1.0,1.0,1.0,-4.1399177600865628e-22,7.794371290226094e-22,1.5382423273552564e-21,1.0,4.971475164066711e-22,-2.234647375162433e-21,3.3485581254605336e-23,-0.03394604087884153,-0.02918073762002874,0.01474230826575764,-0.19859303456798708,-0.12841645858645748,-0.11450936305937842,-4.872120305816547e-22,0.49999999999999994,-1.000000000015507,1.3364837633393094e-21,0.49999999999999994,-1.000000000015507,-3.797325942399921e-22,-0.49999999999999994,1.0000000000155072,-2.84300089838222e-22,-0.49999999999999994,1.0000000000155072,0.1688282741265475,0.3619839968817762,-0.39840459625073876,0.5754085660974194,0.10701189095346342,0.40391455951458877,-0.0056291582071334115,0.8719279359240373,-0.20053741342451303,0.3209719626378314,-0.756453559710526,0.27893018384422597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.008333333333333333,0.0,1.0,1.0,1.0,-0.00028288367399034606,-0.0002431728135002395,0.00012285256888131367,0.9999994006738928,-0.0008274708120582861,-0.0005350684705500457,-0.0004771222507634467,-0.035761997695179716,-0.03274173644409997,0.014243141198034475,-0.20669998919972074,-0.1369728800816965,-0.14081689702827413,0.0014069022843878959,0.5030165333073481,-1.0033200383175964,0.004795071384145162,0.5008917657579455,-0.9966340453528854,-4.690965172611176e-05,-0.49273393386729963,0.9983288549036362,0.0026747663553152615,-0.5063037796642543,1.002324418214209,0.20990632544872498,0.3686143493110794,-0.3777753846636145,0.6171921518948956,0.09532044538994255,0.41807367576962573,-0.015971993711502045,0.8813248257533779,-0.1820770490636292,0.31424819440972607,-0.7700142788385633,0.29009219543409515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.016666666666666666,0.0,1.0,1.0,1.0,-0.0005968077398007268,-0.000544733397880979,0.00023764973333859388,0.9999971765341793,-0.0017223318913693023,-0.0011417379793995308,-0.0011734269946689748,-0.038841075042380296,-0.037151231752668906,0.013618542592147549,-0.21641601856838896,-0.14776888946400063,-0.17825315967366778,0.0034984387574787494,0.5061435724885179,-1.0062962564265672,0.010286535864914927,0.5015886740898323,-0.9930321054193465,-0.0002661998951917007,-0.4853112529041103,0.9969653825311133,0.005237469906828768,-0.512833571313976,1.0048348699394087,0.2654870632573266,0.3751256383296919,-0.3477994781197413,0.6720238769281879,0.07624007900612684,0.4383201931382752,-0.03445562116903515,0.8930163283557624,-0.15955703193037074,0.30186478415617324,-0.7869953377391026,0.2985934217804953,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.025,0.0,1.0,1.0,1.0,-0.0009322044019560552,-0.0008600554810894573,0.00035047674348229424,0.9999930530421703,-0.002630637503391464,-0.001766987776431136,-0.001962490235085409,-0.041050336921033166,-0.03828047770511221,0.013489008162774789,-0.21848417826662356,-0.15053537752716456,-0.19414190970715442,0.005831686672010007,0.5092686272795096,-1.0091166962862588,0.015995469332948292,0.5021624337413809,-0.9893287088005808,-0.0006211700045433644,-0.4778503283947036,0.99566957103813,0.007705846091251482,-0.5194203686265727,1.007300975243884,0.2855093115684365,0.37341994743125495,-0.3339751594389684,0.6891052917655657,0.06363128319619049,0.44933412068916656,-0.047387359485506264,0.896544935416892,-0.15701905054874787,0.2939726133957017,-0.7909702448829758,0.2905768169484402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.03333333333333333,0.0,1.0,1.0,1.0,-0.0012842727325018547,-0.0011788642571630933,0.0004633894122566967,0.9999869569785096,-0.003542602115196583,-0.0023969062550853125,-0.002791179592618757,-0.042769325952092103,-0.03866647014673437,0.013518751595754138,-0.2190928757663879,-0.15118417439871765,-0.20097004528551113,0.008256927283619358,0.5123672382790389,-1.0118625090838833,0.02177162406100769,0.5026491954764355,-0.9855432034078604,-0.0010559892199501384,-0.4703688373138288,0.9943483983553009,0.010137013463423796,-0.5260164087286923,1.0096778168885494,0.29325544768970063,0.3699051481633675,-0.3267732233972609,0.6938839993794926,0.0543688528707742,0.458981402630505,-0.05506343798193637,0.8987417004717113,-0.16193098090166558,0.2914219163428016,-0.7906982535025842,0.27923625148678966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.041666666666666664,0.0,1.0,1.0,1.0,-0.0016496912394091793,-0.0014989039826605528,0.0005769071529235672,0.9999788745304569,-0.004455879152155422,-0.0030276905848873282,-0.003637131219027858,-0.04414158341851096,-0.03889505099105181,0.013588679688706909,-0.21934536458737316,-0.15125942795950742,-0.20398463670218742,0.01071927746683835,0.5154337130822324,-1.0145629166762131,0.027560202655939836,0.5030685812892272,-0.981679018756739,-0.0015388939709089706,-0.4628713000535084,0.9929707213564356,0.012562878030298175,-0.5325986728516158,1.0119549127686638,0.2964392277659904,0.3660863319928942,-0.3220258079660887,0.6941105561934714,0.046953865786378834,0.468366127129316,-0.059914805431951684,0.9006864787352209,-0.16938928365880956,0.2916965617065458,-0.7882906707156501,0.2670903293312721,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.05,0.0,1.0,1.0,1.0,-0.002026029815905696,-0.0018197172907693344,0.0006911382631555031,0.9999688058948585,-0.005369873717825804,-0.0036583071803428144,-0.0044909333149840735,-0.045258163255804604,-0.039094890574673455,0.013666649142092995,-0.2195044850710566,-0.151181621957168,-0.2053936795971686,0.013197581079719198,0.5184686771455871,-1.0172296058833181,0.03334013333089888,0.5034317599062085,-0.9777371012890385,-0.0020545693104826665,-0.4553573960015751,0.991525243627654,0.01499862282519956,-0.5391545865739531,1.014129322377404,0.2978464135383617,0.362452326849223,-0.31830355068729776,0.6925684974183182,0.0406129904770669,0.47764723117668106,-0.06343456110963541,0.9027609573232809,-0.1778045775887338,0.29328808972840914,-0.7846691524726856,0.25468373938568156,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.058333333333333334,0.0,1.0,1.0,1.0,-0.002411476701895447,-0.0021412227521613834,0.0008060864471679676,0.9999567527257123,-0.006284418964576574,-0.0042884771044338745,-0.005348618574094382,-0.046183658587216084,-0.039291494950319715,0.013744419834519262,-0.21963527921827963,-0.15106373183595423,-0.2061250040254213,0.01568338435914438,0.5214745851963861,-1.0198679758543348,0.03910301094624514,0.5037454644638449,-0.973718231570461,-0.002596136656069561,-0.4478252840981204,0.9900073117299567,0.017451012859104994,-0.5456764920594939,1.0161996417584251,0.29853739521848355,0.3591247584201418,-0.3150796949615886,0.69031457005407,0.03493322409531707,0.48683372968189254,-0.06636460961516888,0.9050675151834442,-0.18663415386538595,0.2954595720258086,-0.7802812586791874,0.24212914444580402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.06666666666666667,0.0,1.0,1.0,1.0,-0.0028046745448729003,-0.002463404658318572,0.000921732438055369,0.9999427155575067,-0.00719945293901467,-0.004918123595278299,-0.006208505549634083,-0.04696591606650054,-0.03948855172549703,0.01382020756462014,-0.21975407947811965,-0.15093511413481625,-0.20656804044811322,0.01817320433336059,0.5244540897859228,-1.022480934132678,0.04484537616513338,0.5040139803077971,-0.9696232057943402,-0.003160646137402148,-0.44027293741518436,0.9884146743965643,0.019922949025629702,-0.5521592742186062,1.0181648081181673,0.29893000261196834,0.35609542728161747,-0.31213770079431935,0.6877643475936732,0.029680706025323467,0.49592996322212146,-0.06904575022465169,0.9076002406114114,-0.19567568017149872,0.2978770877549707,-0.7753664148621864,0.22945675356071504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.075,0.0,1.0,1.0,1.0,-0.0032046069889226803,-0.002786252227798672,0.0010380550097919847,0.999926693818671,-0.008114938994480115,-0.005547221816806857,-0.007069871575404617,-0.0476409143901941,-0.039685837878609784,0.01389392484340222,-0.2198650169859633,-0.15080279360383278,-0.20688608452550072,0.02066555106934385,0.5274095089844131,-1.0250702708675734,0.05056575007280636,0.5042401428976003,-0.9654527321834256,-0.0037468991598137557,-0.43269861342126353,0.9867460503937651,0.022415630988354505,-0.5585992656405303,1.020023920984437,0.29919245012554835,0.35331712395900716,-0.3093761246565663,0.6850850214964772,0.02471304807551533,0.5049503520341592,-0.07162888188929553,0.910318083844357,-0.20484382774570875,0.3003945004874003,-0.7700653687953185,0.2166851105704648,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.08333333333333333,0.0,1.0,1.0,1.0,-0.0036105151969871054,-0.0031097510267747127,0.0011550357545749772,0.999908686289489,-0.009030846222935755,-0.0061757587827153,-0.007932395778306322,-0.04823582520062242,-0.039882798615991276,0.013965884375865881,-0.21996912032237015,-0.15066806353134124,-0.20714754839589902,0.023159745168786397,0.5303427085185729,-1.027637202876954,0.05626345985674133,0.504425864442389,-0.9612073665937709,-0.004354460835557073,-0.42510096935111175,0.9850006106008025,0.02492952403375304,-0.5649936970318615,1.021776226627675,0.2993932973430302,0.3507372369215389,-0.3067405782510635,0.6823448988776026,0.01993739608587175,0.5139138528013354,-0.07417957782463096,0.9131741552592831,-0.21409669507663542,0.3029488609568454,-0.7644677259030175,0.203831129665768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.09166666666666666,0.0,1.0,1.0,1.0,-0.004021835020690825,-0.003433883567091756,0.0012726596165697694,0.9998886914836547,-0.00994714475286249,-0.006803723154282581,-0.008795925511874534,-0.04877117946481124,-0.04007908179354572,0.014036449676326541,-0.22006662249752335,-0.15053088274848692,-0.207381067643942,0.025655439358394354,0.5332551295997721,-1.0301826138384245,0.061938165054099735,0.5045724328323649,-0.9568875013034034,-0.004983225456890938,-0.41747904416694215,0.9831777721424878,0.027464778670968595,-0.5713403944055806,1.0234211064788665,0.2995606687495122,0.3483089959711716,-0.3041982763703688,0.6795722785433115,0.015289848422121999,0.522839147350096,-0.0767260415850192,0.9161262122567948,-0.22341030106413307,0.3055131588373615,-0.7586339614764581,0.1909097146973382,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1,0.0,1.0,1.0,1.0,-0.004438149395389349,-0.003758630631170553,0.0013909144173573644,0.9998667078882584,-0.01086380471140845,-0.007431102956180427,-0.009660378498969358,-0.049262477724394,-0.0402745172670725,0.014105946107630876,-0.22015755611333657,-0.15039098467420964,-0.20759861823677495,0.028152422981278267,0.5361478584514258,-1.0327071741497935,0.06758966449912986,0.5046806952494244,-0.9524933808046027,-0.005633228195307393,-0.40983219914683183,0.9812771055830669,0.03002141001437573,-0.5776375963898025,1.024958055205964,0.2997061450245065,0.3459941712461223,-0.3017276762932086,0.6767791362543517,0.010724773036818736,0.5317425101570672,-0.07928031806126362,0.919139465490485,-0.23276914351545885,0.3080757148225906,-0.7526064565446067,0.17793293272359456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.10833333333333334,0.0,1.0,1.0,1.0,-0.004859152226023354,-0.004083972119719756,0.001509790232979376,0.9998427340982475,-0.011780796060310213,-0.008057885280453985,-0.010525701873673887,-0.04972140687178894,-0.04046904215152645,0.014174643772394024,-0.22024190820549702,-0.15024812488591047,-0.20780520611843273,0.030650541775469463,0.5390216991205408,-1.0352114084433113,0.0732178173250056,0.5047511790496452,-0.9480251261341189,-0.006304564091245332,-0.40216005307543407,0.9792982864172302,0.03259937391801177,-0.5838838353479907,1.026386655357593,0.2998345193576548,0.3437627146454303,-0.2993138142934848,0.673970767973702,0.006208820244462121,0.5406373104369777,-0.08184750570041992,0.9221864763592957,-0.24216238559329195,0.31063135138384235,-0.7464155560163155,0.1649099228923223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.11666666666666667,0.0,1.0,1.0,1.0,-0.005284621000515968,-0.004409887495607894,0.001629278835902246,0.9998167688871169,-0.012698088616445133,-0.008684056419771609,-0.011391855060199253,-0.050156763657386305,-0.04066264932427351,0.014242759869521225,-0.22031965947491366,-0.1501021163433507,-0.20800292522748684,0.033149664970572514,0.5418772370288496,-1.0376957377213516,0.07882251063202489,0.5047841755868321,-0.9434827589639864,-0.006997353290314392,-0.39446242454084357,0.9772410658231787,0.03519859920410644,-0.5900778556567411,1.027706553920836,0.29994780421077033,0.3415914893862326,-0.29694595564694115,0.671149737600669,0.001717279270379013,0.5495342328041408,-0.08442972161913931,0.9252461184908023,-0.25158212772935284,0.31317764339631265,-0.7400832082607467,0.1518472519098868,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.125,0.0,1.0,1.0,1.0,-0.005714396036862312,-0.004736356001170893,0.0017493732400704304,0.9997888112426139,-0.013615652094339356,-0.009309602045116017,-0.012258802628656881,-0.05057515593116732,-0.040855358454540996,0.014310465713683123,-0.2203907928527729,-0.14995281985541903,-0.20819265530230785,0.03564967184564897,0.5447148906103113,-1.0401605077040936,0.08440364628501675,0.5047798003708182,-0.9388662222540499,-0.007711726118230987,-0.3867392844339207,0.9751052509550743,0.037819001307950316,-0.5962185554856698,1.0289174428894245,0.3000468781833604,0.3394628908100583,-0.29461626848417133,0.6683174940418285,-0.002768306131548659,0.5584417281861676,-0.08702780214750243,0.9283023771383059,-0.26102250956090645,0.3157133314445811,-0.7336253262184855,0.13874940917300904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.13333333333333333,0.0,1.0,1.0,1.0,-0.00614836476847361,-0.0050633567621599426,0.001870067341767159,0.9997588603843193,-0.01453345613798588,-0.009934507348300816,-0.013126511321711744,-0.050981534787618916,-0.04104720059722676,0.014377894179946202,-0.22045529415059076,-0.14980012978635782,-0.20837477128734896,0.03815044627362852,0.5475349518756839,-1.0426060088627545,0.08996113553272203,0.5047380371513063,-0.9341753968275502,-0.008447816659439432,-0.37899071825520514,0.9728906906638303,0.04046048806151612,-0.6023049444270492,1.0300190440737196,0.30013216054155956,0.337363627297409,-0.29231899826325236,0.6654750310839835,-0.0072617859484314096,0.5673664819973334,-0.08964203229497905,0.9313432607510275,-0.27047917510475195,0.3182376500424766,-0.7270534085844149,0.12561928395991906,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.14166666666666666,0.0,1.0,1.0,1.0,-0.006586449852303085,-0.005390868836992724,0.001991355639459459,0.9997269157722045,-0.015451470339499757,-0.010558757143237788,-0.013994948822099411,-0.05137959808724205,-0.04123821010796648,0.014445146395501355,-0.2205131509572516,-0.1496439627092843,-0.20854943920270802,0.04065187452134163,0.5503376177319348,-1.0450324910084812,0.09549489680308314,0.504658770605011,-0.929410114220761,-0.009205759989813971,-0.3712168967547369,0.9705972647033284,0.04312296214199159,-0.6083361122954101,1.0310110976220899,0.3002038851838912,0.3352837238513695,-0.29004991461174523,0.6626231543124084,-0.011773585848584567,0.5763138230931819,-0.09227245974073248,0.9343598983558277,-0.27994891730256377,0.32075004209148994,-0.7203756955567719,0.11245856722042369,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.15,0.0,1.0,1.0,1.0,-0.007028600175111128,-0.005718871239594007,0.002113233016026319,0.9996929771108518,-0.016369664247716794,-0.011182335934107269,-0.014864083245047503,-0.051772096248705546,-0.04142842041964014,0.014512297421605454,-0.22056435140267353,-0.1494842493564424,-0.20871673919695274,0.04315384436002671,0.5531230139398734,-1.0474401741062835,0.10100485477126217,0.5045418107204965,-0.9245701664426639,-0.00998569098845164,-0.363418053282608,0.9682248753754542,0.04580632209637429,-0.614311206019662,1.0318933535273933,0.30026221024353195,0.3332157368379707,-0.2878059220013762,0.6597625874069291,-0.016311574110510207,0.5852880561460116,-0.09491903089151717,0.9373458210990337,-0.2894294237998274,0.3232500365988979,-0.7135980119581875,0.09926806856867199,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.15833333333333333,0.0,1.0,1.0,1.0,-0.007474784055498672,-0.006047342949141634,0.0022356945693322735,0.9996570443516691,-0.01728800736986258,-0.011805227959001062,-0.01573388293145212,-0.05216106386629489,-0.04161786187381282,0.01457940095424319,-0.22060888314940397,-0.14932092899439786,-0.20887671649599127,0.04565624469206716,0.555891213345901,-1.0498292563751708,0.10649093992653196,0.5043869110365025,-0.9196553132849942,-0.010787743838005924,-0.35559446640308634,0.9657734409733313,0.048510462751973224,-0.6202294124947132,1.0326655654315677,0.3003072608241854,0.3311541465016332,-0.2855847773328124,0.6568940133821255,-0.020881705990829502,0.5942927225328742,-0.0975816504257132,0.9402964021204174,-0.29891908719962057,0.325737195726976,-0.7067243905723553,0.08604795770748908,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.16666666666666666,0.0,1.0,1.0,1.0,-0.00792498410877692,-0.006376262912993186,0.002358735479895273,0.9996191176942405,-0.01820646916853693,-0.01242741721561942,-0.016604316365093085,-0.05254799507831389,-0.04180656066600745,0.014646493156695129,-0.22064673263587498,-0.1491539454369727,-0.20902940233792738,0.04815896537376313,0.5586422497149006,-1.0521999203951637,0.11195308832763093,0.504193782287316,-0.9146652877337826,-0.011612051828880194,-0.34774644658060105,0.9632428905887939,0.051235275358490553,-0.6260899458625346,1.0333274861558515,0.30033914494967645,0.3290948916237557,-0.2833848814511919,0.6540180899064441,-0.025488506310014092,0.6033308015048022,-0.10026020767975041,0.9432084246519901,-0.30841686021381376,0.3282110915412577,-0.6997575364398934,0.07279794451702681,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.175,0.0,1.0,1.0,1.0,-0.00837919337063511,-0.006705610045802978,0.002482350906836233,0.9995791975873604,-0.019125019055483833,-0.013048887473741442,-0.017475352140483368,-0.052933976307175036,-0.04199453840283127,0.014713595754281498,-0.22067788451835316,-0.14898324415536277,-0.2091748224576229,0.0506618971078951,0.5613761282062969,-1.0545523377326906,0.11739124142497269,0.5039621025980022,-0.9095997999265808,-0.012458747299335098,-0.33987432599221984,0.9606331599697677,0.053980647610994185,-0.6318920381020448,1.0338788645068515,0.3003579590640991,0.32703501498798637,-0.2812051237360258,0.6511354545835605,-0.03013543242830874,0.6124048638976132,-0.10295458849004561,0.9460797509865837,-0.317922143877436,0.3306712956551397,-0.6926991740713162,0.05951741159471613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.18333333333333332,0.0,1.0,1.0,1.0,-0.008837412373465685,-0.007035363226316207,0.0026065359052851213,0.9995372847300134,-0.02004362638307781,-0.013669622277815924,-0.0183469589510012,-0.05331978670853241,-0.042181811994055254,0.014780718515097168,-0.22070232125340788,-0.14880877013475285,-0.20931300043401016,0.05316493135816478,0.5640928332980337,-1.0568866724574308,0.1228053459040236,0.5036915250801776,-0.9044585400021558,-0.01332796163704762,-0.33197845073082466,0.9579441881908366,0.05674646361940955,-0.6376349320970566,1.0343194430157634,0.30036378964039423,0.32497239408744827,-0.27904476566379177,0.6482467265390455,-0.03482514793203828,0.6215171890545812,-0.10566468054428947,0.9489090696069169,-0.3274347008853451,0.3331173745825979,-0.6855503076100455,0.046205510833039476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.19166666666666665,0.0,1.0,1.0,1.0,-0.00929964694347658,-0.007365501292601337,0.0027312853599893733,0.9994933800724302,-0.02096226043410707,-0.014289604942057933,-0.019219105584843077,-0.053705974168312146,-0.04236839372183264,0.014847861226107019,-0.2207200227739727,-0.14863046624880716,-0.20944395893489784,0.05566796026856834,0.566792334774421,-1.0592030838270872,0.12819535353395678,0.5033816834658016,-0.8992411801090044,-0.014219825308406589,-0.32405917483210456,0.955175914955012,0.05953260385403748,-0.6433178765622122,1.0346489563540688,0.3003567134599876,0.3229055369409295,-0.2769033533687182,0.6453525067736441,-0.039559729307385716,0.6306698536042088,-0.1083903757712065,0.9516957023886996,-0.33695458833219005,0.335548887678369,-0.6783114159174586,0.03286123317820966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2,0.0,1.0,1.0,1.0,-0.009765906543026266,-0.007696003036123304,0.0028565939310897727,0.9994474848172806,-0.021880890410207316,-0.014908818539762758,-0.020091760923736268,-0.05409291278848638,-0.04255429139505546,0.014915015257880679,-0.22073096622465152,-0.1484482719989531,-0.20956772011193786,0.05817087658249791,0.5694745922470492,-1.0615017283469095,0.13356122101691767,0.5030321962583878,-0.8939473757754189,-0.015134467899901062,-0.316116855691013,0.9523282783853001,0.0623389450807157,-0.6489401223623475,1.0348671302354002,0.30033679751461306,0.3208334274467939,-0.27478065194527,0.6424533781897984,-0.044340822176109906,0.6398647988585737,-0.11113157134564758,0.9544394577691095,-0.3464821055556655,0.3379653862810583,-0.6709825988584384,0.01948345855316891,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.20833333333333334,0.0,1.0,1.0,1.0,-0.010236203025280454,-0.008026847194875328,0.0029824560089705054,0.9993996004210416,-0.022799485419155333,-0.015527245888069635,-0.020964893942388704,-0.054480846361715934,-0.042739508534703645,0.014982164795877323,-0.22073512573206278,-0.14826212251284668,-0.20968430565830018,0.060673573560478554,0.5721395585652009,-1.0637827613595083,0.1389029098371201,0.5026426697628664,-0.8885767667946949,-0.01607201816416738,-0.30815185053595273,0.9494012131957509,0.06516536029205512,-0.6545009198765195,1.0349736806632883,0.30030409884972686,0.31875540834347627,-0.27267659612163264,0.6395499055896736,-0.049169759510343525,0.6491038820333572,-0.11388817003220454,0.9571405189982185,-0.35601775378130585,0.34036641342550733,-0.6635636869335237,0.006070991185769259,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.21666666666666667,0.0,1.0,1.0,1.0,-0.010710549700598213,-0.008358012445685072,0.003108865675809836,0.9993497285955607,-0.023718014461135882,-0.016144869529062376,-0.021838473707887072,-0.05486992124292006,-0.04292404455862818,0.015049287802439084,-0.220732472193379,-0.1480719477271177,-0.20979373673583096,0.06317594489666002,0.5747871823861072,-1.06604633828227,0.1442203861100789,0.5022127002665487,-0.8831289777415297,-0.01703260406710447,-0.30016451370770936,0.9463946491556117,0.06801171863780749,-0.659999517144573,1.0349683134218297,0.30025866443142885,0.316671092685088,-0.27059125329486733,0.6366426357184363,-0.05404765116576726,0.6583889152554478,-0.11666008021046614,0.9597993591306753,-0.36556220500495673,0.34275150382328895,-0.6560543233557414,-0.007377415766018913,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.225,0.0,1.0,1.0,1.0,-0.011188960638526455,-0.00868947739575238,0.0032358166720087836,0.9992978713098345,-0.02463644641403261,-0.016761671707840264,-0.022712469378745093,-0.05526021119759558,-0.0431078949480189,0.01511635676186126,-0.22072297307154423,-0.1478776717001993,-0.20989603385293942,0.0656778846343357,0.5774174101099524,-1.0682926155810895,0.14951362043242736,0.5017418755767703,-0.8776036182071041,-0.018016352834341817,-0.2921551945504415,0.9433085097790016,0.0708778853557766,-0.6654351585991152,1.0348507237338547,0.30020053103779865,0.314580296925131,-0.26852479591770617,0.6337320973511817,-0.05897545177304897,0.6677216953643028,-0.11944721575105344,0.9624166763834641,-0.3751162781109585,0.3451201839618695,-0.6484540254001714,-0.02086304342058032,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.23333333333333334,0.0,1.0,1.0,1.0,-0.011671450147792573,-0.009021220573439839,0.0033633023660941844,0.999244030792016,-0.025554750017751916,-0.017377634348006155,-0.023586850203491324,-0.05565173617938457,-0.043291051386250896,0.01518333925081534,-0.22070659218922467,-0.14767921201537831,-0.20999121672372176,0.06817928708062333,0.5800301873348593,-1.0705217515475651,0.1547825877325986,0.5012297760703313,-0.8720002828187913,-0.019023390996288695,-0.28412423576798496,0.9401427111870957,0.07376372170383864,-0.6708070842345758,1.0346205960314867,0.3001297251547902,0.3124829903676396,-0.2664774809696935,0.6308188014022675,-0.06395401229726039,0.6771040267797357,-0.12224949582870827,0.9649933450007386,-0.3846809206641377,0.34747197224480664,-0.6407622301571481,-0.03438719609964558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.24166666666666667,0.0,1.0,1.0,1.0,-0.01215803239070467,-0.009353220418314148,0.0034913157270098183,0.9991882095316666,-0.026472893857559666,-0.01799273902487816,-0.024461585518753888,-0.05604447651446795,-0.04347350186599875,0.0152501983681511,-0.2206832895159646,-0.1474764792442493,-0.21007930411876913,0.07068004672024887,0.5826254599494131,-1.0727339069305843,0.16002726712246515,0.500675975371816,-0.8663185510941085,-0.020053844431486955,-0.2760719721337625,0.936897161101266,0.07666908489319005,-0.6761145291017343,1.0342776037988606,0.3000462628550471,0.3103792570163777,-0.2644496348056924,0.6279032410363627,-0.06898411927264592,0.6865377391522376,-0.1250668447178794,0.9675303779243061,-0.3942571951527918,0.3498063791320036,-0.6329783285446999,-0.04795119443086193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.25,0.0,1.0,1.0,1.0,-0.012648721098967005,-0.009685455270420891,0.003619849297951423,0.999130410282272,-0.027390846346390944,-0.018606966936626158,-0.025336644746820233,-0.05643838361026807,-0.043655230763557075,0.015316893051258655,-0.22065302094469738,-0.14726937644814642,-0.2101603137102698,0.07318005812820745,0.585203174951799,-1.0749292454609933,0.1652476417498713,0.5000800407491205,-0.860557987166254,-0.02110783840825335,-0.2679987294692465,0.9335717579345492,0.07959382802270537,-0.6813567230436541,1.033821409457639,0.2999501496435908,0.3082692668160103,-0.2624416420930009,0.6249858917660367,-0.07406652473975539,0.6960247010897769,-0.12789919159480725,0.9700288984572336,-0.4038462687330857,0.35212290725725875,-0.6251016904785489,-0.061556371495488094,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2583333333333333,0.0,1.0,1.0,1.0,-0.013143529365938203,-0.010017903358764074,0.0037488951710828596,0.9990706360640352,-0.028308575706078552,-0.01922029887345399,-0.02621199739265244,-0.056833388033669135,-0.0438362188810452,0.015383378300455391,-0.22061573805478193,-0.14705779870032856,-0.21023426191147893,0.07567921588097538,0.5877632810630132,-1.077107934298801,0.1704436986518991,0.49944153329282004,-0.8547181394092789,-0.022185497624733742,-0.25990482382614194,0.9301663899557145,0.08253780001414436,-0.6865328906097101,1.0332516642739358,0.2998413802594188,0.30615325401101456,-0.2604539378668669,0.6220672115256365,-0.07920196916778144,0.7055668309359775,-0.1307464703586185,0.9724901187793944,-0.4134494057319027,0.3544210515109539,-0.6171316833787266,-0.07520407119719241,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.26666666666666666,0.0,1.0,1.0,1.0,-0.013642469496421152,-0.010350542788954031,0.00387844496260686,0.9990088901669706,-0.029226049947435235,-0.019832715184885996,-0.027087613040338358,-0.057229405597632496,-0.04401644345801499,0.015449605328401103,-0.2205713878594095,-0.1468416326155192,-0.2103011637096812,0.07817741446586443,0.5903057291853159,-1.0792701444254411,0.1756154286086319,0.49876000792965747,-0.8487985399839877,-0.02328694624756366,-0.2517905608229233,0.9266809345056841,0.08550084554788794,-0.6916422510999662,1.0325680082710191,0.29971993842616174,0.3040315009021066,-0.2584870019735197,0.6191476407156732,-0.08439119908586257,0.7151661053330027,-0.13360861947742797,0.9749153236905833,-0.4230679623339473,0.3567002990815016,-0.6090676856501043,-0.08889564825291352,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.275,0.0,1.0,1.0,1.0,-0.014145552899655366,-0.010683351529980248,0.004008489787767317,0.9989451761543158,-0.030143236849115778,-0.020444195745168002,-0.02796346134895347,-0.0576263419391532,-0.0441958781543086,0.01551552164783305,-0.22051991253557282,-0.14662075587621123,-0.2103610324915789,0.08067454818807808,0.592830472744715,-1.0814160509983597,0.18076282599716031,0.49803501330805566,-0.8427987043203955,-0.02441230794935754,-0.24365623509796555,0.9231152572501488,0.08848280499883605,-0.6966840187038785,1.0317700701363872,0.2995857965479465,0.3019043256998777,-0.25654135535075895,0.6162276022152852,-0.08963498072387499,0.7248245661207364,-0.1364855818620487,0.9773058583480693,-0.4327033830081306,0.35896012945228456,-0.600909096367066,-0.10263246936953241,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2833333333333333,0.0,1.0,1.0,1.0,-0.014652790014645518,-0.011016307400060557,0.00413902023543495,0.9988794978662878,-0.03106010393517739,-0.021054719916753874,-0.02883951204780641,-0.058024095953272,-0.0443744930060045,0.015581071107842796,-0.22046124913506998,-0.14639503674710028,-0.21041387986015683,0.08317051107499687,0.5953374679469805,-1.083545833681287,0.18588588864555333,0.49726609158425955,-0.8367181305486421,-0.02556170594526447,-0.23550212985045546,0.9194692114555486,0.09148351437209268,-0.701657402706084,1.0308574671148603,0.2994389153481511,0.2997720734934717,-0.254617557733563,0.6133075013613681,-0.09493411064263602,0.7345443259857642,-0.1393773047677921,0.9796631190619615,-0.44235719833033205,0.3612000143522634,-0.5926553420864855,-0.11641591529079509,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2916666666666667,0.0,1.0,1.0,1.0,-0.015164190259571171,-0.011349388051512817,0.004270026341983671,0.9988118594242043,-0.031976618451250105,-0.02166426651181654,-0.02971573493103685,-0.05842256235836805,-0.044552254356039746,0.01564619388656896,-0.22039532927495684,-0.14616433357043113,-0.21045971544203293,0.08566519677721393,0.5978266739696062,-1.0856596769605857,0.19098461768651645,0.4964527781306784,-0.8305562988872994,-0.026735263028820743,-0.22732851644693286,0.9157426372779766,0.09450280523804044,-0.7065616077386533,1.0298298048815406,0.29927924344985535,0.2976351095930041,-0.2527162064767774,0.6103877258944002,-0.10028942409309072,0.7443275731698074,-0.142283739723979,0.9819885464410155,-0.4520310239404868,0.36341941765954205,-0.5843058814835445,-0.13024738348660136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3,0.0,1.0,1.0,1.0,-0.015679761998994166,-0.011682570954590143,0.004401497564205003,0.9987422652349977,-0.032892747339220894,-0.022272813751695295,-0.030592099851532016,-0.058821633600709695,-0.04472912476081743,0.015710826446236573,-0.22032207880592874,-0.14592849423599594,-0.21049854668436704,0.0881584984658278,0.6002980531068639,-1.0877577704559,0.19605901741046,0.49559460118270804,-0.824312670995812,-0.027933101607330788,-0.21913565407643854,0.9119353610565405,0.09754050466641838,-0.7113958340641431,1.0286866773900836,0.29910671689662494,0.2954938146867758,-0.25083793626502704,0.6074686458711948,-0.10570180166009413,0.7541765754674112,-0.1452048424906561,0.9842836203525368,-0.46172656043524496,0.3656177952573597,-0.5758602083320352,-0.14412829131941862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.30833333333333335,0.0,1.0,1.0,1.0,-0.016199512524070366,-0.012015833380215763,0.004533422751035422,0.9986707199961515,-0.03380845721032868,-0.02288033922416711,-0.0314685767141248,-0.05922120125461175,-0.04490506287369042,0.015774901454881356,-0.22024141745693038,-0.14568735562017088,-0.210530378640356,0.09065030872549101,0.6027515708810525,-1.0898403092316695,0.20110909511770303,0.4946910814363435,-0.8179866892961759,-0.029155343736998345,-0.21092378944105725,0.9080471946040558,0.10059643515899644,-0.7161592778775205,1.0274276666928837,0.29892125861230023,0.29334858139271835,-0.24898341954054715,0.6045506135446188,-0.1111721746088179,0.7640936836840262,-0.14814057304141634,0.9865498562909802,-0.4714455940459761,0.3677945948411268,-0.5673178532211343,-0.15806007956919554,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.31666666666666665,0.0,1.0,1.0,1.0,-0.016723448042082995,-0.012349152381547886,0.004665790113889878,0.9985972287010889,-0.03472371431655813,-0.0234868198384078,-0.032345135468033415,-0.059621157036071466,-0.045080023305837325,0.01583834767785034,-0.22015325845424086,-0.14544074298878512,-0.21055521374233416,0.09314051944269947,0.6051871961300759,-1.0919074941149092,0.20613486096953698,0.4937417316058944,-0.8115777762677449,-0.03040211115802106,-0.20269315647158886,0.9040779344891076,0.10367041458043716,-0.7208511316178287,1.026052342730597,0.29872277779802864,0.2911998118876835,-0.24715336752457961,0.6016339632105216,-0.11670152924747712,0.7740813346780673,-0.15109089557199584,0.988788802851826,-0.48118999799257267,0.36994925567600145,-0.5586783843023713,-0.1720442162325897,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.325,0.0,1.0,1.0,1.0,-0.01725157367246331,-0.012682504774299294,0.004798587195405656,0.9985217966450453,-0.03563848452021282,-0.024092231777488583,-0.033221746098499365,-0.06002139351852998,-0.045253956464657887,0.015901089841059004,-0.2200575081130331,-0.14518846935875915,-0.21057305156129508,0.09562902168879149,0.6076049010791805,-1.0939595320237459,0.2111363278378784,0.49274605594888554,-0.8050853337182081,-0.03167352532986494,-0.19444397606019348,0.9000273613041796,0.1067622560869298,-0.7254705842825601,1.0245602630890072,0.29851116926413235,0.2890479163781867,-0.2453485317441917,0.5987190110212709,-0.12229091054024366,0.7841420540762489,-0.15405577853465935,0.9910020400819092,-0.4909617344337902,0.3720812083031011,-0.5499414072895759,-0.1860822005343854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3333333333333333,0.0,1.0,1.0,1.0,-0.017783893447087137,-0.013015867115729855,0.0049318008364044345,0.9984444294314638,-0.036552733261536796,-0.024696550448232747,-0.034098378617576065,-0.06042180461688803,-0.045426808369397456,0.015963048467258576,-0.2199540653991877,-0.14493033481352835,-0.2105838885516635,0.09811570559710167,0.6100046614030457,-1.0959966363106457,0.21611351115322483,0.491703549763557,-0.7985087420331407,-0.03296970746693205,-0.18617645580355704,0.8958952389152111,0.10987176805215551,-0.7300168217393216,1.0229509727216906,0.29828631269377487,0.2868933122362982,-0.24356970600204697,0.5958060547648325,-0.12794142514442997,0.7942784587239782,-0.15703519469810606,0.993191178535468,-0.500762856959327,0.3741898741918498,-0.5411065648782887,-0.20017556710780315,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3416666666666667,0.0,1.0,1.0,1.0,-0.018320410313108413,-0.013349215682222892,0.005065417140882823,0.99836513297895,-0.037466425524244514,-0.02529975042823777,-0.03497500305401733,-0.06082228588939709,-0.04559852044338132,0.01602413968576817,-0.21984282145898212,-0.14466612576715737,-0.21058771777996768,0.10060046023368774,0.6123864562831188,-1.09801902712378,0.2210664287506256,0.49061369886314504,-0.7918473594061418,-0.034290778574833376,-0.177890789751269,0.8916813136881908,0.11299875399012729,-0.7344890270305315,1.0212240036372104,0.2980480718342979,0.28473642366938057,-0.24181772874700247,0.5928953736084691,-0.13365424399984116,0.8044932589103015,-0.16002912123406487,0.9953578589109296,-0.5105955135899176,0.3762746653361229,-0.5321735357101298,-0.21432589031304516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.35,0.0,1.0,1.0,1.0,-0.01886112613693771,-0.013682526445348984,0.005199421438834798,0.99828391352883,-0.03837952579880594,-0.025901805409846445,-0.03585158944220937,-0.06122273469413134,-0.04576902928185688,0.016084275015569183,-0.21972365911392383,-0.1443956141718597,-0.21058452863583504,0.10308317346100664,0.614750268464202,-1.1000269317897624,0.22599510071336598,0.4894759790302263,-0.7851005210513023,-0.0356368594874998,-0.16958715815504155,0.8873853136887124,0.11614301247442423,-0.7388863806678238,1.0193788745498065,0.2977962936118128,0.282577681828482,-0.24009348582141765,0.5899872278048202,-0.13943060456305112,0.8147892603903539,-0.1630375398313659,0.9975037521762048,-0.5204619502659558,0.3783349837905922,-0.5231420329788405,-0.22853478867102872,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.35833333333333334,0.0,1.0,1.0,1.0,-0.019406041708230255,-0.014015775046311688,0.005333798246705186,0.9982007776533558,-0.03929199804332149,-0.0265026881408299,-0.036728107810085175,-0.06162305022695086,-0.04593826639410366,0.016143361121127596,-0.21959645231782646,-0.1441185566633621,-0.21057430652369868,0.10556373179388462,0.6170960843135935,-1.1020205852208036,0.23089954921403927,0.48828985545376086,-0.7782675383996359,-0.03700807090535614,-0.16126572721499893,0.8830069478504249,0.11930433705330383,-0.7432080609135122,1.0174150904926933,0.2975308071633975,0.28041752528556785,-0.23839791357174622,0.5870818583580056,-0.1452718127526198,0.8251693662136961,-0.16606043683894053,0.9996305601174421,-0.530364514821422,0.3803702211430854,-0.5140118027499874,-0.24280392939629358,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.36666666666666664,0.0,1.0,1.0,1.0,-0.0199551567429306,-0.01434893676866089,0.0054685312252598295,0.99811573226461,-0.040203805641806194,-0.027102370361521248,-0.03760452816595416,-0.06202313346067812,-0.04610615791814901,0.01620129953988008,-0.21946106557282713,-0.14383469363819468,-0.21055703253332048,0.10804202024706326,0.6194238938856281,-1.1040002303492915,0.23577979835266608,0.487054782151016,-0.7713476982810741,-0.03840453343481547,-0.15292664881975085,0.8785459051083554,0.12248251616014232,-0.7474532440469902,1.0153321423932016,0.2972514227803033,0.27825640083164904,-0.2367320023210917,0.5841794866471955,-0.1511792446491933,0.8356365783539443,-0.16909780344005934,1.0017400162656753,-0.5403056614481194,0.382379757918522,-0.5047826220513096,-0.25713503301644014,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.375,0.0,1.0,1.0,1.0,-0.020508469884556856,-0.014681986509148575,0.005603603134648245,0.9980287846241617,-0.04111491135968774,-0.02770082273811534,-0.03848082048417374,-0.0624228869993753,-0.04627262430606419,0.01625798637993483,-0.21931735330076527,-0.14354374825658323,-0.210532683087074,0.11051792217355634,0.621733690994121,-1.1059661185928218,0.24063587399149253,0.4857702013762743,-0.7643402620937368,-0.03982636762935713,-0.14457006027723768,0.8740018534929562,0.12567733301861253,-0.7516211046143674,1.013129506609086,0.2969579307551004,0.27609476456213367,-0.2350968002092957,0.5812803140038914,-0.15715434797758498,0.8461939991242651,-0.17214963585989604,1.0038338871727859,-0.55028795566745,0.3843629629088022,-0.49545429677670283,-0.271529878069785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3833333333333333,0.0,1.0,1.0,1.0,-0.02106597870299164,-0.015014898746590753,0.005738995786416242,0.997939942353533,-0.04202527729630409,-0.02829801479182254,-0.039356954689581815,-0.0628222148571212,-0.04643757997749931,0.016313311986066295,-0.2191651591659663,-0.14324542536397472,-0.21050122956169617,0.1129913190929816,0.624025473294997,-1.1079185103527798,0.24546780358606426,0.48443554301805625,-0.7572444649623363,-0.04127369403248041,-0.13619608403353775,0.8693744391805646,0.12888856554195569,-0.7557108156599353,1.0108066444253718,0.2966501001244212,0.2739330832289921,-0.23349341741437435,0.5783845212390842,-0.1631986433856425,0.8568448323549993,-0.1752159356093437,1.005913974019645,-0.5603140798345985,0.3863191924228321,-0.486026659438763,-0.28599030587310725,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.39166666666666666,0.0,1.0,1.0,1.0,-0.021627679690106608,-0.015347647508586809,0.005874689992209682,0.9978492134455413,-0.042934864834168765,-0.028893914823536048,-0.040232900640601636,-0.06322102216755984,-0.04660093293878989,0.016367160571840022,-0.21900431534516293,-0.1429394103238965,-0.21046263788198588,0.11546209050896336,0.6262992423812709,-1.109857675549728,0.25027561601214393,0.4830502239865136,-0.7500595148878202,-0.04274663322284619,-0.12780482737691026,0.8646632854957129,0.13211598622565973,-0.7597215489383468,1.0083630015112008,0.2963276772976789,0.27177183584923714,-0.2319230307753406,0.575492268116165,-0.169313725521133,0.8675923842967737,-0.1782967097683573,1.007982114550435,-0.5703868392085365,0.38824778944965777,-0.47649956679837624,-0.3005182253527172,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4,0.0,1.0,1.0,1.0,-0.02219356825157834,-0.015680206335933988,0.006010665508888985,0.9977566062765848,-0.04384363458475002,-0.029488489833642235,-0.041108628110921405,-0.06361921482765844,-0.046762584364563695,0.016419409815279513,-0.21883464173970163,-0.14262536775398751,-0.2104168680836677,0.11793011371460958,0.6285550038924843,-1.1117838941990354,0.25505934138800035,0.48161364759270403,-0.7427845918907234,-0.04424530586195303,-0.11939638212436383,0.8598679918604223,0.13535936203278331,-0.7636524751065749,1.0057980073361599,0.295990384561666,0.26961151556630814,-0.23038688884117864,0.5726036927643552,-0.17550126389830667,0.8784400642035739,-0.18139197131276097,1.010040185335702,-0.5805091686291486,0.3901480827271925,-0.46687289739450133,-0.3151156179324266,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4083333333333333,0.0,1.0,1.0,1.0,-0.022763638694264197,-0.01601254824455921,0.00614690097975159,0.9976621296199497,-0.04475154633048701,-0.030081705436568077,-0.04198410676964135,-0.06401669907675711,-0.04692242813842034,0.016469930415124553,-0.21865594512490624,-0.1423029401564152,-0.21036387384235167,0.12039526358499113,0.6307927676407094,-1.1136974570304143,0.25981901089154985,0.4801252029215418,-0.735418847151094,-0.04576983274472554,-0.1109708242879819,0.8549881326852271,0.13861845427111294,-0.7675027638949218,1.0031110745456604,0.29563791844960413,0.26745263176843004,-0.22888631737725262,0.5697189110271561,-0.18176300353786812,0.889391384541065,-0.18450173948816442,1.012090104372869,-0.5906841398500662,0.3920193857083104,-0.45714654899472906,-0.3297845424724244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4166666666666667,0.0,1.0,1.0,1.0,-0.023337884208496924,-0.016344645684774676,0.006283373871532999,0.997565792660218,-0.045658558962741444,-0.030673525769624618,-0.04285930615977006,-0.06441338101051165,-0.04708035034889027,0.016518585604383875,-0.21846801823088918,-0.14197174643310365,-0.21030360196516734,0.12285741235543632,0.6330125477552915,-1.115598666155323,0.2645546565717863,0.47858426420040623,-0.7279614021483723,-0.047320334853422436,-0.10252821371814935,0.8500232561962545,0.14189301846125515,-0.771271584256487,1.0003015982949528,0.2952699479612794,0.2652957124728128,-0.2274227253647343,0.5668380157399888,-0.18810076535374032,0.9004499607518257,-0.18762604023614862,1.0141338340405566,-0.6009149695846916,0.3938609954148359,-0.4473204359855165,-0.34452714025087205,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.425,0.0,1.0,1.0,1.0,-0.02391629684464112,-0.016676470497645323,0.006420060406829294,0.9974676050088723,-0.04656463041535512,-0.031263913395663916,-0.04373419567494015,-0.0648091660276891,-0.0472362287363933,0.016565230617493494,-0.21827063874849775,-0.14163138027526004,-0.21023599184133016,0.12531642938434578,0.6352143628485896,-1.1174878357864932,0.269266311153883,0.47699019016564614,-0.7204113478052302,-0.04889693341532802,-0.09406859372063929,0.8449728831921489,0.14518280419469354,-0.7749581044946804,0.9973689555414792,0.294886112620652,0.26314130698940064,-0.22599761153401676,0.5639610759299707,-0.1945164462521487,0.9116195104975677,-0.19076490667768203,1.0161733844288998,-0.6112050283301462,0.39567219116942276,-0.43739448671911596,-0.3593456399801309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.43333333333333335,0.0,1.0,1.0,1.0,-0.024498867483215538,-0.017007993868236447,0.006556935491551632,0.9973675767211896,-0.047469717593453344,-0.03185282919902419,-0.04460874453419991,-0.0652039582063918,-0.047389932086482074,0.016609712106963014,-0.21806356825362488,-0.14128140841585426,-0.21016097484758509,0.12777218089911385,0.6373982362051148,-1.1193652930142233,0.2739540078372858,0.4753423234295371,-0.7127677436400796,-0.050499749964717136,-0.08559199064433436,0.8398365057240854,0.14848755498074553,-0.7785614923684723,0.994312504295284,0.2944860203552224,0.2609899888833622,-0.22461257147854408,0.5610881359306619,-0.20101201889857423,0.9229038522836763,-0.19391837965937575,1.0182108170722837,-0.6215578500426377,0.39745223319392065,-0.42736864083405823,-0.37424236284841594,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.44166666666666665,0.0,1.0,1.0,1.0,-0.025085585797844336,-0.01733918627548835,0.006693972636989031,0.9972657183145365,-0.04837377629710152,-0.0324402322741895,-0.0454829217547236,-0.06559765960514422,-0.047541319564141586,0.01665186750494116,-0.21784655104233663,-0.14092136873243408,-0.21007847370387178,0.1302245297235995,0.6395641959966456,-1.121231378644469,0.2786177800860607,0.4736399898506699,-0.7050296169338356,-0.05212890640965095,-0.07709841343610123,0.8346135856914383,0.15180700808125888,-0.782080915175248,0.9911315828273389,0.29406924517947963,0.258842359258058,-0.22326930540040202,0.558219214403628,-0.20758953109999423,0.9343069033566453,-0.19708650836893452,1.0202482491190066,-0.6319771427489518,0.3992003610621925,-0.4172428465678024,-0.3892197275733533,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.45,0.0,1.0,1.0,1.0,-0.025676440210239772,-0.01767001743844097,0.006831143876016412,0.997162040788182,-0.049276761139385235,-0.033026079806537836,-0.046356696122266235,-0.0659901694831122,-0.04769023998338975,0.016691524324729874,-0.21761931286865233,-0.14055076818678464,-0.20998840177425146,0.1326733349854385,0.6417122755260825,-1.12308644810423,0.2832576614106796,0.47188249791120385,-0.6971959619174688,-0.05378452510419938,-0.06858785315901758,0.8293035533449362,0.15514089433178208,-0.785515539811269,0.9878255088357281,0.29363532466395226,0.25669905038580243,-0.22196962654511765,0.5553543032577013,-0.21425110473778264,0.9458326767454106,-0.20026935102640336,1.0222878579765802,-0.6424668001872336,0.4009157919936962,-0.4070170580781385,-0.4042802554554381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4583333333333333,0.0,1.0,1.0,1.0,-0.026271417836356156,-0.01800045625850608,0.006968419672944621,0.997056555644758,-0.05017862545844532,-0.03361032694449575,-0.04723003615917193,-0.06638138343269347,-0.047836531005775514,0.01672849939667522,-0.21738155957600014,-0.14016908058644792,-0.20989066230755102,0.13511845180133203,0.6438425135030756,-1.124930872420221,0.2878736851403557,0.4700691381050402,-0.6892657389880787,-0.05546672892675767,-0.060060282469824894,0.8239058056883177,0.15848893794782049,-0.7888645328098837,0.9843935785697483,0.2931837571686974,0.2545607297171837,-0.22071547038909678,0.5524933664564846,-0.22099893417480754,0.9574852772965814,-0.20346697565897118,1.0243318864780757,-0.6530309145832747,0.40259771897316055,-0.39669123279417295,-0.41942657541294004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4666666666666667,0.0,1.0,1.0,1.0,-0.026870504422773982,-0.018330470757455204,0.007105768826460273,0.9969492749135058,-0.05107932122295466,-0.03419292666235329,-0.04810291008972457,-0.06677119241633131,-0.04798001826073057,0.01676259803234979,-0.21713297561252376,-0.13977574415185967,-0.20978514761163555,0.13755973093825014,0.6459549543547022,-1.1267650392773816,0.29246588418495434,0.4681991823416237,-0.6812378739625258,-0.05717564136518223,-0.05151565505104965,0.8184197047685483,0.16185085631466808,-0.7921270603578385,0.9808350659121791,0.29271399881810545,0.25242810430334606,-0.21950890464945694,0.5496363387032133,-0.2278352840485065,0.969268896531521,-0.2066794609670633,1.026382648621744,-0.6636737906805368,0.40424530868030273,-0.3862653288171214,-0.43466142897935267,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.475,0.0,1.0,1.0,1.0,-0.02747368427228438,-0.01866002801076164,0.007243158365055475,0.9968402111754666,-0.05197879893047726,-0.0347738296129273,-0.04897528580260886,-0.06715948169863976,-0.04812051438005696,0.016793613110320023,-0.2168732224195875,-0.1393701588714619,-0.20967173815457374,0.13999701844830045,0.6480496485747981,-1.1285893541643786,0.29703429078540927,0.4662718833708984,-0.6731112573792201,-0.05891138660954206,-0.042953904992795826,0.8128445758436421,0.16522635975915886,-0.795302288290169,0.9771492214200924,0.292225460191774,0.250301925672316,-0.21835214019424676,0.5467831239911114,-0.23476248634476393,0.9811878061237511,-0.20990689729075057,1.0284425359440073,-0.674399961157579,0.405857699211844,-0.37573930239472864,-0.449987675238539,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.48333333333333334,0.0,1.0,1.0,1.0,-0.028080940157546887,-0.01898909407590012,0.007380553434288583,0.9967293775907827,-0.052877007498097386,-0.03535298396918562,-0.04984713081022538,-0.06754612966329474,-0.048257817937946576,0.01682132407614032,-0.21660193668173253,-0.13895168362536836,-0.2095503015852285,0.1424301552747797,0.6501266531159074,-1.1304042416139524,0.30157893625147286,0.46428647423587766,-0.6648847438604633,-0.06067408965336141,-0.03437494611864953,0.807179705415922,0.16861515130153215,-0.7983893820644173,0.9733352713248701,0.2917175027034974,0.24818299520192433,-0.2172475429359988,0.5439335940068291,-0.24178293663067785,0.9932463497637056,-0.21314938768598052,1.0305140245934918,-0.6852142035814968,0.40743399757647514,-0.365113105494963,-0.4654082956698824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.49166666666666664,0.0,1.0,1.0,1.0,-0.028692253221573694,-0.01931763391517092,0.007517917175159665,0.9966167879282947,-0.053773894144649975,-0.03593033525386447,-0.050718412204577214,-0.06793100650308186,-0.048391712287151965,0.01684549584856346,-0.21631872842539138,-0.1385196330566853,-0.20942069166518534,0.14485897682669208,0.6521860318281635,-1.1322101465466452,0.3060998506855231,0.4622421677603871,-0.656557151549825,-0.0624638764043084,-0.02577867124957096,0.8014243391172838,0.17201692638543345,-0.8013875067150851,0.969392416492261,0.2911894346377708,0.24607217003984383,-0.2161976468023541,0.5410875863725384,-0.24889908930513238,1.0054489331426697,-0.21640704912081338,1.0325996831839348,-0.6961215590664893,0.40897327694214336,-0.3543866835076481,-0.48092639886985644,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5,0.0,1.0,1.0,1.0,-0.029307602863674637,-0.019645611312574827,0.007655210592815296,0.9965024565976388,-0.05466940426382239,-0.03650582615602438,-0.051589096609417524,-0.06831397277000423,-0.04852196428093579,0.01686587762305826,-0.21602317895247866,-0.13807327416761367,-0.20928274710299496,0.14728331251874255,0.6542278559499048,-1.134007535727325,0.31059706269101517,0.4601381560807921,-0.6481272616414188,-0.06428087380537496,-0.017164951398917286,0.7955776794314805,0.1754313725839012,-0.8042958267895448,0.9653198313437058,0.29064050680990994,0.2439703696255724,-0.2152051678852107,0.5382449027115677,-0.2561134517017716,1.0178000117438857,-0.2196800138028636,1.0347021815138655,-0.7071273528251476,0.4104745736124027,-0.34355997310721254,-0.4965452251095459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5083333333333333,0.0,1.0,1.0,1.0,-0.029926966609347825,-0.01997298878422115,0.007792392414725908,0.996386398684064,-0.05556348128732946,-0.03707939633339353,-0.05245915012831457,-0.06869487777078258,-0.04864832286941822,0.01688220156303223,-0.21571483859376192,-0.13761182261555818,-0.209136290280721,0.1497029852735239,0.6562522046552564,-1.135796899344732,0.3150705990640492,0.45797361023202426,-0.6395938180207602,-0.06612520996768946,-0.008533634891006538,0.7896388832368647,0.1788581692789735,-0.807113506266872,0.9611166627404353,0.290069907813158,0.24187858287452624,-0.21427301987854808,0.5354053065209297,-0.2634285768542932,1.0303040760818072,-0.22296843064979144,1.036824300252613,-0.7182372168235318,0.41193688370704584,-0.332632900311296,-0.5122681506836613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5166666666666666,0.0,1.0,1.0,1.0,-0.03055031996245096,-0.02029972748170315,0.007929418937399518,0.9962686299862137,-0.056456066537291585,-0.0376509821992456,-0.053328538288256074,-0.06907355779157973,-0.04877051755783772,0.016894181368202713,-0.2153932242657233,-0.13713443868252592,-0.20898112586205117,0.15211781098229518,0.6582591656644803,-1.1375787527253007,0.319520484466364,0.45574767979988723,-0.6309555270400553,-0.06799701431620482,0.00011545360529292992,0.7836070591510883,0.18229698731235197,-0.8098397084613997,0.9567820288323114,0.28947675881211055,0.23979787609259562,-0.2134043309264566,0.5325685208323727,-0.2708470547020836,1.0429656339735605,-0.22627246691552805,1.038968941707041,-0.7294571147805673,0.4133591595203373,-0.32160537877814477,-0.5280986919934261,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.525,0.0,1.0,1.0,1.0,-0.031177636237808573,-0.020625787087823047,0.008066243860609444,0.9961491670571362,-0.05734709906686626,-0.03822051669244699,-0.054197225978376645,-0.06944983413361039,-0.0488882567130066,0.016901510708602407,-0.21505781681315217,-0.13664022288891847,-0.2088170392698847,0.15452759792039242,0.6602488359234663,-1.1393536381935063,0.3239467410779221,0.4534594926536562,-0.6222110574545342,-0.06989641774961493,0.008782514137444145,0.7774812646571886,0.18574748860431245,-0.8124735959131744,0.9523150178738782,0.2888601078379138,0.2377294016939846,-0.2126024620118283,0.5297342256424797,-0.2783715014794419,1.0557891893616111,-0.22959230998583574,1.0411391417972902,-0.7407933697774793,0.4147403055272364,-0.3104773083879797,-0.5440405093012668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5333333333333333,0.0,1.0,1.0,1.0,-0.03180888637221858,-0.020951125703992633,0.008202818108020125,0.9960280272488177,-0.05823651548809755,-0.03878792902918905,-0.05506517738334849,-0.0698237689262727,-0.04900126151880967,0.01690387447144418,-0.2147082094287998,-0.13612834780061198,-0.20864386345158029,0.15693214611292708,0.66222132235938,-1.1411221270921645,0.328349388227072,0.45110815477522986,-0.6133590405506951,-0.07182355281596875,0.017467772635247764,0.7712605029881303,0.1892093257378059,-0.8150143302678661,0.9477146870106237,0.2882193675125,0.23567397610942287,-0.2118708760196819,0.5269023917338922,-0.28600510154907166,1.0687796688279683,-0.2329274268807069,1.04333641056653,-0.7522503102932965,0.41607942252085084,-0.29924917668809004,-0.5600972014399419,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5416666666666666,0.0,1.0,1.0,1.0,-0.03244404305585161,-0.0212756998396256,0.00833908955376332,0.9959052291626531,-0.059124251115681314,-0.03935314555335202,-0.05593235649226202,-0.070194863201127,-0.04910916335753583,0.01690090269300445,-0.2143435294859345,-0.13559756570757747,-0.20846120135620247,0.15933125404560075,0.66417673552529,-1.142884819460501,0.3327284476068203,0.4486927409611717,-0.6043980629740681,-0.07377854153096004,0.026171454313552975,0.7649437594856336,0.19268214564632663,-0.8174610821913092,0.9429800645165458,0.2875526306150977,0.233633170274945,-0.21121340808787803,0.524072005773969,-0.2937499502605534,1.081940962372947,-0.23627945729970012,1.0455666698176327,-0.7638389411430446,0.417374915116866,-0.287919908998584,-0.5762733641396744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.55,0.0,1.0,1.0,1.0,-0.03308306704670501,-0.021599464099812473,0.008475003000814775,0.9957807910275325,-0.06001023472253306,-0.039916085449220304,-0.05679872465789299,-0.07056260048236042,-0.04921153887787205,0.016892217128059103,-0.2139630823179869,-0.1350466821738354,-0.20826876401062727,0.16172468995651204,0.6661152085306291,-1.1446423505602958,0.33708392165663814,0.4462123222708873,-0.5953266911778127,-0.07576154377096375,0.034893883798874974,0.7585298539690796,0.196165574323087,-0.8198129954178425,0.9381101309416291,0.28685853227399305,0.23160920569182064,-0.21063466355677907,0.5212424813214678,-0.30160798170476455,1.0952769426601772,-0.23964877608390195,1.0478343802841568,-0.7755680131891651,0.4186253655347555,-0.27648899820944095,-0.5925729382435962,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5583333333333333,0.0,1.0,1.0,1.0,-0.0337259203906125,-0.021922370767432205,0.008610500015868645,0.9956547333890512,-0.06089439530949243,-0.04047666549494171,-0.05766424404851732,-0.07092701012904148,-0.04930802812569867,0.01687742305290195,-0.2135664599401334,-0.13447473849000882,-0.208066385457085,0.16411222958350064,0.668036888953487,-1.1463953971864473,0.34141582229551143,0.44366594126609227,-0.5861434472630651,-0.07777268779902508,0.043635360651622254,0.7520176259324809,0.1996592350719059,-0.8220692321614665,0.9331038488791525,0.2861365845873054,0.2296034692548421,-0.21013920341529158,0.518413923541009,-0.3095823012681598,1.1087923355647167,-0.2430342445803796,1.0501406347905082,-0.787441631088146,0.41982985871914624,-0.26495727270573477,-0.6089994746021077,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5666666666666667,0.0,1.0,1.0,1.0,-0.03437256225642658,-0.022244370410484486,0.0087455181723006,0.9955270773072958,-0.06177665783049511,-0.04103479725602873,-0.05852887527790886,-0.07128782902514864,-0.04939822342814011,0.016856070881144703,-0.21315281372091696,-0.13388041089899164,-0.20785366599751062,0.16649363303296713,0.6699419330182098,-1.1481446706172174,0.34572415371565496,0.4410526172497513,-0.5768468189184007,-0.07981211451397008,0.05239622771205011,0.7454058267842771,0.20316273863507278,-0.824228949962938,0.9279601396982606,0.28538508141752517,0.22761737713455021,-0.20973161455319023,0.5155855384387653,-0.3176755447326518,1.122491154669445,-0.24643680909549298,1.0524900820183947,-0.7994696336998941,0.4209868947348955,-0.25332433293747236,-0.6255577532386591,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.575,0.0,1.0,1.0,1.0,-0.03502294804619229,-0.02256541121501035,0.008879991227283956,0.9953978449402405,-0.0626569436001032,-0.04159038689813336,-0.05939257779664096,-0.07164473013328339,-0.04948165447627154,0.01682770026660336,-0.21272132403529795,-0.13326230862083557,-0.2076302300672013,0.16886864760712605,0.6718305119057295,-1.1498909240956672,0.3500089146028242,0.4383713488538814,-0.5674352613519077,-0.08187996795061663,0.0611768620185955,0.7386931320374827,0.20667568331748748,-0.8262913043770911,0.9226778863251749,0.28460244480939756,0.22565282443713697,-0.20941714352116225,0.5127566502447767,-0.3258901252272173,1.1363771564715286,-0.24985684812055625,1.0548869337052431,-0.8116613777300463,0.42209495626398197,-0.24158995374365055,-0.6422524197907586,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5833333333333334,0.0,1.0,1.0,1.0,-0.03567702902133118,-0.022885438868693382,0.00901384874680978,0.9952670596086188,-0.06353517010318625,-0.04214333485628487,-0.060255309799695726,-0.07199735095103743,-0.04955781633745912,0.016791808251042345,-0.2122711202097147,-0.1326189488149443,-0.20739567029370196,0.17123700711312376,0.6737028134254954,-1.15163495634257,0.35427009788640124,0.435621115162631,-0.5579071996438753,-0.08397639531597935,0.0699776766071375,0.731878137155443,0.21019765457280581,-0.8282554491919989,0.917255932701748,0.2837869907575391,0.22371190163040122,-0.20920146471918422,0.5099265355628435,-0.334228312525372,1.15045378584119,-0.25329476062706524,1.0573356467685575,-0.8240267985092609,0.4231524584754759,-0.2297539237750179,-0.6590882167110235,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5916666666666667,0.0,1.0,1.0,1.0,-0.03633475189212128,-0.023204396381173643,0.009147015771759755,0.9951347458739204,-0.06441125070871676,-0.04269353542804674,-0.06111702810956893,-0.07234528937804541,-0.04962616289115758,0.016747851333137127,-0.21180126566577862,-0.13194874051778127,-0.20714954220979265,0.17359843078641837,0.6755590435995695,-1.1533776151743202,0.35850769019553824,0.43280087697845854,-0.5482610315878879,-0.08610154729440105,0.07879912279807146,0.7249593520623283,0.21372822429207874,-0.830120536440008,0.9116930827133245,0.28293689681017864,0.2217968970116413,-0.20909070559286036,0.5070944003133271,-0.3426922042625913,1.164724104802417,-0.2567509857555697,1.059840969572219,-0.8365765332921349,0.4241577241812855,-0.2178160313785127,-0.676070022105546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6,0.0,1.0,1.0,1.0,-0.03699605835802851,-0.023522223875881345,0.009279412471929701,0.9950009296247717,-0.06528509434843216,-0.04324087631533934,-0.061977688045423515,-0.07268809868699112,-0.04968610214357359,0.016695243167539082,-0.21131075095970217,-0.13124997288152884,-0.20689136024237634,0.17595262205996007,0.6773994283756894,-1.1551198014357844,0.3627216712249567,0.42990957842492117,-0.5384951312305016,-0.08825557841190551,0.08764169276667448,0.7179351949339075,0.21726694997582724,-0.8318857163816408,0.9059880989999889,0.2820501853866403,0.2199103149828896,-0.20909148677592526,0.5042593707211118,-0.3512836801588648,1.1791907012008207,-0.26022600868447043,1.0624079766032426,-0.8493220041433491,0.42510897165643824,-0.20577606456431585,-0.6932028562665282,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6083333333333333,0.0,1.0,1.0,1.0,-0.03766088459419681,-0.023838858361496667,0.009410953774061342,0.994865638171321,-0.06615660516647831,-0.04378523812300036,-0.06283724327909444,-0.07302528202237332,-0.049736991765695085,0.016633351037311832,-0.2107984874550274,-0.13052080445088626,-0.206620593735275,0.17829926720952904,0.679224215515951,-1.1568624732872523,0.3669120130408901,0.4269461489758108,-0.5286078532345408,-0.09043864743914222,0.0965059224081255,0.7108039853266058,0.22081337381968605,-0.83355013751608,0.900139701775549,0.2811247088088237,0.2180548985056241,-0.20921096617695145,0.5014204862867944,-0.360004346340711,1.193855582198231,-0.2637203652032702,1.0650421057538637,-0.862275499846954,0.426004304330565,-0.19363381547962577,-0.7104918780609104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6166666666666667,0.0,1.0,1.0,1.0,-0.038329160679175904,-0.02415423348368554,0.009541548958992698,0.9947289003480237,-0.06702568213942312,-0.04432649381450726,-0.06369564567739547,-0.07335628639210601,-0.04977813437140459,0.016561491808893766,-0.21026330072110866,-0.12975925221865803,-0.20633666274445617,0.18063803387344046,0.6810336766841165,-1.158606650872067,0.3710786793297366,0.4239095059859093,-0.5185975381938644,-0.09265091783196001,0.10539239452923888,0.7035639366031249,0.22436702171467,-0.8351129466396345,0.8941465676989737,0.2801581336874054,0.2162336541012433,-0.20945688638842608,0.4985766927238966,-0.3688554702223201,1.208720051145149,-0.26723464635469457,1.0677491998892505,-0.8754502646486162,0.4268417002361874,-0.18138908706286871,-0.7279423770376581,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.625,0.0,1.0,1.0,1.0,-0.03900080995846833,-0.024468279256050694,0.00967110122483827,0.9945907466254561,-0.06789221866470907,-0.04486450812278919,-0.06455284512969654,-0.0736804961002432,-0.04980877240579224,0.01647892750512807,-0.20970392347565014,-0.12896318005497448,-0.20603893349958394,0.18296856943765247,0.6828281097509717,-1.160353421393726,0.3752216245862884,0.4207985578054388,-0.5084625190487884,-0.09489255821172046,0.11430174240627967,0.6962131475824622,0.22792740215695584,-0.8365732889671278,0.8880073288249214,0.27914792409954037,0.21444987920378633,-0.2098376257040213,0.4957268344344279,-0.37783790482598834,1.223784565090127,-0.2707695033530136,1.0705355534952623,-0.8888605965834917,0.4276190007524333,-0.16904170146899933,-0.7455597624780075,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6333333333333333,0.0,1.0,1.0,1.0,-0.03967574833796375,-0.02478092176880436,0.009799507213395085,0.9944512092318745,-0.06875610211525156,-0.04539913691323604,-0.06540878935950514,-0.07399722556885377,-0.04982808259387207,0.016384860512602503,-0.20911898802058704,-0.12813028637987017,-0.20572671347668708,0.18529049927509947,0.684607841337513,-1.1621039446338006,0.37934079323697706,0.41761220757214285,-0.49820112877569567,-0.09716374288784357,0.12323465375415991,0.6887495933267334,0.23149400506054388,-0.8379303083307845,0.8817205716576736,0.27809132336386877,0.2127071919545065,-0.21036225299495115,0.49286964640937736,-0.3869520009718519,1.2390485698586051,-0.2743256527915161,1.0734079651417296,-0.9025219570707588,0.42833389852613757,-0.15659151031353957,-0.7633495494096132,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6416666666666666,0.0,1.0,1.0,1.0,-0.04035388350083846,-0.02509208287353442,0.009926656496960881,0.9943103222852889,-0.0696172133577688,-0.04593022649575939,-0.06626342371863381,-0.07430571149967989,-0.049835169920086596,0.016278428417157032,-0.20850701815500217,-0.12725809104476085,-0.20539924604539153,0.18760342482705028,0.6863732296168802,-1.163859458943642,0.38343611869311134,0.41434935778924126,-0.48781170955114495,-0.0994646524249124,0.13219187515864184,0.6811711149646162,0.2350663004657248,-0.8391831474723535,0.8752848363347612,0.2769853343097056,0.21100956357507528,-0.21104058659245695,0.4900037455137918,-0.39619750551641464,1.2545103093287724,-0.27790388211063916,1.076373796569746,-0.916451093302757,0.42898392453726675,-0.14403840689802605,-0.7813173412700225,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.65,0.0,1.0,1.0,1.0,-0.04103511404104135,-0.02540167984238631,0.010052431022703952,0.9941681219368537,-0.07047542623239192,-0.046457612882726956,-0.06711669096241919,-0.0746051043312196,-0.049829061117466524,0.016158698461068065,-0.20786642056530916,-0.12634392143385315,-0.20505570466298434,0.18990692151359456,0.6881246673970975,-1.165621287743675,0.3875075223288736,0.41100891581353594,-0.4772926236202161,-0.10179547425635423,0.14117421703032235,0.6734754084383541,0.238643737136165,-0.8403309484457516,0.8686986159698399,0.27582669797100556,0.20936135344435725,-0.2118832572263285,0.4871276211404052,-0.40557344358811975,1.2701666051573335,-0.2815050552789136,1.0794410393135978,-0.9306661750373513,0.4295664343092931,-0.13138234061584653,-0.7994688087868562,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6583333333333333,0.0,1.0,1.0,1.0,-0.04171932850610063,-0.025709624999985185,0.010176704511718869,0.9940246465263899,-0.07133060699114241,-0.046981120989711675,-0.06796853100436069,-0.07489445895451836,-0.0498086976530295,0.016024661621793283,-0.20719547570948854,-0.12538489783307774,-0.20469518659401412,0.19220053645990037,0.6898625855076195,-1.1673908465640808,0.39155491237878476,0.40758980039610593,-0.46664226613185605,-0.10415640334622762,0.1501825591472018,0.665660012047327,0.24222574103754635,-0.8413728531492842,0.8619603561883136,0.27461187066360415,0.2077673469688568,-0.21290177495531193,0.48423962523344577,-0.4150779825189066,1.28601260277327,-0.28513011861678483,1.0826183898830577,-0.9451869475551122,0.4300785932945267,-0.11862333375394662,-0.8178096645825828,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6666666666666666,0.0,1.0,1.0,1.0,-0.0424064043416862,-0.026015825326472623,0.010299341809964006,0.9938799367508625,-0.07218261369298105,-0.04750056377625866,-0.06881888064846735,-0.07517272466228005,-0.04977292820608893,0.015875226322302868,-0.20649232823218797,-0.12437791815486049,-0.2043167061413907,0.19448378602465463,0.6915874565132452,-1.1691696506595968,0.395578182749431,0.4040909494382208,-0.45585908024066163,-0.10654764289996731,0.15921785686170664,0.6577222926457689,0.24581171369107377,-0.8423080040083174,0.8550684548934635,0.273336999437106,0.2062327962807764,-0.21410859988058473,0.4813379617048785,-0.4247082749104347,1.3020414789945889,-0.2887801066646953,1.0859153346616002,-0.9600349027226396,0.4305173614991842,-0.10576150090817915,-0.8363456329761809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.675,0.0,1.0,1.0,1.0,-0.04309620673020771,-0.026320182030149752,0.01042019818843954,0.9937340358466007,-0.07303129555336091,-0.048015741324320904,-0.06966767329754579,-0.07543873432277833,-0.04972050065023108,0.01570921179722331,-0.20575497697424666,-0.1233196421583993,-0.2039191873847033,0.19675615311718547,0.6932997987789657,-1.1709593232287572,0.39957721174053273,0.4005113291475987,-0.4449415748152796,-0.10896940512397255,0.16828114805822847,0.6496594303352831,0.24940103039586609,-0.8431355448310872,0.8480212623053772,0.2719978959380204,0.20476346372054754,-0.2155172162475738,0.47842067529085264,-0.43446027800523535,1.318244106146964,-0.2924561479599386,1.0893422458167368,-0.9752334702974408,0.43087947745876376,-0.09279707122608505,-0.8550824144266889,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6833333333333333,0.0,1.0,1.0,1.0,-0.043788587315772065,-0.026622590088419534,0.01053911859025859,0.9935869897860014,-0.07387649224658421,-0.0485264398526885,-0.07051483863563861,-0.07569119279333747,-0.049650053568813905,0.015525341157908702,-0.20498126467465852,-0.12220647537086518,-0.20350145643450845,0.1990170842902883,0.6950001809085876,-1.172761604263723,0.40355186067094523,0.39684994480480024,-0.43388834513821223,-0.11142191203263295,0.17737356095865225,0.6414684014741449,0.2529930383153865,-0.8438546218620855,0.8408170813196854,0.2705900087821861,0.20336566795078337,-0.21714220929056616,0.4754856399309504,-0.444328546270224,1.334608667099122,-0.29615947053930863,1.092910489671427,-0.9908082318073186,0.43116144173357074,-0.07973041366868605,-0.8740256440593197,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6916666666666667,0.0,1.0,1.0,1.0,-0.04448338280814284,-0.026922937756034805,0.010655936822733728,0.9934388474893556,-0.0747180331598154,-0.04903243066671136,-0.07136030228284346,-0.0759286646208188,-0.04956010735968523,0.015322234224401723,-0.20416886750774854,-0.12103455299968774,-0.2030622332298141,0.20126598659688857,0.6966892265781455,-1.1745783600502666,0.4075019724060486,0.3931058533764283,-0.4226980970302942,-0.11390539629962769,0.18649632288608559,0.6331459598051611,0.25658705442475893,-0.8444643850588986,0.8334541682377219,0.26910839461612657,0.2020463324029853,-0.2189993438548976,0.4725305467974028,-0.454305993856583,1.3511202152078028,-0.2998914069250114,1.09663254915023,-1.0067871595365485,0.4313595001720705,-0.06656206544753074,-0.8931808437323641,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7,0.0,1.0,1.0,1.0,-0.045180413459047664,-0.027221106040116235,0.010770474693295498,0.9932896610522806,-0.07555573659839047,-0.049533469043968686,-0.0722039854208281,-0.0761495611210345,-0.04944905501906023,0.01509840022445464,-0.20331528465555412,-0.11979972423319987,-0.20260012293015528,0.20350222420055708,0.6983676197819707,-1.1764115933279713,0.4114273697842353,0.38927817824052385,-0.41136967488474885,-0.1164201021480498,0.19565077011115609,0.624688615481869,0.26018236331825434,-0.8449639896195443,0.825930733924146,0.2675476881557015,0.20081303556331864,-0.22110564341517147,0.46955289216012996,-0.4643836234064802,1.3677601728366306,-0.3036533982767317,1.1005221620822865,-1.0232008833383177,0.43146962728836336,-0.053292763731711545,-0.9125533671527397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7083333333333334,0.0,1.0,1.0,1.0,-0.045879481405393156,-0.027516968142048123,0.010882541089044493,0.9931394859890195,-0.0763894089431534,-0.050029293058372615,-0.073045804387524,-0.07635212698857281,-0.04931515273925854,0.014852230500994948,-0.2024178281875378,-0.11849753746241495,-0.2021136069859293,0.20572511473281693,0.7000361105042008,-1.1782634541071861,0.41532785394205074,0.3853661263196536,-0.3999020941496837,-0.11896628627090655,0.20483835892079036,0.6160926117495225,0.263778214879565,-0.8453525977877605,0.8182449454518429,0.265902071631931,0.19967406234404628,-0.22347946757766302,0.4665499653481042,-0.4745502175602412,1.3845057619320156,-0.3074469973007224,1.1045944773157608,-1.0400829881517692,0.4314875102258875,-0.039923480622314766,-0.9321483376544903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7166666666666667,0.0,1.0,1.0,1.0,-0.04658036887584431,-0.027810388867237534,0.010991931001088175,0.9929883814915486,-0.07721884376201825,-0.05051962234763259,-0.0738856702397606,-0.0765346048506963,-0.04915652530729263,0.014582117984117172,-0.20147359522638575,-0.11712272464439105,-0.20160113165800891,0.2079339253944226,0.7016955208210381,-1.1801362511209323,0.419203202540037,0.38136900794785317,-0.3882945788525486,-0.12154421876972851,0.21406067806641876,0.6073538990126729,0.26737382182201913,-0.8456293809632496,0.8103949282965711,0.26416551993513726,0.19863735378570002,-0.22613995115617236,0.4635189885612456,-0.4847929656974881,1.4013298593900014,-0.31127376092161263,1.1088664714510417,-1.0574729511267789,0.43140843352109326,-0.026454100199480024,-0.9519739466403854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.725,0.0,1.0,1.0,1.0,-0.04728283940782237,-0.02810122349401446,0.01109842627420671,0.9928364108128862,-0.07804382036899837,-0.05100415274694249,-0.07472348940570182,-0.07669469306662466,-0.04897114440557184,0.014286037955499311,-0.20047958076678107,-0.11567099875789695,-0.20106075387649966,0.21012787339840255,0.7033467330672958,-1.1820324532931223,0.4230531704180715,0.3772862435580288,-0.37654659649318367,-0.12415418228626676,0.22331946677830772,0.5984680625640761,0.2709683554382499,-0.8457934994577518,0.8023787130078365,0.26233087208740125,0.19771420206783796,-0.22910928241635098,0.4604566421940337,-0.4950939313189784,1.418198721495273,-0.3151355247578147,1.1133556420595625,-1.075406280281066,0.43122770908192276,-0.012888439020364295,-0.9720295467482276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7333333333333333,0.0,1.0,1.0,1.0,-0.04798662647096406,-0.028389319232857015,0.011201788729346645,0.9926836411464092,-0.07886410516167985,-0.05148256963872431,-0.0755591592114982,-0.07682991037892295,-0.04875675882953692,0.013961865101155348,-0.19943243888879042,-0.11413726411619568,-0.2004904619209328,0.21230610659587928,0.7049907575221688,-1.1839547391612049,0.4268774799099376,0.3731174424258702,-0.36465793349429404,-0.1267964775156921,0.23261660543407814,0.5894304610079885,0.27456095030671784,-0.8458441882802556,0.7941944358507673,0.26039055161880154,0.19691604066712554,-0.23241046936648413,0.45735937270234617,-0.5054322418348689,1.4350725227794503,-0.3190343244414956,1.1180828521073949,-1.09392669224452,0.4309400902650229,0.0007709581158144019,-0.9923171294969335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7416666666666667,0.0,1.0,1.0,1.0,-0.048691440931452876,-0.02867451137151111,0.011301765251728225,0.99253014445519,-0.07967944688467032,-0.05195452814183605,-0.07639257226636383,-0.07693787238805641,-0.048510976162858856,0.01360764206909181,-0.19832857063030632,-0.11251488279013562,-0.19988831783974084,0.21446771592538258,0.7066286670784145,-1.185905961115897,0.43067582662977727,0.368862372860781,-0.35262872111352617,-0.12947142102695836,0.24195418098009763,0.5802359510266675,0.27815069027600026,-0.8457806501558216,0.7858400941828876,0.25833701609579873,0.19625295613675542,-0.2360668997386961,0.4542237182959752,-0.515785127023658,1.4519050011798729,-0.32297206605110207,1.1230719667366396,-1.113088664030235,0.4305397315129589,0.01452418277577694,-1.0128455906376055,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.75,0.0,1.0,1.0,1.0,-0.04939696480619783,-0.028956624683034345,0.011398085020053985,0.9923759975403842,-0.08048957823654916,-0.05241966040807077,-0.07722361364072786,-0.07701576369736987,-0.048231266748408566,0.013221083568016384,-0.1971643133813241,-0.1107979224497885,-0.1992520250236738,0.21661172353080926,0.708261640124448,-1.1878891874901831,0.4344478752148705,0.36452102364214256,-0.3404595168079628,-0.13217934528321046,0.25133447154635546,0.5708789832741512,0.2817366124986005,-0.845602118567326,0.7773136760068072,0.25616172423700234,0.1957378224224704,-0.24010489325039241,0.4510458040317544,-0.5261238795511158,1.4686408204609402,-0.3269507668816668,1.1283477429323885,-1.1329446591037695,0.43002080829372735,0.028367785512701804,-1.0336164564016248,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7583333333333333,0.0,1.0,1.0,1.0,-0.05010284933418476,-0.029235472265260996,0.011490457467114003,0.9922212823537577,-0.08129421425382267,-0.052877574048009524,-0.07805216035392862,-0.07706057011845817,-0.047914890770233705,0.01279972935357565,-0.1959357207685527,-0.10898006011467753,-0.19857913034089525,0.21873707799599929,0.709890964118789,-1.189907709336737,0.4381932566969732,0.36009364153492907,-0.32815137410584383,-0.13492060047498614,0.26075997669563744,0.5613535400416046,0.2853177037475624,-0.8453078537306099,0.7686131532428605,0.2538555584057067,0.19538415942314424,-0.24455192658065172,0.4478214783351364,-0.5364149261540263,1.4852155305596193,-0.3309725702839633,1.1339382940471343,-1.153553989739855,0.429377107021196,0.04229838264982355,-1.054631444945402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7666666666666666,0.0,1.0,1.0,1.0,-0.05080871255634083,-0.02951085486332078,0.01157857140461514,0.9920660863269507,-0.08209305132019853,-0.05332785061012701,-0.07887808082205292,-0.07706903933766793,-0.047558931005561064,0.012340996467703608,-0.19463864559465674,-0.10705463612556793,-0.19786701149610467,0.2208426495042377,0.7115180427815004,-1.191965052933194,0.4419115665204561,0.3555807748729088,-0.31570592463196917,-0.13769555478794318,0.2702334431138077,0.5516530834451536,0.2888928976156204,-0.8448971455231623,0.7597364852577172,0.2514088198396136,0.19520637238375382,-0.24943694907741953,0.4445463570428454,-0.5466190980879981,1.5015542153851325,-0.33503963978913254,1.139874968984077,-1.1749823519606006,0.42860210081220096,0.05631216468626743,-1.0758916740942426,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.775,0.0,1.0,1.0,1.0,-0.05151413689523664,-0.02978256023612996,0.011662093998758005,0.9919105026830995,-0.08288576627515125,-0.05377004439956747,-0.0797012342514869,-0.07703768645499226,-0.04716029631123157,0.01184217212999399,-0.19326875918912534,-0.1050147294273599,-0.19711287261770363,0.22292722499332618,0.7131444036585183,-1.1940649918213606,0.44560236264768727,0.35098332323346243,-0.3031254705160916,-0.14050459447147168,0.27975789284537206,0.5417705008422613,0.2924610720944324,-0.8443693176525054,0.7506816253412898,0.2488112368685269,0.19521975657269097,-0.25479027644137897,0.4412158364911445,-0.5566909148498878,1.5175702464226715,-0.3391541262192532,1.146192698352635,-1.1973022852792226,0.4276889947735074,0.07040479541376765,-1.0973974081795967,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7833333333333333,0.0,1.0,1.0,1.0,-0.05221866681627474,-0.030050362583704603,0.011740669779755224,0.9917546307288272,-0.08367201562880892,-0.054203681566650404,-0.08052147001366257,-0.07696280768024508,-0.046715732437549576,0.011300423058797476,-0.19182157845210127,-0.10285322923381224,-0.19631374658850032,0.2249895034520465,0.7147717053910453,-1.1962115575405503,0.4492651637953085,0.346302592958744,-0.2904130871915913,-0.14334812355826407,0.2893366547530183,0.5316980453571666,0.2960210475285122,-0.8437237322662662,0.7414465284547239,0.24605199480187856,0.19544043572761405,-0.26064339181131935,0.4378251163655811,-0.566577883446433,1.533164029286328,-0.34331811640193444,1.1529304034821908,-1.2205938078958734,0.4266307798200464,0.08457137814135818,-1.1191479429455775,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7916666666666666,0.0,1.0,1.0,1.0,-0.0529218066709184,-0.0303140220669298,0.011813919771197527,0.9915985761156161,-0.08445143493666403,-0.054628259503186075,-0.0813386270247639,-0.07684050549369774,-0.04622184123708307,0.010712814541620125,-0.19029250603159603,-0.10056292274043241,-0.19546650382212105,0.2270280915733575,0.7164017442539785,-1.1984090483515493,0.45289944792044695,0.3415403585093552,-0.2775727366946528,-0.14622656307817058,0.29897339957007524,0.5214272707106634,0.29957158509143317,-0.8429597946834828,0.7320291596255302,0.2431197933862772,0.19588524600023582,-0.2670286541443945,0.4343692375182229,-0.5762198065400825,1.5482217565405265,-0.3475335631196136,1.1601314458093925,-1.2449451263237599,0.4254203072827778,0.09880645576462399,-1.1411415527648372,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8,0.0,1.0,1.0,1.0,-0.05362301885264105,-0.030573284459811778,0.01188144080864484,0.9914424510552924,-0.08522363839898585,-0.05504324663531832,-0.0821525331524032,-0.07666672897242824,-0.04567511009478865,0.010076338791939192,-0.18867688572530739,-0.09813660887351841,-0.19456786839036472,0.22904150000848444,0.7180364594910492,-1.2006620351096235,0.4565046510872789,0.3366989295164093,-0.2646093912492492,-0.14914034961025763,0.3086721788498415,0.5109489599184373,0.3031113859832252,-0.8420769580035224,0.72242750257531,0.24000293644381832,0.19657155700531614,-0.2739788946246824,0.43084313668132146,-0.5855481234728888,1.5626142186070768,-0.3518021951688799,1.167844110423314,-1.2704533874325574,0.4240503901297954,0.11310404231133386,-1.1633754906546878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8083333333333333,0.0,1.0,1.0,1.0,-0.0543217224330924,-0.030827880982767442,0.011942805122171225,0.991286374470487,-0.08598821876240895,-0.05544808273228195,-0.0829630046740094,-0.07643733355070692,-0.0450719538954678,0.00938795381900737,-0.18697007572371635,-0.09556724497576663,-0.1936144429335955,0.2310281405140878,0.7196779368707338,-1.2029753632619606,0.46008016686513564,0.3317812231181404,-0.2515291663845349,-0.15208993299765192,0.31843746807713047,0.5002530475867875,0.3066390915935964,-0.8410747273116272,0.7126395681146187,0.23668946018369053,0.1975170157035544,-0.28152687820962363,0.42724172096476054,-0.594485325032883,1.576195748898923,-0.35612540479687926,1.1761221184522175,-1.297225454921772,0.42251393640037715,0.1274576929645077,-1.1858460533509207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8166666666666667,0.0,1.0,1.0,1.0,-0.055017292489543755,-0.031077528374681387,0.011997560268593157,0.9911304720569784,-0.08674474761496881,-0.055842179875452355,-0.08376984581628481,-0.07614816519087365,-0.044408772163488236,0.008644634485315533,-0.18516754253169027,-0.09284813239320856,-0.19260274404356123,0.2329863243448793,0.7213284097527751,-1.2053541497464506,0.46362534643669157,0.32679084076586123,-0.23833946210093382,-0.15507577302353895,0.32827421415737845,0.48932853566974105,0.31015328492323146,-0.8399526631207807,0.702663401686128,0.23316730779875783,0.19873919578361487,-0.2897046062516262,0.42355996559645503,-0.6029444977217302,1.5888034035914822,-0.3605041092959671,1.1850251608478113,-1.3253786927536026,0.42080412063548844,0.1418606234989439,-1.2085487336317535,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.825,0.0,1.0,1.0,1.0,-0.05570906038493187,-0.03132192927085255,0.012045229510981864,0.9909748762307884,-0.08749277617977012,-0.056224924254917055,-0.08457284841046284,-0.0757951746738338,-0.04368202419694096,0.007843437462167945,-0.18326497830328797,-0.08997314636545092,-0.1915292498813092,0.23491426231073376,0.7229902568004607,-1.2078037733661544,0.46713949962507656,0.32173214815611156,-0.22504910965801017,-0.15809833481925137,0.338187887424594,0.47816340270756075,0.3136524936041879,-0.8387103835866448,0.6924970892207561,0.22942455844996434,0.20025513308242537,-0.29854243649101164,0.41979303854688843,-0.6108290691745355,1.6002565032970812,-0.36493858359585074,1.1946194427989199,-1.3550417346068477,0.41891459905774586,0.15630589257168204,-1.2314784891987673,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8333333333333334,0.0,1.0,1.0,1.0,-0.05639631531818653,-0.03156077296283755,0.01208531275346076,0.9908197259290384,-0.08823183672520785,-0.056595678981159914,-0.08537179170348407,0.23241963415904993,0.02527883816069476,-0.051870096230031,0.03505324477200565,-0.23936716336902236,0.1192965980051251,0.23681006698571203,0.7246659953041489,-1.2103298570213008,0.4706218970791397,0.316610356279619,-0.2116685203793158,-0.16115808275013646,0.3481845382040271,0.4667445067596269,0.31713519490752723,-0.8373475649112526,0.6821387601994818,-0.07141882342009742,-1.923604456156922,1.4562415753208402,-0.10403762799633731,0.42293885154897737,0.6045017357243876,-0.09414085928963034,1.3285187454540592,-1.0307168940413103,0.1287729435927465,-0.10657988925055317,0.8380703214025287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8416666666666667,0.0,1.0,1.0,1.0,-0.05175726416216186,-0.03168946729582991,0.01162292973123051,0.9909698455157913,-0.08743164248245112,-0.058137573358788094,-0.08339361927209873,0.5597776791202541,0.10384778767360325,-0.13096999523272432,0.30982610284817147,-0.449026816937845,0.5725713867588768,0.23372394858706547,0.6909301825311787,-1.1835330804441404,0.46540553915847094,0.3287811290152612,-0.21497408072927038,-0.1596673491407452,0.360329866515495,0.46098478780687224,0.3157987093307337,-0.8404867150741541,0.7064649279107983,-0.6059657465890073,-4.045519698383695,3.275235781692283,-0.77054818296866,1.680029035810764,-0.6601976502368112,0.3401280001316431,1.248457981002734,-0.2003574583245249,-0.164688090864612,-0.4525054163847808,3.221247951161934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.85,0.0,1.0,1.0,1.0,-0.04673617123882716,-0.031727093458245696,0.010878527930862702,0.9912213963897314,-0.08626342771062322,-0.060101927925314345,-0.08016559510614382,0.5958674687052221,0.1195954886153431,-0.1622649539163709,0.38943350154321427,-0.5324449252486784,0.782364576232068,0.22671063787589524,0.657240666997754,-1.155742593993096,0.4577794273629954,0.3446108402097984,-0.22267181454992932,-0.1554892827479424,0.36899217122073935,0.4634052157875515,0.31439039339311703,-0.844889321850999,0.7358262260521807,-0.9585190473132293,-4.012615248224418,3.3925563308602324,-0.9724157678940193,1.9984512309806468,-1.0134964951848802,0.5927897826435291,0.8545277995523293,0.6569728407137609,-0.15889409534833754,-0.531869376109011,3.634065556113304,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8583333333333333,0.0,1.0,1.0,1.0,-0.041403264217819175,-0.03171535583553682,0.009977271285026762,0.991503162508939,-0.08496278429669415,-0.06223350154837852,-0.07635309623478419,0.6252161847150629,0.128242036548383,-0.18330436086722768,0.4283936511611198,-0.5689705467535844,0.8848239275306411,0.21774863113184498,0.6240532617274384,-1.1269904749298032,0.4491986096935706,0.3620886495316053,-0.23186568898235171,-0.14978751943001972,0.3745719965080338,0.4719343351521016,0.3131504744082614,-0.8493512046759709,0.7670326871793534,-1.1520082514675773,-3.9593613516174786,3.5260494915103147,-1.061306505907731,2.1503650669305987,-1.132693367586175,0.7354784837992528,0.4984866222693951,1.327533168572519,-0.14314788117383404,-0.5168200705522952,3.7867358422270936,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8666666666666667,0.0,1.0,1.0,1.0,-0.03583450721969936,-0.031656786789840886,0.008972587714370336,0.9917910432511826,-0.08354492841134346,-0.06444900996749378,-0.0722294716712826,0.6472543065658448,0.13397880176248528,-0.1992767583161739,0.4613761754396607,-0.5864006856625019,0.9419647224056172,0.20751050035143562,0.5912513111374627,-1.0969751024679242,0.4400909855978665,0.380450257991975,-0.24155003734303224,-0.14323130801795486,0.37730028159189594,0.4855307685970935,0.31200459537355313,-0.8535029896935372,0.798938490089299,-1.287605050346533,-3.9203849359950405,3.6849385172062776,-1.1141085944901008,2.234311525784769,-1.1683522616548603,0.8208491435034115,0.16371861505233953,1.8981001123710306,-0.13439463317416744,-0.4698402796527068,3.834750691037223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.875,0.0,1.0,1.0,1.0,-0.030089387655788565,-0.031547564615874574,0.007889965819746093,0.9920753501190258,-0.08200860373311232,-0.06670166802779189,-0.06791153129196265,0.6634401327923322,0.13804878236041324,-0.21231150674451077,0.49253128412235736,-0.5921396605305368,0.9796017265839819,0.19628854695940276,0.5587135127941877,-1.0655748329763652,0.4306301331187356,0.39932717496135145,-0.2513382266765994,-0.13610670037162953,0.37730064009223946,0.5035693370249521,0.3109105638553586,-0.857181876003516,0.8309451986966404,-1.3963703243241687,-3.8953283985922904,3.8531134999029115,-1.1512800202160212,2.2838569769796715,-1.1726836262470537,0.8828582615330444,-0.15709278472744725,2.3994660251275537,-0.12891997415680367,-0.40739864934605574,3.8230773847532507,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8833333333333333,0.0,1.0,0.0,1.0,-0.024213460482351644,-0.03138495149829932,0.006746167200507738,0.9923520963782415,-0.08035290813312242,-0.06895330931009905,-0.06345209297993816,0.6752429269213528,0.14083258854439337,-0.22314780378687804,0.5225428754794802,-0.5882911316795538,1.0084603300930741,0.18423766161269947,0.5263291711609245,-1.032756544136209,0.42090298526093284,0.4185145409416362,-0.2610947644471498,-0.1285170036590708,0.37468206851310515,0.525521869015886,0.3098559291376064,-0.8602929671826381,0.8626564465018531,-1.489937136664562,-3.8826298701142283,4.0226441301151965,-1.1800912964638555,2.3136556760076266,-1.1676236950527819,0.9370931688474204,-0.46408598104082266,2.8376308075091417,-0.12415797788539296,-0.33526013740208915,3.769532364794399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8916666666666666,0.0,1.0,0.0,1.0,-0.01824032809281225,-0.031167779102589305,0.005555338067993367,0.9926198259709442,-0.07857830800134695,-0.07116723257820741,-0.05887746265142303,0.6840144197335596,0.1425332415909723,-0.23207132393846985,0.5515240133588041,-0.5753823345918166,1.0330312530878574,0.17145626134832673,0.49400301495895055,-0.998530764141112,0.410961944844338,0.4378881028948119,-0.27079862159414575,-0.12048848089083919,0.3695658737415591,0.5508631838167711,0.3088412642239354,-0.8627695449602175,0.8937707381098804,-1.573261852382249,-3.8802087357791173,4.18923000570488,-1.2035536420958892,2.3313941094000246,-1.163495391040461,0.9898209422210278,-0.7557163247932053,3.212155824478826,-0.119104532969867,-0.25599217277748165,3.6832309647325734,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9,0.0,1.0,0.0,1.0,-0.01219282380529655,-0.030896012310996097,0.004330742967346772,0.9928783533278319,-0.07668628437845608,-0.07330651697689942,-0.05420280297171374,0.6909891166718876,0.14330547310489727,-0.23924360254912164,0.5794731500452971,-0.5534977650498597,1.0552130952336414,0.158016630739662,0.46165902556460586,-0.9629360440411276,0.400843757892668,0.4573711094316366,-0.28048635429782415,-0.112019987955387,0.3620867964332184,0.5790577994238665,0.3078708535881086,-0.8645595033955962,0.924043629247396,-1.6487424895234226,-3.8856405578754605,4.349750926253626,-1.2230831733931213,2.3418272314925415,-1.1655607452072225,1.0429638516126933,-1.030777615578159,3.5224571599758736,-0.11354970038677359,-0.17098407782600855,3.5700153279048985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9083333333333333,0.0,1.0,0.0,1.0,-0.006084067365255005,-0.030570447219058355,0.003085149679882047,0.9931282291627078,-0.07467907525557957,-0.07533385609342001,-0.049438510143830015,0.6972422912474475,0.1432618702370117,-0.24479612618578828,0.6063605712642297,-0.522639988301137,1.0758178905938747,0.14397721985626968,0.42924233899435954,-0.9260349153702182,0.390577225287786,0.4769185567530209,-0.2902246340142661,-0.10310575003062764,0.35238624681525643,0.6095708031497024,0.30694876921748915,-0.865619279590651,0.953270993574962,-1.717719487517555,-3.896451909530391,4.501389774248081,-1.2394193534429943,2.3481241944200293,-1.1764457546390272,1.0964616283067097,-1.2890341329247745,3.7696103352523225,-0.10758870928122222,-0.08106323264702286,3.4340575635264203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9166666666666666,0.0,1.0,0.0,1.0,8.087152406843767e-05,-0.030192565148493476,0.0018308788738890637,0.993370485849772,-0.07255956749373589,-0.07721181319320858,-0.04459285717643553,0.7036463899717817,0.1424641705819758,-0.24884571711715994,0.6321380512902981,-0.48283705985053804,1.0951953285109914,0.1293879726143694,0.396718160405766,-0.887912881136993,0.3801867686686181,0.49650651267197043,-0.30009378354180793,-0.0937456274836085,0.3406028942178055,0.6418846383447385,0.3060777084334216,-0.8659105572730466,0.9812779219728364,-1.7810512119942632,-3.9103647462061377,4.641393639831673,-1.2529598688099708,2.3523351895232616,-1.1971424618885107,1.1493589730975649,-1.5312556807777578,3.956484971202021,-0.10137938645276567,0.013262899597556999,3.2783490784117553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9249999999999999,0.0,1.0,0.0,1.0,0.006303241554559712,-0.029764511783472735,0.0005797866643264087,0.9936064848195805,-0.07033132882143883,-0.07890310139616517,-0.03967314079813901,0.71087018393246,0.14092276029910217,-0.2514902070846202,0.6567350917142064,-0.43416487503844203,1.1134858830072738,0.11429303298969863,0.36406959322425725,-0.848678354706357,0.3696945608076198,0.5161241432450753,-0.31017700837907464,-0.08394976714566822,0.3268653188022938,0.6755122193364027,0.3052591127766097,-0.865398231264025,1.0079101448818246,-1.8393437382610298,-3.9253692053616906,4.767010645068281,-1.2638906219410806,2.355641613426509,-1.2275257715895938,1.2002855965665205,-1.7589102377104282,4.087187743237273,-0.09504631904902583,0.11168571142159855,3.1049424364790545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9333333333333333,0.0,1.0,0.0,1.0,0.012588953081119146,-0.029289117425780154,-0.0006567018195047448,0.9938378012192128,-0.06799866391212939,-0.08037084243209366,-0.034686225806842,0.719345254517785,0.1386016689942999,-0.2527892668996859,0.6800642336415093,-0.37674990316097257,1.130737621250255,0.09873224364335224,0.3312953403164045,-0.8084627037191883,0.3591219249696001,0.5357672062290789,-0.3205525464016345,-0.07374086754083316,0.31128772358929835,0.7100044340653597,0.3044936031159378,-0.8640491287493532,1.0330269625808206,-1.8930737607231483,-3.939839232242869,4.87557116516474,-1.272265713787979,2.358441712488719,-1.2666701248956647,1.247699181515801,-1.9739960038163784,4.166625615201864,-0.08866134411646076,0.21396507299932477,2.915040489591285,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9416666666666667,0.0,1.0,0.0,1.0,0.01894628959159459,-0.02876988615081187,-0.001867492639515091,0.9940661246197368,-0.0655666574559746,-0.08157879133721137,-0.02963872665216384,0.7292850944118305,0.13542950981585314,-0.25275436130261586,0.7020213853532599,-0.310759460167299,1.1469488044722198,0.08274180364431283,0.29840560602020944,-0.7674188352869447,0.3484901322444868,0.5554315051198873,-0.3312881771273357,-0.06315478078707154,0.29396538540535416,0.7449559795897671,0.30378142370800204,-0.8618321467140363,1.0564941530416794,-1.9426411782099502,-3.952506079833291,4.964522889520729,-1.278045870240685,2.3604982563098775,-1.3131150072661624,1.2899949534525437,-2.178750624353857,4.199966420845714,-0.08225620003894485,0.31984851818399385,2.7091418304285764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.95,0.0,1.0,0.0,1.0,0.025384580836062355,-0.0282110328136869,-0.0030416887954573552,0.9942931572437359,-0.0630412381293057,-0.08249148477376843,-0.02453721038132993,0.7407340512990042,0.13131391321736716,-0.25134584587616715,0.7224906328630695,-0.23639286163936185,1.1620792968326612,0.06635489067318641,0.26542023898584965,-0.7257206555605095,0.3378211604655887,0.5751088438342435,-0.3424377965227372,-0.05224095164995743,0.27497521318340074,0.7800038744127883,0.30312266644862207,-0.8587183201129533,1.0781793264212969,-1.988399953548419,-3.9623288949623796,5.031397885705049,-1.2811287016554551,2.3611157824712437,-1.3650765831242484,1.3255493682446513,-2.3753314268958627,4.192135772717154,-0.07585723388861543,0.42903100942368155,2.487219901692348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9583333333333334,0.0,1.0,0.0,1.0,0.03191274987887226,-0.027617459004235123,-0.004168408051700867,0.9945205152894812,-0.060429177376594215,-0.0830743845723443,-0.01938829074353108,0.7535773000294022,0.12615520524270873,-0.24846599467760358,0.7413550142716607,-0.15387895459772746,1.176063892922033,0.04960180441850585,0.23236679110416977,-0.6835622038585272,0.3271379872168959,0.5947834348277413,-0.35403945351273985,-0.041062291316327354,0.2543765282904231,0.814824909135053,0.3025171364765251,-0.8546816298903083,1.0979478180698852,-2.0306941937443503,-3.9684636721186446,5.0738365651810495,-1.2813880283411005,2.3592335285960275,-1.4206143349916478,1.3527747254126452,-2.5657237846135357,4.147639030596995,-0.06952406539411315,0.5410971945937537,2.248819258086443,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9666666666666667,0.0,1.0,0.0,1.0,0.038538163076381395,-0.026994715832540022,-0.005236574488209873,0.9947496277929214,-0.05773806584318861,-0.0832939981384343,-0.014198719406215674,0.7675696863564209,0.11985891947341662,-0.24395873429508233,0.7585032890837917,-0.06347317854081094,1.1888142338707781,0.0325099874441139,0.19927917778387225,-0.641156712807492,0.31646469332657035,0.6144294026441773,-0.36611470210593133,-0.029694706226413344,0.23221315010650848,0.8491311915894049,0.30196393202538685,-0.8497000335363908,1.1156596473894043,-2.0698747498011403,-3.9702065304499548,5.089604526158132,-1.2786994458724033,2.3535390539451284,-1.477771365192817,1.370162740809929,-2.75162802020143,4.070400505804832,-0.06338438895201137,0.6554982637534645,1.993167049843585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.975,0.0,1.0,0.0,1.0,0.045265674276622724,-0.026348939384732553,-0.006234685759716884,0.9949816338752284,-0.054976251736433245,-0.08311799453609717,-0.008975465473142845,0.7823535386247144,0.11234739521257597,-0.23761011730393095,0.7738384671050985,0.03454286615080433,1.2002223488606378,0.015103891921820175,0.1661966822633372,-0.5987354617558917,0.3058263297856892,0.6340090857268268,-0.37866897626595347,-0.01822624563616187,0.20851606128706596,0.8826649175651335,0.3014607299939916,-0.8437566588277505,1.1311672689006116,-2.106316967997343,-3.9669768194280457,5.076640648418995,-1.2729679770714941,2.3425535814691867,-1.5346906168350005,1.3763347021111303,-2.9344181432798013,3.963710386558601,-0.05766594917148482,0.7715362156669903,1.7192549797180234,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9833333333333333,0.0,1.0,0.0,1.0,0.05209678900452586,-0.025686759283697826,-0.007150561734191715,0.9952172788879072,-0.05215274537878864,-0.08251531703096603,-0.003725776146358522,0.7974684812107145,0.10357013271195215,-0.2291503599299572,0.7872853534800343,0.13986247069752636,1.2101664772431648,-0.0025952953558418127,0.13316289746007148,-0.5565460353338421,0.2952485603753788,0.6534719623353304,-0.39169287905318134,-0.00675579452456117,0.18330618105184512,0.9151930313653815,0.30100283287252877,-0.8368410966086076,1.1443138970513713,-2.1404378980929066,-3.958349044348414,5.033155838825623,-1.2641541438326054,2.324700980000609,-1.5897243037426345,1.3700987288488506,-3.1151467060660503,3.8302319285350883,-0.05272077672820674,0.8883560495483334,1.4258977326034517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9916666666666667,0.0,1.0,0.0,1.0,0.05902889351977678,-0.02501518394065674,-0.007971081395917751,0.9954568103607868,-0.049277096480320484,-0.08145628436266854,0.001542791907923639,0.8123559833197973,0.09351303197947866,-0.21825825658802828,0.7987965237167303,0.2521577459236236,1.2185198800861772,-0.02057007304639493,0.10022419819086363,-0.5148495311087979,0.28475709405514577,0.6727541020601703,-0.4051643813283307,0.004608733177985644,0.15659694951929845,0.9465021163740517,0.3005820503818548,-0.8289507246686116,1.1549322311106691,-2.1727147124884416,-3.944130765339994,4.957785536691548,-1.2522978488481573,2.298370169287496,-1.641548006446637,1.350509781898464,-3.2945755126665217,3.672033863106914,-0.049039316751952056,1.0049477786928174,1.1117728794335768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0,0.0,1.0,0.0,1.0,0.0660545237036664,-0.02434146856061629,-0.008681919440969773,0.9956998749391608,-0.04635925367667411,-0.07991266325593072,0.006822382010768773,0.8264059269506673,0.08207026606451384,-0.20287784215722388,0.8085859440660905,0.3789045349641305,1.2257536181144824,-0.03880720723064917,0.06742738470440492,-0.4739162763889829,0.2743769295612428,0.6917781318234554,-0.4190520124939586,0.015752701840413226,0.12839658917406976,0.9763935957504968,0.3001855109266629,-0.8200919669637273,1.162843445041931,-2.2046109586436926,-3.928112302891735,4.839888951907052,-1.2378303320138628,2.2605044678265895,-1.7000433731371345,1.3176505289219709,-3.4787365347079096,3.474316961676802,-0.04953649178991437,1.1245864648518045,0.7537901136813785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0083333333333333,0.0,1.0,0.0,1.0,0.0731569115046376,-0.02367264703395766,-0.009239263867719132,0.9959505097288046,-0.04340868318357955,-0.07779258304116923,0.01210712266737598,0.838582976836447,0.06918816092780775,-0.18136672821301744,0.8166247228492804,0.5253295555131919,1.2324351630130406,-0.05731358902378981,0.034755659809334725,-0.4341847152436804,0.2641265885215814,0.7104291765239468,-0.43349843754728296,0.02656957532668516,0.09861800727416663,1.004407399068665,0.29975644218535624,-0.8102076169210816,1.1674953996720254,-2.2379224586340625,-3.913671966531201,4.671359333736598,-1.221165001583172,2.2086473211550883,-1.7735612296070757,1.27138242754062,-3.6728574343061324,3.2278842751874315,-0.056447925643636765,1.247951028452905,0.33511247704964386,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0166666666666666,0.0,1.0,0.0,1.0,0.08030919898468569,-0.02301723929494059,-0.00960757820035807,0.9962096815305966,-0.04043694320404731,-0.07502422731153927,0.017392221411848822,0.8475447443611691,0.05518010193899841,-0.15603963760474593,0.8224198360289897,0.6783686119098135,1.237727509745546,-0.0761059148745502,0.0021995185955515596,-0.39606028749337296,0.2540241795348566,0.7285889205093735,-0.4486113663207432,0.036942408966090225,0.06718229860230089,1.0301916670036206,0.2992447121659356,-0.7992927831561789,1.1684286529927583,-2.2725353943714137,-3.896851153416114,4.469143505728728,-1.202161646292229,2.1438059061079384,-1.8460256767670424,1.2101988785869824,-3.868971086424469,2.9609781961940262,-0.0667533879922011,1.3652164714991821,-0.11070269937576871,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.025,0.0,1.0,0.0,1.0,0.08748120939204243,-0.02238408231012895,-0.009786994893425164,0.9964702785973808,-0.03745662122775859,-0.0716244928798285,0.02266974676289496,0.8525509089209994,0.040514429667501246,-0.12929348374021463,0.8258309565103238,0.8246052772751437,1.2403307757928108,-0.09518917892998004,-0.030191859414267167,-0.3596989901482016,0.24409056108337757,0.7461592749590791,-0.464265532160067,0.0467395566364682,0.03413515583375881,1.0537570356718988,0.29864388571881956,-0.7874540090627619,1.1656503546824293,-2.307525328892684,-3.8742502055873476,4.255003609015914,-1.1809295870951881,2.066999468204631,-1.8993486082677236,1.133525265781375,-4.056240772744521,2.69871694051659,-0.07773657515557697,1.4689859145832118,-0.5495468679128468,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0333333333333332,0.0,1.0,0.0,1.0,0.09464236006342915,-0.021780245582166947,-0.00978277682910573,0.9967230881655029,-0.03447854365225854,-0.06763347810584837,0.027928984677555373,0.8534855364777798,0.02556877737825753,-0.10153724240918062,0.8270940905627859,0.9604696421499058,1.2395894836644283,-0.11456467035609494,-0.06237131816423756,-0.32514356067644107,0.23434201974993682,0.7630389116461174,-0.4802671764585386,0.05583449672911314,-0.00042171427677445986,1.0751702826788971,0.29794910258000934,-0.774809684579792,1.1592695385275442,-2.342559460913364,-3.846375041732092,4.039036974835981,-1.157973880906766,1.9784636975263248,-1.9292908161122924,1.0427627137198603,-4.229224365400616,2.4439570558859725,-0.0895619417184279,1.5591403935759929,-0.9740600320045933,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0416666666666667,0.0,1.0,0.0,1.0,0.10176332205892308,-0.021211229615777677,-0.009600237080995735,0.9969584822025213,-0.03151189077752394,-0.06309805513748115,0.033157517133043886,0.8504116954263841,0.01065713617465408,-0.07292830614184774,0.826447225313266,1.084918676747848,1.235244174056257,-0.13423183661186944,-0.09429811010980203,-0.2923817072342686,0.22479099640159814,0.7791336699178512,-0.49642037909527187,0.06411893519846587,-0.036351916922918115,1.0944896532699984,0.2971511866901791,-0.7614683358364953,1.149416020815686,-2.377521745921295,-3.8138380364958655,3.8262075666770747,-1.1337334753654178,1.8794999418994052,-1.9371365145817687,0.9404993165350883,-4.384520085480716,2.195227574671672,-0.10267116263466103,1.6370491260258202,-1.382764246774646,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.05,0.0,1.0,0.0,1.0,0.10881628762336107,-0.020681231836569215,-0.009244474241701092,0.9971670522024589,-0.028564475837471667,-0.05806719619511864,0.03834242361650485,0.8434485538724571,-0.003944584215818642,-0.0436629241783147,0.8241178477249097,1.1976113003228221,1.2273026244885625,-0.15419003278811652,-0.12593528543916865,-0.2613734345651565,0.21544646182717986,0.7943639106777741,-0.5125527850349014,0.07150948533803128,-0.07349704903478639,1.111757408923425,0.2962379165360983,-0.7475255324793617,1.1362234677479668,-2.4124573985915716,-3.7769200446816784,3.6191407399928144,-1.1086284345465558,1.772003054957485,-1.9260307972834678,0.829807227098969,-4.519860297228461,1.950770857623465,-0.11732050054784837,1.7043248990588822,-1.7753251937028836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0583333333333333,0.0,1.0,0.0,1.0,0.115775343550229,-0.02019331291106959,-0.008720680495105017,0.9973399267925509,-0.02564281318156489,-0.05259074034216123,0.04347103160861119,0.8327710575740171,-0.017990742649972552,-0.01400195824268928,0.8203387221408688,1.2983835627877125,1.2159254709644423,-0.17443945992172896,-0.15724677752116334,-0.23206269490105502,0.2063138558258222,0.8086670541671426,-0.5285208923833297,0.07794905565011535,-0.1116829218767258,1.1270025008970561,0.2951958450143816,-0.7330629208521806,1.1198272675873047,-2.447488453678638,-3.735536601585514,3.419317450025736,-1.0830889692631873,1.658035659494801,-1.8993340140592885,0.7137511238049247,-4.633599479823119,1.7092764384559178,-0.13356284351124348,1.7626576792986004,-2.1514711318747226,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0666666666666667,0.0,1.0,0.0,1.0,0.12261676449148536,-0.019749480336349753,-0.008034493242789995,0.9974689821890151,-0.022752129861575876,-0.04671911072200206,0.04853138008677347,0.8186034695510398,-0.03126210619903078,0.0157397998705585,0.8153503724509973,1.38710334136598,1.201361829308193,-0.19498150701609382,-0.18819422879892722,-0.2043848103980609,0.19739497900612674,0.8219978383360208,-0.5442083519358896,0.08340533740144669,-0.15072370703183838,1.140245349564357,0.29401186914424426,-0.7181479044910517,1.1003656155500547,-2.4827536200356994,-3.6892119347592125,3.227392637237884,-1.0575579681633862,1.5396316726365944,-1.860061647609026,0.5951119816668937,-4.724543888180473,1.4700178157591326,-0.15129042458020825,1.8137465489179783,-2.510765329043223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.075,0.0,1.0,0.0,1.0,0.12931921659663206,-0.019350718655662586,-0.007192297443370705,0.9975470076255858,-0.019896333170252863,-0.04050329982879597,0.05351248648931366,0.8012105887731756,-0.04356338672625376,0.04520933851854392,0.8094036816502224,1.4636312963964384,1.1839094443150577,-0.21581868692232395,-0.21873364310048354,-0.17827281761375696,0.18868788968976577,0.8343275820444191,-0.5595219198434801,0.08786758867789692,-0.190425320013067,1.151502797826375,0.2926743379380448,-0.7028338117035476,1.0779811787699176,-2.5183674542260395,-3.6370641701706097,3.043263047099199,-1.0324904201491487,1.4187098972707113,-1.8107123933007307,0.47623432656315995,-4.79189992691278,1.2328514365365795,-0.17028994333451952,1.8592338913134254,-2.8525705962801773,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0833333333333333,0.0,1.0,0.0,1.0,0.13586383613445913,-0.018996984557754813,-0.006201470899816412,0.9975678449005762,-0.017077952207592093,-0.0339949110507939,0.05840448953019487,0.7808846598915128,-0.054720720724744376,0.07403046309351582,0.8027606181669584,1.5278161077754764,1.1638918933982991,-0.23695429791986114,-0.24881196496843738,-0.15366375961307424,0.18018680533697426,0.8456430032905327,-0.5743868918242351,0.09134257617749936,-0.23058870581371804,1.1607928735066333,0.2911737034220023,-0.6871606729691613,1.0528227722787185,-2.55439353282614,-3.5778056229620403,2.8660582009026516,-1.0083531499483467,1.297036513055383,-1.7532560117713958,0.35896253065358735,-4.835283151350803,0.9981869372538066,-0.19029316110806827,1.900626359112254,-3.176051478773534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0916666666666666,0.0,1.0,0.0,1.0,0.1422341582520169,-0.018687182482268885,-0.005070576102039826,0.997526507042176,-0.014298072420433195,-0.027246177195089705,0.063198723960891,0.7579294402832918,-0.06457897115018159,0.10181678964018054,0.7956923544248575,1.5795037872407836,1.1416482816991556,-0.2583919124694263,-0.27836373681651755,-0.1305051809320461,0.17188200385729333,0.8559448572620089,-0.5887428533730034,0.09385029752212337,-0.2710133725355804,1.168139246780605,0.28950278525291034,-0.6711567057183434,1.0250469874570254,-2.5908291971110438,-3.509759228304136,2.694112777616819,-0.9856245291512006,1.1762131758944072,-1.6891981169117232,0.2446400669707932,-4.854756039904234,0.76694215385261,-0.21101747623487932,1.9392082243355402,-3.4801756451398025,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1,0.0,1.0,0.0,1.0,0.14841589058788313,-0.01841913555811767,-0.003809504662455874,0.9974192750889448,-0.011556281545119217,-0.02030991619440405,0.06788777028649902,0.732643653104058,-0.0729991420082958,0.12818197139209214,0.7884745737997876,1.6185550621664413,1.1175319588481676,-0.28013478453837853,-0.30730795210683964,-0.10876187998612726,0.16375972985112092,0.8652465562221061,-0.6025401937727638,0.09541991062701258,-0.3115013064787886,1.1735752427375101,0.2876567454847543,-0.6548405358969023,0.9948198448597217,-2.627601163236275,-3.4308844421948606,2.5249316279681855,-0.964792852447634,1.0576821038979078,-1.6196872734685241,0.1341502202600156,-4.850871412010543,0.5404777523772664,-0.23219440081412746,1.9759550199352294,-3.76370499710863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1083333333333334,0.0,1.0,0.0,1.0,0.15439654699938554,-0.018189565754289563,-0.0024295822793543183,0.9972437687334706,-0.008850643890605223,-0.013239397903405661,0.07246551031205421,0.7053060884900344,-0.07985635913194244,0.15274679873429056,0.7813800779995623,1.6448685721585352,1.0919150760877514,-0.30218526519003086,-0.3355451441864319,-0.08842298713257635,0.1558021229831661,0.873572892326974,-0.6157376412641454,0.09608613452645696,-0.35186122940242276,1.1771472093202262,0.2856328785726749,-0.6382241220527562,0.9623185708385482,-2.6645717822097392,-3.338802661304534,2.355142430431142,-0.9463519699042577,0.9427440531352338,-1.5456449632071245,0.027980941847613183,-4.824702528029482,0.32050594793557874,-0.25358561025310866,2.0114543138849905,-4.025175061043864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1166666666666667,0.0,1.0,0.0,1.0,0.1601649750701129,-0.01799409565282213,-0.0009436434021239085,0.9969989847462986,-0.006177717710592597,-0.006088103606973214,0.0769272073737503,0.6761644322749368,-0.08503893486585964,0.1751433006717346,0.7746690510240417,1.6584081466514764,1.06519584684809,-0.3245443142418742,-0.3629546631285819,-0.06950950614560822,0.1479871970193833,0.8809589571076933,-0.6283009431595492,0.09588625965780613,-0.39191301527927996,1.1789170085364364,0.2834303186472025,-0.6213162973321524,0.927733593842324,-2.7015552597424044,-3.2308133534520103,2.180430585501253,-0.9307929485542621,0.8325855819722805,-1.4679025879559537,-0.07369928041801338,-4.777844466082269,0.10897189940950014,-0.2749874768126559,2.045838964748521,-4.262863554018224,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.125,0.0,1.0,0.0,1.0,0.1657108271338704,-0.017827282208340806,0.0006339157259062488,0.9966852965227521,-0.0035326273773098,0.0010906314955561923,0.08126961786191501,0.6454297814807168,-0.08844902737282988,0.1950166097909039,0.7685776775325437,1.6592315744696107,1.0378052527779784,-0.3472111861857376,-0.38939203341063205,-0.05208247737422213,0.1402889071739284,0.8874493186931787,-0.6402026843967447,0.09485781318615674,-0.4314919705037939,1.1789634076437179,0.2810497539591306,-0.6041268059736142,0.8912708449382445,-2.7383415504637334,-3.1038985519962172,1.9954645783439302,-0.9185909304572393,0.7283106629004577,-1.3873277750817303,-0.17096409651840505,-4.7123747533044895,-0.09208871130627738,-0.2962261208630046,2.0787373490000816,-4.474749248932164,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1333333333333333,0.0,1.0,0.0,1.0,0.17102404009268157,-0.017682689893984777,0.0022871008877737168,0.9963044090828721,-0.0009091970617572353,0.008244088605113078,0.08549112722664455,0.6132789257806937,-0.09000530748318049,0.21202621351746234,0.763306487999273,1.6475161777160479,1.0102094757108704,-0.3701833400829364,-0.41468630566185216,-0.036251763173209384,0.1326773481784293,0.8930974681560343,-0.6514230727442447,0.09303685804916605,-0.47045259450102145,1.1773821966813318,0.27849321663281906,-0.5866706748488177,0.8531544396934546,-2.7747222111536387,-2.954728090612815,1.7938535884056463,-0.9101871304932091,0.6309687609530745,-1.3049150987740266,-0.2640578761510992,-4.6307636557729035,-0.2807076066874803,-0.31714644642638734,2.109245561506623,-4.658461117032385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1416666666666666,0.0,1.0,0.0,1.0,0.17609440732721454,-0.01755300579933091,0.00399830591135847,0.9958592670980946,0.0016998568305486928,0.015320719470870433,0.0895918869496619,0.5798668590130405,-0.08964780063170608,0.22584941143812992,0.7590110334758962,1.6235728358551083,0.9829033669265499,-0.39345655637163157,-0.4386375015875123,-0.022184917567461354,0.12511912166570824,0.8979654647090632,-0.6619512693763118,0.09045684858363842,-0.5086713647666756,1.1742849475322599,0.27576397985202417,-0.5689727132818372,0.8136298263210381,-2.8105061709734924,-2.7797047464694358,1.5682406986674042,-0.9059673298598179,0.541566563228526,-1.221802851718925,-0.3533372137554444,-4.535725385469994,-0.4551440555434372,-0.33760078890525125,2.135928710579378,-4.811214960615218,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.15,1.0,1.0,0.0,1.0,0.18091134897856048,-0.017430190968073807,0.0057483458958830546,0.9953539200985615,0.004302694586251505,0.022270713178629418,0.09357390624156661,0.5453522602584115,-0.08734459753571167,0.23619118203884307,0.7557991667802892,1.5878352739570076,0.9563891324644593,-0.4170251095991613,-0.4610147181030094,-0.010114418195419311,0.11757789268076567,0.9021235775431764,-0.6717864536062268,0.0871479044865753,-0.546048017592188,1.1697964624222745,0.27286653681773154,-0.5510718630058281,0.772967523683201,-2.8455039453838795,-2.575125787012349,1.3107192193839585,-0.906240298813446,0.4610443704019018,-1.1391606082858319,-0.43923336445442135,-4.430002308568368,-0.6140277940193917,-0.3574455160264045,2.1568608027599745,-4.929729981663553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1583333333333332,1.0,1.0,0.0,1.0,0.18546401174397215,-0.01730564926787067,0.007516592312114953,0.9947933598571623,0.006908130386450185,0.029046442778431776,0.09744102375437877,0.5099375797857963,-0.08309940454917453,0.24280517032584636,0.7537401012396973,1.5408088675261722,0.9311349163900936,-0.44088162212802956,-0.4815562647043848,-0.00033959724439538004,0.11001511668548414,0.9056495375490949,-0.680937279514409,0.08313629250939807,-0.5825047365761484,1.16405115096527,0.2698065545849174,-0.5330250332358376,0.7314676599599789,-2.8794504044833094,-2.3375630745237532,1.0138105458315563,-0.9112213842566463,0.3901959656421905,-1.0578887757143551,-0.5222430232936814,-4.316082023354293,-0.7564576060686878,-0.37655506313790776,2.1697103358653957,-5.01011222779767,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1666666666666667,1.0,1.0,0.0,1.0,0.189741836642309,-0.017170379613635052,0.00928129184559655,0.9941833586649269,0.009525492144192698,0.0356025988153688,0.10119866272669352,0.3468760376049585,-0.03935560614079982,0.2593783518254348,0.7801354274494419,1.425880230795583,0.9691130846467038,-0.4650159496738831,-0.4999741026784053,0.006782424235106626,0.10239086960982156,0.9086268436372129,-0.689417933201466,0.07844385409834728,-0.6179827179814262,1.157188835654463,0.2665906190987664,-0.5149100240747382,0.6894656532199065,-2.8843441101007627,-1.2788472567149223,-0.13457236168204398,-1.0553467838510546,0.23275329941757184,-1.108256150979312,-0.6598812685181785,-4.5107130055287685,-0.7528185496596373,-0.4481451156025218,1.9540925520517805,-4.954572715447581,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.175,1.0,1.0,0.0,1.0,0.19155811190865044,-0.016831521012811636,0.011412555418158435,0.9934934281395771,0.012461784330493218,0.0414407545562836,0.10534788132532563,0.19107939920109548,0.0005613507404039139,0.2566707039567299,0.7835665586997546,1.333811183695132,0.9970294960188353,-0.4889540239630423,-0.5028703856496335,-0.002582469939096113,0.0924260036212999,0.9095287592060545,-0.6994082153640642,0.07213827136742842,-0.6576832866682946,1.1515041751376094,0.2623374693248754,-0.5004568240349746,0.6488914480358525,-2.8476865133186426,-0.22307370377657398,-1.384309753613145,-1.1758387243445658,0.22882315836180833,-1.5051986383549654,-0.7697698733462297,-4.698813335496295,-0.7604444361110296,-0.4889110112718398,1.7068157897988123,-4.851029457562195,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1833333333333333,1.0,1.0,0.0,1.0,0.19320639796041164,-0.01655989116864884,0.013289558637049477,0.9927675666073249,0.015185258779782607,0.04722928431335305,0.10932228217272563,0.18183994956649915,-0.00495305927980836,0.23265684431637937,0.7451460030372403,1.3090451016767062,0.9555652470907555,-0.5124773915625271,-0.5036919977413482,-0.016289404991779124,0.08279355753741213,0.912440562943243,-0.7145045771740488,0.06561435620924345,-0.6962962735730311,1.1445147617192792,0.25844210224423575,-0.486463094244758,0.6086151622605366,-2.7881485981560163,-0.0322986924273283,-1.7100863886051036,-1.1483481140915788,0.44340965556117773,-2.0034432223816023,-0.8026543328139135,-4.511853975687634,-0.9327789363038752,-0.45490949007461867,1.6883058833566045,-4.805460751262814,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1916666666666667,1.0,1.0,0.0,1.0,0.19489711568426282,-0.01632673901861038,0.014993601331134268,0.9920153661904679,0.01780971533093019,0.05282853624358683,0.11312591701142674,0.18831523468273978,-0.0110614995247399,0.2159837477076425,0.7204980510196721,1.2527057013226235,0.9170120419360734,-0.5354231672656425,-0.503408697190089,-0.031083909749181175,0.07328686838644025,0.9169189201320741,-0.7327989357370909,0.0587606991538632,-0.7328808529297551,1.1359578595325448,0.2547556444902984,-0.47231839264569786,0.5688004355148056,-2.7084966382440445,0.08498093329104561,-1.7677469795462215,-1.138133850971905,0.6141919830611742,-2.3240652075668566,-0.8408057153211661,-4.255663328297768,-1.1049619938118216,-0.4297622308900084,1.7094181587207613,-4.720154525447964,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2,1.0,1.0,0.0,1.0,0.19667997103242058,-0.01611323736393527,0.01654187445431839,0.9912470781342987,0.020364502740680145,0.05812844700639225,0.1167715753671451,0.19940195282082757,-0.01652681604150391,0.20054860021702595,0.6983651021064723,1.1730393039666136,0.8816592747199328,-0.5576190021999279,-0.5022756488531641,-0.045751854650882814,0.06382466002121372,0.9226770959942626,-0.7532389973001631,0.05160092762055735,-0.7672239957113273,1.1260987284890822,0.25127939839606894,-0.45797279159941195,0.5299459201697372,-2.609327179848413,0.18455804001319187,-1.7222074140989263,-1.1355067594316584,0.7583308120485177,-2.5430388199378773,-0.8754844572131035,-3.985329003320295,-1.240583421387198,-0.4033022022309951,1.725379327120381,-4.5681199367085945,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2083333333333333,1.0,1.0,0.0,1.0,0.1985715856684376,-0.015906790212821587,0.017928681468954294,0.9904733362758594,0.022864722399365357,0.06304850351283335,0.12026911837586032,0.21293741179984885,-0.02144640035174395,0.18440803661655975,0.6770615809347327,1.0754388842216398,0.8489362128592189,-0.5789119535964494,-0.5003327298565358,-0.05978736665082995,0.05436175572924594,0.9295577669995494,-0.7751829160693888,0.04416929153364481,-0.7993030029850934,1.1152814691760915,0.24803394111978183,-0.44356207052702484,0.49266510323632906,-2.492145786618183,0.28531488278129125,-1.6336672284461207,-1.1375434130369713,0.8866425101549291,-2.6939542147087847,-0.9061227101061107,-3.7157128525475613,-1.334796462713408,-0.37419276481891584,1.720325139143719,-4.337988508852505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2166666666666666,1.0,1.0,0.0,1.0,0.20058293880696423,-0.015696801681851908,0.019142351939622316,0.9897049373022797,0.025322042842749245,0.06752218593743502,0.12362720434826643,0.2287072234851626,-0.025988494894041585,0.1670707299210774,0.6561941124743945,0.962430015854565,0.818664752628922,-0.5991547653102309,-0.49752040080680926,-0.07297964179165149,0.0448656031372642,0.9374544711635114,-0.7981382342119762,0.036498882452122176,-0.8291525432537866,1.103852120777192,0.24504285231575368,-0.42930070594701664,0.4576461116888621,-2.3573239676467628,0.3962320856672241,-1.5280120558527763,-1.143059303721536,1.0037250089184369,-2.7897130114483226,-0.932847807555622,-3.451556129296167,-1.387822727405723,-0.34213546223544944,1.6864018759957156,-4.0206271483368665,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.225,1.0,0.0,0.0,1.0,0.20272620631255128,-0.015473402693362268,0.020169695249890412,0.9889526467899213,0.02774701560765341,0.07148980526527875,0.12685414179165577,0.24691994371458326,-0.03031867977224395,0.14841498486493615,0.635606934003801,0.8353197802260854,0.7908150024557441,-0.6182006863905621,-0.493728861762082,-0.08525423424837622,0.03531076733388701,0.94628651714819,-0.8216781329268609,0.02862182807438444,-0.8568289384733628,1.0921510903859961,0.24233168341585767,-0.4154553725937629,0.42565465076404796,-2.205000240818309,0.5217350899929085,-1.4173969581104429,-1.1513078047190934,1.1122404466333013,-2.8368316337709487,-0.9557464744466088,-3.1949294381983995,-1.4001438140982359,-0.3068779706344038,1.6178174164052617,-3.6066944077596297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2333333333333334,1.0,0.0,0.0,1.0,0.20501571698726728,-0.015227073881411859,0.02099700741162653,0.9882269657724048,0.030149743683604225,0.07489571287968845,0.12995802890460595,0.2677872298785399,-0.034576825941488025,0.12836203964749396,0.6152176697946978,0.6948648061523248,0.7653589747672727,-0.6359047693238694,-0.4888248159735941,-0.09660292442682554,0.025677139725279307,0.9559918119407331,-0.845418761441492,0.020569774544678697,-0.88240136722376,1.0805163905422215,0.23992821947184695,-0.4023370823402623,0.3975345382262016,-2.035570133017226,0.6636744837961117,-1.3074841433209003,-1.1617024688310618,1.2142898663181345,-2.840070884355752,-0.9748779878624342,-2.9473129052017577,-1.3716094766398657,-0.2681312948639847,1.5097138904216345,-3.0873030095876675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2416666666666667,1.0,0.0,0.0,1.0,0.20746736975038016,-0.014948471772613912,0.021609921989748468,0.9875379311799705,0.03254022051143966,0.07768654164344514,0.13294649217572097,0.2915132243566788,-0.038782519511411505,0.10660355360726415,0.5949140154819765,0.5405147909816417,0.7418258291818144,-0.6521268552741826,-0.48266762036548017,-0.10704563663705789,0.015949059520035978,0.9665246815868256,-0.8690126476661234,0.01237386161001054,-0.9059508202267255,1.0692909324419984,0.23786282850145793,-0.390293474420069,0.3741996006042535,-1.848683671247604,0.8231911624191401,-1.2000102141560653,-1.173683916543228,1.3120033327727332,-2.8024997905705207,-0.9906204371651605,-2.710697860610094,-1.2983380448209125,-0.2256567018035649,1.3570956399451573,-2.450768111997973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.25,1.0,0.0,0.0,1.0,0.21009832304744527,-0.014626399406303114,0.02199018725985791,0.9868959997601483,0.034928780431368066,0.07980221909923964,0.13582294277462462,0.3161962971687142,-0.04224759878207379,0.0874296977616979,0.5778418128394559,0.3947689086374626,0.7172569909246044,-0.6667161638446628,-0.47510496326660845,-0.11660309466275996,0.006115741116225508,0.977858534153612,-0.892127091284334,0.004059433925259356,-0.9275796649005948,1.0588774231285396,0.23616727444178753,-0.37971882167450965,0.3566884030262354,-1.6629893068058665,0.9814321013665861,-1.1127110090085226,-1.1905034415765654,1.3975106902718903,-2.7558736212928903,-1.0119738281045367,-2.4815512715516808,-1.241302788967622,-0.18950313048051726,1.1973119074546323,-1.813732554091061,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2583333333333333,1.0,0.0,0.0,1.0,0.21290393676344382,-0.014251595909656193,0.022201079356346808,0.9862968241518028,0.03732397739394343,0.08137885708212958,0.13857480651483392,0.3379398788307807,-0.044410013741333805,0.07731438861800558,0.5669906648041586,0.2926526283071801,0.6889842519863756,-0.679843343720947,-0.46631041867603706,-0.12559082012053327,-0.0038926645062401116,0.9898165264246904,-0.9149438746876716,-0.004492368858398405,-0.9473100080859201,1.0486025526258713,0.2347044429934493,-0.3703382759624918,0.3439707247027358,-1.5085532828595816,1.1072724898389674,-1.0701804274120705,-1.2153588902684913,1.4571509157288731,-2.748119538126881,-1.0470091989160335,-2.249537726580455,-1.2960959776786085,-0.17197457199890465,1.0970831114646062,-1.3771132062527836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2666666666666666,1.0,0.0,0.0,1.0,0.21585774920762807,-0.013828062983975318,0.02234103348128271,0.9857264108804058,0.03971890439973241,0.08264841720516733,0.14119168056303397,0.35583792361113886,-0.046229072778242786,0.0744732032624879,0.5584437852542625,0.22831103554271817,0.6592150013911714,-0.6918587185589892,-0.4566504217692923,-0.1344394351196278,-0.014140240388249346,1.0021443827490932,-0.9379290835864487,-0.01339071939000787,-0.9650719603436024,1.0372758235005628,0.23330103157513912,-0.36143410315009955,0.33373651625535566,-1.3827653651414518,1.2017114163116083,-1.0630885527711205,-1.2434026247422107,1.4932166596465257,-2.7752535718788285,-1.0853653800638448,-2.0112020865668856,-1.4446133014814677,-0.16544756392922466,1.058193431785892,-1.135884756314447,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.275,1.0,0.0,0.0,1.0,0.21894266263408632,-0.013367409552461747,0.022443307838903304,0.985179775554176,0.042097092152030724,0.08369347564730573,0.14368036332711645,0.37176744401463674,-0.04857785788339416,0.07409114915409465,0.5486519958768487,0.17784697617841583,0.6305863528096772,-0.7028894331399712,-0.4462818950708436,-0.1433089626667186,-0.024616041585276957,1.0147034707521325,-0.961198100885652,-0.022581791859462484,-0.9808300428620349,1.0245256642678469,0.2319469835946289,-0.35270171876606027,0.32503931209749504,-1.267938634378396,1.282546299149896,-1.068604267490021,-1.2704017533830156,1.515024719535325,-2.8070814590768944,-1.1171942636056205,-1.7712377525744127,-1.6204288750536389,-0.1588362371588764,1.045292874455196,-0.9740666092877748,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2833333333333332,1.0,0.0,0.0,1.0,0.22215332042032765,-0.012876328355669833,0.022520757482566413,0.9846554473724662,0.04445047717625596,0.0845444870909424,0.14604805627354817,0.3871028415554165,-0.05135524060364915,0.07466146692679318,0.5380234363167395,0.1323378848580974,0.6032562895436488,-0.7129910291319624,-0.43527465011679406,-0.15224950624446149,-0.03531360294463294,1.0273947947413486,-0.9847137745710636,-0.032010623783434874,-0.994592589553176,1.0102686755830022,0.23065376095582452,-0.34401255524251295,0.3175020727672261,-1.1580461093105754,1.3572992698788688,-1.077521494282217,-1.2970175903467747,1.5259829803950264,-2.830871263224961,-1.1429901292287987,-1.5334206363504688,-1.7991597239989687,-0.1508461602849165,1.0434810311612652,-0.8432678402237037,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2916666666666667,1.0,0.0,0.0,1.0,0.22548999205617754,-0.01235753671455436,0.022578491628354503,0.9841535460109694,0.04677613190841862,0.08521096868217723,0.1482999736145994,0.40249790172642114,-0.05440127270550392,0.07559999757736578,0.5269774715911801,0.08811060094560519,0.5769595847584863,-0.7221902016284808,-0.42366024057286245,-0.1612676542380889,-0.046233001424389866,1.040136520425383,-1.008379288606068,-0.04163162734660913,-1.006387053467876,0.994539668867864,0.22943288092321362,-0.33531036824670585,0.31098484809376664,-1.0506129627353133,1.4292295874804695,-1.0860914697299424,-1.3237872284424903,1.5276310031996365,-2.8418403177489515,-1.1636799449875619,-1.2995880880353061,-1.9706737381253325,-0.14159000039265124,1.0466353526962358,-0.723314138353307,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3,1.0,0.0,0.0,1.0,0.2289553766126769,-0.011811702481444062,0.02261849706631973,0.9836748902578167,0.04907352724757474,0.08569369829802133,0.15043965325614053,0.418231146084058,-0.05762536463691134,0.07665678043653344,0.5157203905595282,0.04361074533241713,0.5514480497789744,-0.730501245177551,-0.41145415699211957,-0.17035103073996052,-0.05737672341867445,1.0528553114613426,-1.0320777798668794,-0.05140528953322757,-1.016252391020431,0.9774241132809133,0.228293927615947,-0.3265686326975757,0.3054468371280043,-0.9445915509820213,1.4996312661766698,-1.0925198143708104,-1.3508426169922068,1.520765121684402,-2.83857537716512,-1.1798128279027567,-1.070949510224195,-2.130579931347123,-0.1312567881347798,1.0522768829162388,-0.6058381537205748,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3083333333333333,1.0,0.0,0.0,1.0,0.232553054035893,-0.011238593826234305,0.022641465192847546,0.983220571503084,0.05134312896877299,0.0859897131044311,0.15246953833830412,0.4343997893672155,-0.06098342911640983,0.07771177892280125,0.5043275867150614,-0.0018320982766028004,0.5265509991583378,-0.7379333941448478,-0.3986663861365846,-0.17947631781093573,-0.06874704504092664,1.0654826057867897,-1.0556888782254867,-0.06129517447832174,-1.0242362119716126,0.959030003345412,0.22724526778763396,-0.31777242019810187,0.30088754553175706,-0.8395835971818344,1.5688569169188904,-1.0956222664283544,-1.3780819189538975,1.5058491998948975,-2.821053839000287,-1.1916645608748218,-0.8484611493060745,-2.276891720267582,-0.1199521498875028,1.0594944110816618,-0.4875500689317136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3166666666666667,1.0,0.0,0.0,1.0,0.23628673861654462,-0.010637641585283021,0.022647556687429158,0.9827917470504032,0.053585754417489896,0.08609440673866518,0.15439139218705814,0.4510143748541542,-0.0644524260886097,0.07869759147479582,0.49281111118457854,-0.04851299547925328,0.5021581776527435,-0.7444943051305816,-0.38530654171013806,-0.18861140184709976,-0.0803447554012394,1.0779527981262575,-1.0790953438502175,-0.07126636554780794,-1.0303934101755323,0.9394759179431202,0.22629472511782195,-0.3089103925128813,0.2973210026458091,-0.7355019006463759,1.6368003941566722,-1.0943624773859695,-1.4052900805645598,1.483177096967534,-2.7897969599647077,-1.1993796304160618,-0.6329476210298957,-2.408640753038229,-0.10771863915628621,1.0680784053206216,-0.3674047223275312,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.325,1.0,0.0,0.0,1.0,0.24015991023711317,-0.010008195127504617,0.02263673785609798,0.9823895374912968,0.05580229136687093,0.08600242186851736,0.15620654384052576,0.4680431232876968,-0.06801665535318757,0.07956852384433953,0.4811552301665219,-0.09656557333376822,0.47819706745503254,-0.7501917591556208,-0.37138637956730675,-0.19771569243403522,-0.09216854638366931,1.090202224069582,-1.1021854942248985,-0.0812848349852561,-1.0347853389887776,0.9188859907947748,0.2254499571350292,-0.2999711134427582,0.2947641334929649,-0.632412983256716,1.7031301221161876,-1.0877168240889619,-1.4321955708658782,1.4529430630991857,-2.745511295654306,-1.2030555612400753,-0.4251494726149918,-2.525279913888656,-0.0945653741011171,1.0781475968181087,-0.24538061103704045,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3333333333333333,1.0,0.0,0.0,1.0,0.24417562231926265,-0.009349634801614522,0.022608936493110993,0.9820149726962943,0.057993579151410284,0.08570803568906495,0.1579160245061814,0.4872249490253193,-0.07220235299842123,0.08124753238969364,0.4671225216461533,-0.15896182884271245,0.4559362977436625,-0.7550345215181935,-0.35692103967486827,-0.2067400155819158,-0.10421468158233738,1.1021685158445773,-1.124853865444456,-0.09131729156847586,-1.0374792347191155,0.8973879193783093,0.22471863554947,-0.2909412658992462,0.29323132579519173,-0.5146497520191451,1.768314530432551,-1.0404485236208811,-1.4545157588131532,1.4112470518793785,-2.6581059176058464,-1.199215622349515,-0.2255034625195229,-2.602639896978698,-0.07529110918169213,1.0885042256800226,-0.08836108880179938,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3416666666666666,1.0,0.0,0.0,1.0,0.24837002988536727,-0.008661749276999637,0.022574020656872956,0.9816774745818011,0.06016038631239976,0.08509612770720139,0.15952652715674973,0.510862792812284,-0.07737987512819156,0.08442326119377719,0.449136633959367,-0.2515684659701528,0.4366889875397073,-0.7587692550226065,-0.34191447072676423,-0.2150565011610499,-0.11641047569722186,1.1137230082675715,-1.1464872595183293,-0.10127176202441468,-1.0385437300307696,0.8755086591784632,0.22419510531533432,-0.28182937634809113,0.29329144867960155,-0.3651547243685238,1.8326501426977926,-0.9095175380982418,-1.4683151830604042,1.3553149813283039,-2.4937427983250204,-1.185504518096796,-0.03682928850249123,-2.607024930776576,-0.04478704308191195,1.0951992600511584,0.14967991578219597,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.35,1.0,0.0,0.0,1.0,0.25278614809072303,-0.007938375252850372,0.02253898032518128,0.9813875819316292,0.062312703371548483,0.08402836846953249,0.16104277171386422,0.537728562541641,-0.08268039376672041,0.08757469919388956,0.43042175287485146,-0.36475188053847263,0.4189919899923441,-0.7611204335910022,-0.32637687062990506,-0.2218986412168865,-0.12868660130001078,1.1247570988667157,-1.1664162454165397,-0.11107570020342246,-1.038093056194157,0.8539375038653664,0.22397218483143813,-0.27268794489839354,0.29572599105822833,-0.19967125009821673,1.8940965101217955,-0.7192069121756839,-1.4779937772749094,1.291518142371939,-2.2816468182425753,-1.1675880845683373,0.1355944507943141,-2.548422562269288,-0.008700937986222401,1.0964166862236846,0.4504225899188452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3583333333333334,1.0,0.0,0.0,1.0,0.25743191591089293,-0.007169887830195094,0.022497574729113807,0.9811467118968303,0.06446419985646469,0.0824733507579365,0.16246120486343002,0.5651548510177978,-0.08741190938875931,0.08928665561006828,0.4133312915415508,-0.481331578613846,0.4010842616675636,-0.7620971091909101,-0.31034619555806764,-0.22704328303064464,-0.14104370531847035,1.1352483106404372,-1.184514706489039,-0.12073156343388697,-1.036283822517531,0.8330349498073084,0.2240500896822306,-0.2635557649110297,0.30079849184491564,-0.04032758033395423,1.9493598343429275,-0.5122425168401418,-1.4875192471420662,1.2252496194791052,-2.064505390443161,-1.1497547809910522,0.2894414130403078,-2.4561724258755,0.026965413493882928,1.0973465629164536,0.76319480485883,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3666666666666667,1.0,0.0,0.0,1.0,0.2623009959714669,-0.006351613079463174,0.022444061349425663,0.9809527265866739,0.06662030062048016,0.08043719727514227,0.16377832897529115,0.5918553642516924,-0.09168812059803709,0.08948531809524762,0.3973451494668814,-0.5946918899118248,0.38264022743856785,-0.7617925599299015,-0.29388754005752293,-0.23043601649755552,-0.15347858875237855,1.1451779258580341,-1.2008246685905923,-0.13023827988660666,-1.0332690326434852,0.8130012967674414,0.2244216083896695,-0.25439883551645265,0.30844590447254217,0.10605836668450719,1.9954702444659433,-0.3015616473308752,-1.4961463428075539,1.156186417609728,-1.8556743803488063,-1.131312667559835,0.42580213583436777,-2.3450729097444167,0.06189982092800361,1.1057086849732634,1.0572202136449127,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.375,1.0,0.0,0.0,1.0,0.26738188732668555,-0.005482837348077228,0.022375041296697044,0.9808017052645148,0.06878123822805372,0.07794202754282904,0.1649915045102532,0.6172837110373606,-0.09568869003765167,0.08835093819427664,0.3819910357256515,-0.7018434726651328,0.3636095051256888,-0.7603294697461683,-0.2770883581503019,-0.23206931048615922,-0.16597947769859625,1.154518084267266,-1.2154426128281857,-0.13958677455988422,-1.029187120253625,0.7939504013115681,0.225081753364364,-0.245127286828142,0.3184188287389975,0.2371288945230421,2.0303163199264453,-0.0908347405356219,-1.5029740788592838,1.0832639880662143,-1.659399677393818,-1.1114846104290617,0.5464589542044607,-2.223357103128276,0.09636057997921776,1.1268527278643925,1.3152540991742068,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3833333333333333,1.0,0.0,0.0,1.0,0.27266154545635835,-0.004565290838340322,0.022289110109664292,0.9806887611151921,0.07094431924252784,0.07501775446399421,0.16609874745088182,0.6412303162355977,-0.09955295325970373,0.08607630468622995,0.3669766066228837,-0.801255549502754,0.34397756119138084,-0.7578404116878508,-0.2600489347254155,-0.23194992883981588,-0.1785281567333666,1.1632323256591377,-1.2284813298804893,-0.1487630233937577,-1.0241613834067442,0.7759453450486368,0.2260276180559898,-0.23561795671871277,0.3303668061254456,0.3522312815913864,2.0528437927788925,0.11855194921631396,-1.507327218676362,1.0056232868246884,-1.4768464866637077,-1.0898235239968774,0.6531126537790533,-2.0960227950039934,0.1305385322772945,1.1636417717694858,1.5283617861094523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3916666666666666,1.0,0.0,0.0,1.0,0.2781268567712041,-0.003602223590355653,0.02218621164018407,0.9806085153711045,0.07310509222057161,0.07169860260400737,0.16709846036916248,0.6639980713491368,-0.10298078575099655,0.08238126843725066,0.35184217831097236,-0.8950891300588224,0.3216061691045474,-0.7544589483863119,-0.24287429493732038,-0.23009344466588733,-0.19110159800986895,1.1712784723810108,-1.2400567209392475,-0.15775049995983217,-1.0183019093573074,0.7590166880615016,0.22725739556898558,-0.22573325729865057,0.34389152517415505,0.4552672728949858,2.065420732281005,0.32553902882851815,-1.508058318621291,0.9232245618884161,-1.30554306012296,-1.0673972444537305,0.744157028475434,-1.955499685252673,0.1632735247460182,1.2127892547724923,1.7077690765951803,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4,1.0,0.0,0.0,1.0,0.2837674935129474,-0.002588672417871779,0.022060354440788594,0.9805602723420636,0.07525875173175658,0.06799753988304927,0.16797025677812946,0.6857919422393544,-0.10584970385694831,0.07711984691241625,0.3366219521606093,-0.9842704453412056,0.29530698728060195,-0.7502526238062677,-0.22562525585406543,-0.22652427835934058,-0.20366246204372146,1.1786194016906113,-1.2502403808825386,-0.16655297746798653,-1.011758766265487,0.7433536836277589,0.22874884346842345,-0.21540480247250457,0.3588296240686986,0.5482051760313111,2.0695111434354363,0.5290721854910679,-1.5045798739993739,0.8361983862806577,-1.144405951345533,-1.045018389160874,0.8190520958515624,-1.7983632517492354,0.19360227321094048,1.2720563537430736,1.8601440380330092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4083333333333332,1.0,0.0,0.0,1.0,0.28957303555190395,-0.0015251022984378985,0.021909209290149365,0.9805406162034752,0.07740153623867717,0.06394201863551527,0.16870246120331137,0.7060663994171362,-0.10887618796383784,0.07106924125892074,0.32180496586743035,-1.0634970922254265,0.26836255107658624,-0.7453221954524567,-0.20838244254672977,-0.22127557490770286,-0.21617792924319185,1.185215112152355,-1.259130153461673,-0.1751674731125134,-1.0046510410931146,0.7290439671990143,0.23048410012250126,-0.20453231806959934,0.37489392580803854,0.6255401195083032,2.061562876361622,0.7274536125066516,-1.4975580983863186,0.7438320992288849,-0.9975931365380619,-1.0207691707366824,0.8835459686436975,-1.6436836027101176,0.2232453244043897,1.3472671843029471,1.962315704536357,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4166666666666667,1.0,0.0,0.0,1.0,0.29553104916639106,-0.0004227600572676337,0.021738072184929062,0.9805410421204263,0.07952703708009841,0.05958706197992221,0.16930474634607293,0.7245370198104443,-0.11239636647655586,0.06468639082901317,0.3070491340186608,-1.1301914006510272,0.24233358752757517,-0.739826955147796,-0.19126587458137173,-0.21440005148422972,-0.22862176368349343,1.191016603344426,-1.266866933158173,-0.18356579698026457,-0.9970330001214254,0.7159589569159236,0.23246959887516327,-0.19295034940078878,0.39153488581097123,0.6860389721926508,2.0408253379116394,0.9180758313287901,-1.4867589468021554,0.645672595740785,-0.8663532152525644,-0.9933835789293349,0.9410073730360513,-1.501696276837261,0.2533919575866578,1.4398149287725914,2.0049933643183215,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.425,1.0,0.0,0.0,1.0,0.30162985250966146,0.000710123596842158,0.021550154361460197,0.9805554843685276,0.08162598130768536,0.054979863180851817,0.16978031657131096,0.7413746784985483,-0.11623081897798736,0.057835270824837165,0.2919347734293909,-1.1856887604193869,0.2161328184061757,-0.7338882125825792,-0.17436868691486912,-0.20597431105222302,-0.24095724502322777,1.1959763220813682,-1.2735693737158824,-0.191723866094669,-0.9889675848758471,0.7040156959183933,0.23470729941561222,-0.18053540259005615,0.40831048188001057,0.7331200890663303,2.010130349282198,1.0980881243960512,-1.4714514300430965,0.5420813290204451,-0.7487692813145275,-0.9634662002402328,0.9908100698733913,-1.3686860271851486,0.2834258521607719,1.5448939760280478,1.9994376408481374,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4333333333333333,1.0,0.0,0.0,1.0,0.3078585079340036,0.00186626214638039,0.021347264114327615,0.9805791069590912,0.08368968748106774,0.05016471208005062,0.17012981181044623,0.756638817475738,-0.12032548277279312,0.050458236764724024,0.27649076049503063,-1.230599132609691,0.18931507975764678,-0.7276082869966904,-0.1577637020933351,-0.19609858274429554,-0.2531459541842117,1.2000512921614335,-1.2793464211800818,-0.19962356698426845,-0.9805194989568689,0.6931475231295045,0.2371933630778428,-0.167202116466988,0.4248588464917735,0.7687945454555245,1.9717116708193383,1.2647015494211118,-1.4514652389675227,0.43357770291164055,-0.6439105638046527,-0.931602604184894,1.0328517750061006,-1.2433978241819066,0.31276923063468853,1.6582776978624743,1.9540743522031323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4416666666666667,1.0,0.0,0.0,1.0,0.3142059785733446,0.0030386552604029886,0.02113018999368812,0.9806080477014023,0.08570972598963757,0.045184249282174876,0.17035281996769783,0.7703186781003069,-0.12464106025978175,0.04253428169216767,0.2607319447901713,-1.2652831003422107,0.16169651794440104,-0.7210749701583204,-0.14150682573454682,-0.1848959518952045,-0.26514833233935314,1.2032026171298955,-1.28430121644596,-0.20725057616441722,-0.9717533886257455,0.6832923988486949,0.23992011992619036,-0.15289744095901492,0.4408783877500628,0.7946250519649656,1.9276493063615703,1.4150193141881613,-1.4267379057131058,0.3205878730681899,-0.5510603005666326,-0.8982235603001798,1.0672033358797361,-1.1255603140461101,0.34097400764718067,1.776386170706122,1.8753973427036263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.45,1.0,0.0,0.0,1.0,0.3206610441753827,0.0042205673282802265,0.020898887013889783,0.9806392859519764,0.08767799572609514,0.040080069073129186,0.1704486666896221,0.7823577641931175,-0.12913024005991275,0.034071997666865694,0.24466672764482705,-1.2900190489660903,0.13321380192948493,-0.7143645361306077,-0.1256362136539756,-0.17251492750782618,-0.27692491927943014,1.2053944233792366,-1.288530759522859,-0.2145939596559381,-0.9627327766922066,0.6743881845620693,0.24287626320529582,-0.13759568028855262,0.4561154688701673,0.8119528382731134,1.8799955444990422,1.5460695194959528,-1.397292891430968,0.20341137130284626,-0.46950454933490704,-0.8637011082610224,1.0940304029152914,-1.0153762531120747,0.36760890808045843,1.896070137319882,1.7687708785309375,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4583333333333333,1.0,0.0,0.0,1.0,0.3272116777778899,0.005405380360246958,0.020652745137720318,0.9806706408190256,0.08958658579961991,0.03489269527946353,0.17041665909361847,0.7926512867613343,-0.13372726321195832,0.0251059323853058,0.22830231867408451,-1.305086047850277,0.10386338316194689,-0.7075424228537686,-0.11017356665956278,-0.15912812657027195,-0.28843654719653594,1.2065928066516096,-1.2921262922682084,-0.22164559463543426,-0.9535195485771573,0.666369461296827,0.24604693506086467,-0.12129627200368355,0.47035790239224506,0.8219869351672604,1.8307445690802868,1.6549487699267473,-1.3632314666123901,0.08219435900048477,-0.39846087790404994,-0.8283883337899833,1.1135528221411883,-0.9133109518656424,0.39221202378454445,2.0144505561535375,1.638899074187945,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4666666666666666,1.0,0.0,0.0,1.0,0.3338448356428596,0.006586722038633619,0.020390734828948927,0.9807007214867853,0.09142796540845936,0.029661545039617744,0.1702563207712353,0.8010722537492484,-0.13834183859753427,0.015691204751011836,0.21167798995727666,-1.3107881562483878,0.07369373591921771,-0.70066475387782,-0.09512380416930415,-0.14493244800904706,-0.29964544372297,1.206764329362578,-1.2951717741545932,-0.22840043188577117,-0.9441735629898534,0.6591663353643086,0.24941313026837156,-0.10402150435266033,0.4834304534399664,0.8257757801860865,1.781889185430837,1.7388094535175924,-1.3247746727559473,-0.043095757950517566,-0.33696369907014745,-0.792664795926083,1.1260316713958018,-0.8199423187494337,0.4142527064075341,2.1288908094548047,1.4900389280147575,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.475,1.0,0.0,0.0,1.0,0.3405461783275294,0.00775857383229105,0.020111577159784295,0.9807288795268158,0.09319513568822597,0.02442475205611015,0.1699675352332166,0.8074548691409869,-0.1428587514266163,0.0059092774632474865,0.19484150866266392,-1.3074921849928223,0.04278558934421624,-0.6937794931840005,-0.08047541356904883,-0.1301479690116454,-0.31051612507580173,1.205874544019101,-1.2977423539193775,-0.23485667456753564,-0.9347523540538939,0.6527037559843364,0.25295114683432357,-0.08581475851277014,0.49519188452582436,0.8242668677151888,1.7352662573282316,1.7951345965503198,-1.2822212345274497,-0.1726815402642723,-0.2838642137052272,-0.7569144729474347,1.131766977835924,-0.7359336468511235,0.43314725646842966,2.2369248156167845,1.3261819116967,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4833333333333334,1.0,0.0,0.0,1.0,0.347299588636127,0.008915294633138955,0.019813999345817426,0.9807551705395781,0.09488166178401156,0.019218798302551496,0.16955059277079002,0.8116046321214179,-0.1471356194851993,-0.004133562266557332,0.1778668517857246,-1.295620066140867,0.01125572420208712,-0.6869269727492335,-0.06620269988050029,-0.11501353806654173,-0.3210157976317608,1.2038863036915068,-1.2999028443830136,-0.24101567310156174,-0.9253107800259214,0.6469007745834565,0.25663225120951205,-0.0667394240923806,0.505533485301578,0.8182715145873098,1.692495071093479,1.8218426255688243,-1.2359698670021602,-0.30700394949779497,-0.23777982230792194,-0.7215437672434849,1.1311048758767184,-0.6620186675883488,0.4482469837061642,2.336246184109402,1.1511205513310008,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4916666666666667,1.0,0.0,0.0,1.0,0.35408701605512594,0.010051824017213409,0.01949688714157369,0.9807802409664131,0.09648194614350201,0.014078418366963639,0.16900636418388643,0.8133095843620268,-0.15100599758929106,-0.014311392066705203,0.1608613464759185,-1.2756556757914135,-0.02075880534722884,-0.6801416346075453,-0.05226716238415752,-0.099783925252165,-0.33111562285917107,1.200757811527471,-1.301705350957843,-0.24688240402159373,-0.9159006061226153,0.6416701115245306,0.260421929896093,-0.04687732211094677,0.5143772270480077,0.8084675750346415,1.6549454160492674,1.817347689688852,-1.186508426011258,-0.4467155581743043,-0.19707797180354536,-0.6869885453243096,1.1244174271853002,-0.5989154927958262,0.45883179958584264,2.4246926865266345,0.9685613286560768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5,1.0,0.0,0.0,1.0,0.3608881649872743,0.011163743675766427,0.0191594515773693,0.9808052668031914,0.09799131665132665,0.009036197544497646,0.16833620408622263,0.8123391255659248,-0.15428602163692173,-0.024477922089735135,0.1439470122012917,-1.2481442043812083,-0.05311515485892001,-0.6734525131653228,-0.038620276279679164,-0.08472440990506086,-0.34079093806528177,1.1964410443886018,-1.303187477246406,-0.25246548219030024,-0.906570489572833,0.6369188497035261,0.2642794478692761,-0.02632787931693668,0.5216761741125127,0.7954350827314349,1.6236391957784317,1.7807027959304307,-1.1343674094087786,-0.592656621251999,-0.15990770557156253,-0.6536862738068572,1.1120997622094175,-0.5473185802641223,0.4641340496680313,2.5002340691509657,0.7821625762846884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5083333333333333,1.0,0.0,0.0,1.0,0.3676803488151896,0.012247371844017413,0.01880139625988965,0.9808318412220038,0.09940613219272292,0.004122465724060228,0.16754201086315182,0.808459391544476,-0.15678236832368117,-0.03446947476334194,0.12726325698371022,-1.2136482706321663,-0.08565663402312429,-0.666884383228688,-0.025206509121183655,-0.07010554531999116,-0.3500217463493174,1.190880201173271,-1.3043704793840356,-0.257777175251708,-0.8973656100857916,0.6325481351867952,0.26815749739056016,-0.005206754291764008,0.5274132699860858,0.7796306355941662,1.5992438082185059,1.711558885059116,-1.0801143559719661,-0.7458260751718981,-0.12422298426563838,-0.6220632206723486,1.0945835292350048,-0.5079403669860572,0.4633559849977986,2.561007357138059,0.5954371790271074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5166666666666666,1.0,0.0,0.0,1.0,0.3744384538420092,0.01329980596044265,0.018423034007618178,0.9808618700799625,0.10072382611722165,-0.0006347461729284962,0.1666262277465033,0.8014444287567273,-0.15830476735137836,-0.044112440095031444,0.11095544210768399,-1.1727310237873134,-0.11823213196509468,-0.6604586692387534,-0.011966212809370734,-0.05619842848740893,-0.35879284399814787,1.1840106098024035,-1.3052578603175,-0.2628332025348394,-0.8883274307522496,0.6284531769204251,0.2720020476192394,0.016355576635364306,0.5316001270962978,0.7614173023705617,1.5821167296896816,1.6100509376239804,-1.0243096888327985,-0.9073206892156627,-0.08784553999636291,-0.5925104144927562,1.0723154096899745,-0.48146615798718484,0.4556912228155885,2.6053194800650883,0.4117536196930516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.525,1.0,0.0,0.0,1.0,0.3811350318180907,0.014318917673826611,0.018025328801176667,0.9808974849889088,0.10194288767858714,-0.005209671967919624,0.1655917597960565,0.7910894159127537,-0.1586790261776626,-0.05323223562983968,0.09516383290101971,-1.1259299140121362,-0.15071347477570804,-0.6541940948558453,0.0011621030403110378,-0.043271363026258156,-0.3670935744965307,1.1757581896863434,-1.3058345717173083,-0.2676523488265873,-0.8794936865909587,0.6245236992203421,0.2757523511041533,0.03821523704265413,0.5342758303143034,0.7410892410632841,1.5724052349180837,1.476581869894453,-0.9674675578243508,-1.0782631366505235,-0.04854390650862683,-0.5653603167630938,1.0457364624525334,-0.4685205301674178,0.44034625256280324,2.6316574106256176,0.23429930171140256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5333333333333332,1.0,0.0,0.0,1.0,0.38774054579118566,0.015303302037149098,0.017609871471825817,0.980940971540345,0.10306277641708117,-0.00957863690788571,0.164441856550698,0.7772255271130919,-0.15776027334616313,-0.061662357347940885,0.08001336699889411,-1.0737235011442727,-0.1830077539080254,-0.6481071818876987,0.014240541105930659,-0.03158873065583471,-0.3749173032952204,1.1660395575248947,-1.3060669254259771,-0.27225587448089095,-0.8708984897113741,0.6206445014176348,0.27934115182861946,0.0602165334791246,0.5355051154581545,0.7188912950846515,1.5701914601502318,1.3115285237421377,-0.9100242574367456,-1.2597210402056902,-0.004122055680841896,-0.5408634674145729,1.0152687882401001,-0.46965317832606157,0.41656411810831684,2.6387106046234474,0.06599820316452565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5416666666666667,1.0,0.0,0.0,1.0,0.3942237797612326,0.0162521817658381,0.017178788097068253,0.9809947182442575,0.10408377686564825,-0.013719751517600237,0.1631799576807298,0.7597365181347866,-0.15544581955796888,-0.06925367254786446,0.06560514255973882,-1.0165014808917674,-0.21507010152175482,-0.6422125732711012,0.027331960709481566,-0.021412554297222528,-0.3822606454538098,1.1547628390162485,-1.3059032726453224,-0.2766667399501635,-0.8625725401202904,0.6166961462482411,0.2826950864059586,0.08219374711971159,0.5353758003670455,0.6950408433578525,1.5756625496319536,1.1149218826250271,-0.8523114423242928,-1.4526195541574838,0.047488874984709106,-0.5191685477838992,0.9813050465486328,-0.4853195537543442,0.38364608488747787,2.625403470211905,-0.09058935912655164,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.55,1.0,0.0,0.0,1.0,0.4005524327986526,0.017165275736020398,0.016734588997360012,0.9810611889786344,0.10500680914214107,-0.017612489237921105,0.16180949828907637,0.7385794725675379,-0.15168737269887636,-0.07588332052948868,0.05201081203375313,-0.9545403582075791,-0.24691735331223674,-0.6365231678317345,0.04050158359979655,-0.013006699278750923,-0.38912249400062526,1.14182923162227,-1.305275444176232,-0.2809086836106226,-0.8545434056022302,0.6125558421883958,0.28573525324341076,0.10397325798265634,0.5339952928060453,0.6697512540167017,1.589274869110763,0.8861699164856617,-0.794534073706159,-1.6576464015060521,0.10814042566307247,-0.5003071834668449,0.9442028423577664,-0.5158476410808754,0.34097019937578077,2.5909508154084016,-0.2333955100591445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5583333333333333,1.0,0.0,0.0,1.0,0.4066939431400335,0.018042644559528632,0.016279970893657087,0.9811429196489102,0.1058332155777243,-0.021237172163348052,0.16033366527921727,0.713813111269337,-0.14650338773668944,-0.08146325268232432,0.039269913793552214,-0.8879855162201373,-0.27864376690598086,-0.6310500523708228,0.05381987519466095,-0.006643055689128165,-0.3955028800155791,1.1271353989911477,-1.3041009322176045,-0.28500519300794425,-0.8468358260809943,0.6080986855635598,0.2883779230622216,0.1253762607098516,0.531485875199393,0.6432575659913575,1.6118839865604349,0.6238849671674432,-0.7367496893003345,-1.8751421940548507,0.17937400259544045,-0.48418227449463447,0.9042828197868502,-0.5613770488980085,0.2880078926058238,2.5349530973497294,-0.361020549344806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5666666666666667,1.0,0.0,0.0,1.0,0.41261661853905146,0.01888452444723495,0.015817582299753333,0.9812425385431384,0.10656453982928664,-0.02457438672308417,0.15875509101009608,0.6856360203696397,-0.1399929529523464,-0.08594941533322586,0.027388219759237997,-0.8168366970631268,-0.3104394519575023,-0.6258022083985452,0.06736631670913713,-0.0026086164926268697,-0.40140165548896417,1.1105768617213558,-1.302285877466308,-0.2889783881855332,-0.8394720252724494,0.6031995580400956,0.29053538478684116,0.1462224762718185,0.5279782836502985,0.6158449700659285,1.644828474500089,0.32583710675130917,-0.6788441381689836,-2.1049657164309243,0.26230730012672954,-0.47055588532985193,0.8618240253478682,-0.621757702083281,0.22434277246645262,2.457543214680778,-0.47297586667125247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.575,1.0,0.0,0.0,1.0,0.4182911612713526,0.019691151273022,0.015349748798107693,0.9813628096130363,0.107202298421605,-0.027604331308254265,0.15707547235197541,0.654432809454002,-0.13235244699208154,-0.08935356938991566,0.016332650528091297,-0.7409285658514156,-0.3426101525826289,-0.6207859695363906,0.08123368310299577,-0.0012124372432730126,-0.40681694898506215,1.0920526370506323,-1.299729143882159,-0.2928477910967751,-0.8324720923251965,0.5977360571955052,0.2921169692699958,0.16633531428786458,0.5236029440882055,0.5878791834642194,1.68998317341289,-0.011018189699645584,-0.6205004618041732,-2.3463286375024994,0.3574659490694154,-0.4590302764825904,0.8170435333111792,-0.6964072395775966,0.1496989315506525,2.359576989008067,-0.5700019313389659,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5833333333333333,1.0,0.0,0.0,1.0,0.423692638448956,0.02046255854628818,0.01487812892842902,0.9815066986131575,0.10774771299290656,-0.030306056579355742,0.1552951185870082,0.6233065426754952,-0.12511600011581242,-0.09188315778021616,0.0024236707804670687,-0.6731621312015033,-0.37546794701521324,-0.6160042220074748,0.0955327029326853,-0.0027922529876209627,-0.41174332985236706,1.0714713844296475,-1.2963281116484844,-0.29662889279357635,-0.8258546330505964,0.5915927707138023,0.29303036697935203,0.18554875942195295,0.5184782514613158,0.5695979534365625,1.7351279075549022,-0.3309650285285085,-0.5511262440769049,-2.591886523865372,0.4821538238923706,-0.4445171918532953,0.7607911433692327,-0.7402636041600519,0.07585402418602172,2.256353776535828,-0.6394579256913957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5916666666666666,1.0,0.0,0.0,1.0,0.42884861378055017,0.02119223424255488,0.014400980374872785,0.9816769242398432,0.10818888652087567,-0.032769759517084995,0.153400534906572,0.5971538496470299,-0.12028278647479375,-0.09418287385281988,-0.01860924200771663,-0.6322238834308066,-0.40900678698487664,-0.6112926703124479,0.11015248156224414,-0.006728521052081487,-0.4160023863863439,1.0488545283195427,-1.2916932468172861,-0.3002564109609967,-0.8197922399357093,0.5853983304595043,0.2933812030064295,0.2039412105634617,0.5129453119933489,0.5736516036705308,1.758374248691137,-0.543804760143676,-0.4580082863942536,-2.8260845214137964,0.656389452443289,-0.4213314617880004,0.678420664616306,-0.6841574309957044,0.020027137750907587,2.172521760790307,-0.6655464636403319,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6,1.0,0.0,0.0,1.0,0.4338223092169747,0.02187527177618795,0.013913544409438417,0.9818736879383934,0.10851588670617654,-0.03513280772965821,0.15137387187926674,0.5769025098336805,-0.11754178737525718,-0.09678925401961778,-0.04388527835296241,-0.6133525116598296,-0.4428627441619124,-0.6064433619462993,0.12483894041087092,-0.011855665656682229,-0.4193768012922713,1.0243699757394176,-1.2853882874410962,-0.30365108382337636,-0.8145476219736579,0.5801901468638739,0.2933641526085338,0.22175745543512473,0.5073858104006436,0.5936987524522874,1.7615268975149445,-0.6587276406977824,-0.3481201259009781,-3.0400316727511734,0.8664574714910067,-0.39291764159185005,0.5708782619089559,-0.5336695558513105,-0.02122824488914654,2.1116529594865177,-0.6623887863612721,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6083333333333334,1.0,0.0,0.0,1.0,0.4386548571336544,0.022514892344793137,0.013412415482822015,0.9820955445007652,0.10873359686872885,-0.037442979050610704,0.14920914751989367,0.5606863405687813,-0.11578973255632714,-0.09965864672135125,-0.06962664313544198,-0.6026300960692562,-0.4767006393396638,-0.6013976911049098,0.1395112631874932,-0.017707315063711194,-0.42180438848469354,0.9981873337736898,-1.2772522889591027,-0.30680503832086087,-0.8102776022372267,0.5765038378619824,0.2930273989249437,0.23913542655490366,0.5019054988873277,0.6187796254148248,1.76003199622465,-0.7359193788588562,-0.23270660589286174,-3.2347796559155584,1.0905843468242482,-0.36386036981858605,0.44736810909620894,-0.3314535227936899,-0.058767744285739276,2.0646976879595065,-0.6529030565915706,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6166666666666667,1.0,0.0,0.0,1.0,0.4433743473160032,0.023112935511195476,0.012896385455712159,0.9823412588040888,0.10884448686790346,-0.03971916034166267,0.1469044493250118,0.547360979700398,-0.11478588878973363,-0.10262468844258286,-0.09561570747435742,-0.5951803858457871,-0.5104038579381964,-0.5961303681893856,0.15417280701461508,-0.024120988637663165,-0.423255244723819,0.9704569814741583,-1.267211881660692,-0.3097154233203528,-0.8070914868220544,0.5746659214839791,0.2923846902037715,0.2561690835677832,0.49650409279078406,0.6463423286130787,1.760954406376884,-0.8011166173884968,-0.11433737905697239,-3.4120490445954754,1.3210298400350906,-0.334396195169655,0.31195497389682636,-0.09547001871175409,-0.09529569136579541,2.027691831851264,-0.6457932740811423,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.625,1.0,0.0,0.0,1.0,0.44800248010555077,0.023669535067104962,0.012364779136023601,0.9826098431201904,0.10884878516993254,-0.0419690469708002,0.1444591197079069,0.5363716394754362,-0.1144873628071145,-0.10565355290173625,-0.12196329854283265,-0.5890494638270516,-0.5439787787532755,-0.5906253189613585,0.1688605032937746,-0.031059258686852807,-0.4237100114689764,0.9413198496970986,-1.2552351249585179,-0.3123783082403551,-0.8050783526722796,0.5749126708834532,0.29143913740218047,0.2729302904190914,0.491142277652642,0.6756463700833759,1.7670856200262808,-0.8648266479281993,0.0060060916084136995,-3.5726260874490245,1.5539230688139671,-0.30443126367746265,0.1665534174021266,0.16621414354216713,-0.13168553953834872,1.9987599435647163,-0.644461589037798,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6333333333333333,1.0,0.0,0.0,1.0,0.45255827095725,0.02418389534950631,0.011816841468630133,0.9829004247108976,0.10874550826917859,-0.044195649358307255,0.14187288011557336,0.5275101939530714,-0.11489407985887633,-0.1087782576430869,-0.14876277748224237,-0.5833939744535683,-0.5774468482099964,-0.5848695953546627,0.1836242340150531,-0.03853476610313315,-0.4231551431970121,0.9109132133500079,-1.241313163847126,-0.31478927771497717,-0.804315596532019,0.5774361572096819,0.2901899312114657,0.2894817492938618,0.48576306630682076,0.7064270135080419,1.7795060110923562,-0.9311883330771449,0.12771541285535926,-3.7167783267672605,1.786939548004347,-0.2739456029072329,0.012452778029001799,0.44933350717590637,-0.16825392344831602,1.9772671639611894,-0.6507162737150951,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6416666666666666,1.0,0.0,0.0,1.0,0.45706007856328046,0.02465478748224503,0.011251545616038403,0.9832121542100895,0.10853303368103433,-0.04639982736175865,0.13914559437658572,0.5207591604296437,-0.1160209843387342,-0.11206128895941624,-0.17607523119691182,-0.5778074628498971,-0.6108154301823131,-0.5788515354028911,0.19851893681198055,-0.046579064238138554,-0.4215814212547204,0.8793735442509776,-1.2254527991584454,-0.316944068288809,-0.8048708063717962,0.5824015626697183,0.28863490534470854,0.3058847431517779,0.4802970064240571,0.7385673189651576,1.7986413394181577,-1.0016792456848063,0.2503147615580936,-3.844531036291836,2.0183661463931557,-0.24297446922635801,-0.1491406431293063,0.7509970070661165,-0.20509112469516366,1.963315698341812,-0.6660476605142152,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.65,1.0,0.0,0.0,1.0,0.46152669746931624,0.025080780650665095,0.010667539021152772,0.9835441562279734,0.10820935729152602,-0.04858129616671062,0.13627723730387417,0.516199802134202,-0.11788871264974723,-0.11557844921790195,-0.2039441369352719,-0.5720558943129729,-0.6440735067121609,-0.5725601400385767,0.2136015896720224,-0.05522942019787992,-0.4189832305043772,0.8468376960784773,-1.2076737280739067,-0.31883885220208313,-0.8068012739175074,0.5899527739941172,0.28677174579987963,0.32220367759955865,0.47466227196491717,0.7719984554430059,1.8246461504401674,-1.0766123080298073,0.373397178223539,-3.9558306551660682,2.2467062078510835,-0.21157979058688103,-0.3169163103576156,1.0686899575791653,-0.24217989037080612,1.9574288427967779,-0.6920041615795014,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6583333333333332,1.0,0.0,0.0,1.0,0.465977881489135,0.025460337241069192,0.0100631372220483,0.9838955047219607,0.10777220127595374,-0.0507390203032792,0.13326792651932676,0.5139542021025926,-0.12051508008262037,-0.11941090620884487,-0.23240404173855142,-0.5659713409666902,-0.6771930764373655,-0.565984894478841,0.22892970598598333,-0.06452260270530201,-0.4153581349509948,0.8134430333315431,-1.1880076956942607,-0.3204703981319237,-0.8101527448777565,0.6002130619627044,0.28459857383852843,0.33850855719839085,0.4687636037310654,0.8066598504319189,1.8575020085393819,-1.1557001443910215,0.49659435411736785,-4.050654485735408,2.470528324069474,-0.17984495050912708,-0.4894071602600403,1.3998573031162365,-0.2794566652682795,1.960339647960081,-0.7302451262670406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6666666666666667,1.0,0.0,1.0,1.0,0.4704344732161622,0.025791850753376432,0.009436341670512195,0.9842652105477873,0.10721906456521374,-0.05287135944049958,0.13011797281709875,0.4985298498347119,-0.11934673507036773,-0.11834400278521937,-0.25989431816114555,-0.5463683301071691,-0.7060374631095735,-0.5591158091980447,0.2445599564810121,-0.07449108927106361,-0.4107066579357544,0.7793267879828871,-1.1664982560060821,-0.3218362680439019,-0.8149580599218414,0.6132837290460544,0.28211413471207497,0.35487600506556,0.4624915198604665,0.8333161118049004,1.8414653186389374,-1.2050632168222692,0.6058336030008404,-4.182500659929,2.7092024559988737,-0.018184617685956805,-0.6148376136236999,2.50248256277132,-0.3389815034941157,1.755004213293161,-0.5102064296596731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.675,1.0,0.0,1.0,1.0,0.47464120738661747,0.026061784680815287,0.008851260729459538,0.9846524453030419,0.10654461863910951,-0.054871069220060686,0.12687384269755558,0.5061173040353976,-0.12495209492022302,-0.12231868526862572,-0.2928229239245821,-0.5402988674486704,-0.7367945396654131,-0.552096292615426,0.2596207946299656,-0.08460698965233983,-0.4052609082343141,0.7437346889993931,-1.1428543214276128,-0.3207734750933563,-0.8204000384381515,0.6419211046755597,0.2789488821136265,0.36775862741994353,0.4602601632367375,0.8751674222386896,1.8931930684818232,-1.2835147887876421,0.7337945613192454,-4.233713318741161,2.9242347325447193,0.1451027826134843,-0.6516114179639465,3.5292309677515354,-0.37498247632702264,1.4138601154553865,0.009526254545390023,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6833333333333333,1.0,0.0,1.0,1.0,0.4792572559049983,0.02628872807077253,0.008187849353069215,0.9850563292536582,0.10572444263172,-0.056959750440260304,0.12345832194606729,0.5474263790668686,-0.139876946704498,-0.13583730001464386,-0.3298258776604399,-0.5551389727686613,-0.7725696447309929,-0.5445296854940666,0.2761131742890425,-0.09588300241752432,-0.39847674858043364,0.7087648993372011,-1.1177610104636702,-0.3194178883336772,-0.8258182502212406,0.6721042451752467,0.27586442677329126,0.37844034032314977,0.4626502907695563,0.93484616751077,2.0493208479950034,-1.412619954804616,0.8857541476623543,-4.165097795267405,3.0895130738026033,0.17526027028225033,-0.6299226365303334,3.6608917103148375,-0.37318754395444187,1.14115535313571,0.5557396816199733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6916666666666667,1.0,0.0,1.0,1.0,0.4842177116897287,0.02646634215640636,0.0074618356199197215,0.9854736513812472,0.1047751138608399,-0.05908639828844151,0.11988601038675255,0.5818320272388533,-0.15245925791189946,-0.1476362638688445,-0.3635759534149151,-0.5597971403158227,-0.8067107874012136,-0.5365155231569132,0.293776142096549,-0.1081506555657501,-0.3904983391066082,0.674316392411603,-1.091362436864236,-0.3178524705886521,-0.8308987490469903,0.7029359665141404,0.2727290897143858,0.3867778833055387,0.4695224912637371,0.985482502579389,2.1760145062223435,-1.52162108571654,1.023631520577909,-4.109052684052181,3.2405471268668684,0.19835151752579216,-0.5810754623821057,3.7103117314544276,-0.38508565391646044,0.8556257420017765,1.0818919356793488,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7,1.0,0.0,1.0,0.0,0.4894646033288135,0.026590836453417862,0.00668263246265478,0.9859034279561474,0.10369537339042888,-0.06121545459123739,0.11616526331586982,0.6103442137779174,-0.16295591253782654,-0.15822021938942185,-0.39665783801625465,-0.5567249441135849,-0.8398306716149049,-0.5281049771177434,0.31238008272608153,-0.12124335384613331,-0.3814162232374685,0.6402806879363314,-1.0637518916825557,-0.3161120297082473,-0.8355028412609423,0.7339427740328205,0.26944633254135025,0.3927007693565127,0.4806818230308788,1.0306785801431562,2.277486226441079,-1.6117276036179418,1.1514991830944232,-4.064844897749622,3.381573800623756,0.21754706068421226,-0.5184620757700364,3.710854974247677,-0.407884724598504,0.5654955210139856,1.5810837758336427,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7083333333333333,1.0,0.0,1.0,0.0,0.4949506854095555,0.02665970280525095,0.005857542855420718,0.9863447874251217,0.1024839232398196,-0.06331824594052915,0.11230229529231385,0.6340914392377924,-0.17166342563758538,-0.1677493701698946,-0.4292014357101762,-0.547095046614268,-0.8720969372394108,-0.5193375468211939,0.331734245870567,-0.1350127822927158,-0.3713066860550345,0.6065689774491093,-1.0350028735205068,-0.31422668624391525,-0.8395397836431576,0.7647835494182683,0.2659310109710774,0.3962028086557718,0.4958738875276311,1.0715010568187777,2.357884708230519,-1.685363865517818,1.2706552049949194,-4.030413683331506,3.5144732372972287,0.23337018252842845,-0.44647676744398845,3.6749227062119183,-0.44046762200369405,0.2775804284132688,2.0459354941149543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7166666666666666,1.0,0.0,1.0,0.0,0.5006373123474699,0.026671129364117308,0.0049935341950696766,0.9867968719110839,0.10114013248551039,-0.0653687966095655,0.10830294371487677,0.6540211309027888,-0.17882962658510668,-0.17623764636151495,-0.4611603230866266,-0.5313657427036055,-0.9034757131581292,-0.5102466261707638,0.3516781611965902,-0.1493327516047636,-0.36023863648755317,0.573107126547473,-1.0051773377276019,-0.31222252666610684,-0.8429441207183421,0.7951914858030191,0.26210520550795535,0.3973271098300672,0.5147807479327947,1.1085762065059002,2.4206065265310364,-1.7452976053505809,1.3818538802137503,-4.004107231706294,3.6402546685713033,0.2463197077796464,-0.3675868571005214,3.6099120672195517,-0.48201874725368965,-0.0030732333285776736,2.4695887801553353,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7249999999999999,1.0,0.0,1.0,0.0,0.5064932443209935,0.026623780759759096,0.004097781256632748,0.9872588659754234,0.09966391675839405,-0.06734215267023154,0.10417326779541511,0.6709746521427966,-0.18466820039698684,-0.18366312336882024,-0.49247229596481384,-0.5097007820505431,-0.9338741608359236,-0.5008612767127623,0.3720776879794176,-0.16410107571522548,-0.34827578805147197,0.5398338569206711,-0.9743319623776517,-0.31012135778092115,-0.8456662312614996,0.8249487505385942,0.2578973651835159,0.3961515881002955,0.53703370053022,1.1423702133331337,2.4686479969661703,-1.7943741486040228,1.4856620467502613,-3.9843924672846254,3.7592082472943877,0.25690232149022774,-0.28338288377613985,3.5208902860547764,-0.531772071762221,-0.27309108327505216,2.8470650608106585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7333333333333334,1.0,0.0,1.0,0.0,0.51249393399897,0.02651672188152077,0.0031777451276433963,0.9877300285040645,0.09805565926475569,-0.06921368068246973,0.09991969217339602,0.6857148209047652,-0.18936238277122583,-0.19000829396656777,-0.5230738138926802,-0.4821441664680827,-0.9631969195151092,-0.49120712261521154,0.3928222944793597,-0.17923898741483066,-0.3354776023750488,0.5067005854260626,-0.9425238669393621,-0.3079408213079364,-0.8476671687812778,0.8538729905705987,0.25324233764525167,0.392775591775483,0.562231832279639,1.1732563310603084,2.504663228964912,-1.8352406930853522,1.5825580584747,-3.9697461188188976,3.870988256252732,0.2655923949829486,-0.19494991068537582,3.411593547064109,-0.5889373401149761,-0.5306139354148376,3.1756375593935893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7416666666666667,1.0,0.0,1.0,0.0,0.5186208620423584,0.026349409186588936,0.0022410913620502467,0.9882097118093225,0.0963161887556732,-0.07095879108166202,0.09554897821370674,0.6989098965112253,-0.19305916265057077,-0.19526807321477613,-0.5528998133136663,-0.44869996270552953,-0.9913665799710544,-0.4813070045284238,0.4138220751288328,-0.19468842059998134,-0.32189982041022697,0.4736714216070228,-0.9098154914401062,-0.30569481786453867,-0.8489153964395892,0.8818086429896627,0.2480817428482663,0.3873080225100482,0.5899609931867799,1.2015319411778436,2.5308900558040937,-1.8701206340712613,1.6729642674015621,-3.9586999102628475,3.9747497462134818,0.27279784853591504,-0.10305008424061679,3.2848206540883895,-0.6526770567870616,-0.7751317114029421,3.4547643074479106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.75,1.0,0.0,1.0,0.0,0.5248605746110075,0.026121711408533217,0.0012955844117339128,0.9886973648742605,0.09444679538197458,-0.0725528748497766,0.09106812770647572,0.7111456306219719,-0.19586832190674647,-0.19945122280681105,-0.5818734592932062,-0.4093638242974711,-1.0183218097639275,-0.4711815902622475,0.4350037954094279,-0.21040766464935168,-0.3075948645850228,0.44072225358834843,-0.876278037835804,-0.30339419049900446,-0.8493846701852881,0.9086200014720719,0.24236438669880064,0.3798567299187673,0.6198112374037709,1.2274123942735016,2.5491555876639618,-1.9007290145832578,1.7572485086870016,-3.949828018122792,4.069235641176164,0.27884116420813676,-0.00821057929946356,3.14267555634274,-0.7220741326341984,-1.0071210153782573,3.6855780019791995,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7583333333333333,1.0,0.0,1.0,0.0,0.5312042355404744,0.025833994036083937,0.00034897990004326097,0.9891925141776325,0.09244932323678637,-0.0739712800301507,0.08648434690095615,0.7228584447254165,-0.1978521674089926,-0.2025609234140233,-0.6099117326940946,-0.3641518710796477,-1.0440238796530266,-0.4608501312905321,0.4563080015898988,-0.2263672375097023,-0.2926123452654436,0.4078409546383096,-0.8419948974205035,-0.3010474651277364,-0.8490522394279136,0.9341865689287083,0.23604717397102967,0.3705226722537439,0.6513872932197665,1.2510432220597167,2.5607302707470083,-1.9281751869055448,1.8357421713672006,-3.9419352727444767,4.153006157558319,0.2839466014250236,0.08916400857203355,2.9865819026839624,-0.7961483837749794,-1.2279742577541264,3.8706725288446675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7666666666666666,1.0,0.0,1.0,0.0,0.5376455307633105,0.025487105736371706,-0.0005909583935358614,0.9896947449308395,0.09032616641427167,-0.07518948666516985,0.08180486912414628,0.7343312270845164,-0.19902631418657357,-0.20458526592288878,-0.6369157750079981,-0.31310523933775253,-1.0684514080676328,-0.45033086989458554,0.4776826332552114,-0.2425439177644441,-0.27699916172890277,0.3750233323759405,-0.8070612685431654,-0.29866174714192073,-0.8478986033757542,0.9583963665168046,0.22909524696921765,0.35939049228953185,0.6843224462178487,1.2724929398218976,2.5663541062134954,-1.9530281101120812,1.9087347327902349,-3.934106025829409,4.224580076323963,0.2882341990103132,0.18872492561247123,2.8173744209814022,-0.8738506344262092,-1.439725660923712,4.013609285452988,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.775,1.0,0.0,1.0,0.0,0.5441801557267483,0.02508250883418381,-0.0015164743908937118,0.9902036528956195,0.08808044024524087,-0.07618312109878457,0.07703696449259549,0.7457473269135434,-0.1993721558619263,-0.20549752514889336,-0.6627640947000568,-0.25628530255028803,-1.091587742236334,-0.4396419156268338,0.4990805700267904,-0.2589177060115703,-0.2608000997189397,0.3422725208744861,-0.7715852294817708,-0.29624356181089784,-0.8459068240010391,0.9811428092783984,0.22148299673059285,0.34652724457168205,0.7182807813106497,1.2917546161280657,2.5664050304934185,-1.9754741993784348,1.9764768180055214,-3.9255717773237855,4.282431263851978,0.2917409293991191,0.29015735841300794,2.6354857641204776,-0.9540093955888285,-1.644606213136438,4.118228398076951,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7833333333333332,1.0,0.0,1.0,0.0,0.5508046555910767,0.024622309184728342,-0.002419739367569884,0.9907188009826888,0.08571601729860841,-0.07692809848705907,0.07218787586044796,0.757159192609811,-0.19884071866255087,-0.20524183428654297,-0.6873266030136091,-0.19378500609761343,-1.113426487329051,-0.4288016262924511,0.5204560504301017,-0.27546848775408467,-0.24405788142881074,0.30959713608721073,-0.7356874141456324,-0.2937993983186021,-0.843062647402204,1.002321129252146,0.2131950903760705,0.3319803887372579,0.7529595861857978,1.308775298199123,2.560881785581144,-1.9953816754351172,2.0392125455793155,-3.915784060588956,4.325108352981711,0.2944426366130004,0.39311016969650225,2.440965276356677,-1.035329495758995,-1.844999359284849,4.18850867540878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7916666666666667,1.0,0.0,1.0,0.0,0.5575154000968178,0.024109291638344466,-0.0032927584383423336,0.9912396682656853,0.08323759100010296,-0.07740074024551861,0.06726476723096642,0.7685105229354968,-0.19736250084450674,-0.20373279966836452,-0.7104624051186763,-0.12572432793959148,-1.1339682022187274,-0.41782899399018175,0.5417619331198095,-0.2921740672688223,-0.22681322395928444,0.2770094531980035,-0.6995000902654089,-0.2913361845340145,-0.8393549878394307,1.021825563884343,0.2042275051346096,0.3157772552502679,0.7880892592341293,1.3234623268921841,2.54951309365844,-2.0124510057086376,2.0971848101785495,-3.904376079951154,4.3512704070014445,0.29627167957177347,0.49716572223192257,2.2335797101688692,-1.116380583373796,-2.043258135324977,4.228279362597975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8,1.0,0.0,1.0,0.0,0.5643078244619063,0.023546945992963236,-0.00412726537915465,0.9917655953400062,0.08065071984026183,-0.07757788235560296,0.062274693563858584,0.7796697618259053,-0.19485940586621164,-0.20085788705656304,-0.7320255371141924,-0.05224897080301269,-1.1532133414001529,-0.40674392084424804,0.562947935324409,-0.3090093378492286,-0.20910480125916825,0.24452420142135817,-0.6631662406956084,-0.28886153699240585,-0.834776552031672,1.0395474577549604,0.19458874731984058,0.2979260864818416,0.8234309088957641,1.3356984715196685,2.531867046742924,-2.026319325545729,2.150646886872267,-3.891076520999916,4.359674164423559,0.2971475071622054,0.6018377104956052,2.012919900758958,-1.195571768828545,-2.241521248147018,4.240970896133669,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8083333333333333,1.0,0.0,1.0,0.0,0.5711759995531046,0.022939474582838695,-0.004914605665236266,0.9922957265978875,0.07796183370565243,-0.07743699270797999,0.057224606781207846,0.7904481015575712,-0.1912549589639766,-0.1964796116511568,-0.7518731415839758,0.026469016586067734,-1.1711584574090328,-0.3955673527981873,0.5839597172321915,-0.32594605602791776,-0.19096910917808,0.21215817784800492,-0.626838854191683,-0.2863837260813111,-0.8293243593311707,1.0553742288969923,0.1843013089874672,0.2784185677811509,0.8587721075030238,1.34536011802731,2.5074229455586394,-2.0366394868804116,2.199876164054378,-3.875661275307022,4.349171085618093,0.29700564612604397,0.7065684520680793,1.7784704662520534,-1.2711489646016838,-2.4416230212884873,4.229508887609965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8166666666666667,1.0,0.0,1.0,0.0,0.5781122079445452,0.02229175882818286,-0.005645625699358495,0.9928289536058903,0.07517820398641176,-0.07695629307583564,0.05212135342952593,0.8006077605033858,-0.18648272575796898,-0.19043819206370588,-0.7698730028067374,0.11023188942117229,-1.1877936590245772,-0.38432125221045954,0.6047383177503863,-0.3429533292972355,-0.17244019852492862,0.1799298468329078,-0.5906800559353068,-0.2839114428903051,-0.8230004111638707,1.0691886321924946,0.17340293124314585,0.2572323694603668,0.8939227236892635,1.3523333848638996,2.4756210978640136,-2.0431496593076384,2.245184220705048,-3.8579420756328435,4.318725865805133,0.29582248788209253,0.8107282450657349,1.5296512537058415,-1.3412181388899653,-2.6450624590014327,4.196292769226713,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.825,1.0,0.0,1.0,0.0,0.5851066839362324,0.021609302917523287,-0.006310565274584519,0.9933638584740753,0.07230788119431851,-0.07611487645269495,0.04697169974968034,0.8098745497976326,-0.18049413357583297,-0.18255585684865996,-0.7859106911557079,0.19881852233106656,-1.2030971478621106,-0.3730284630504556,0.6252200688632584,-0.35999855034971173,-0.1535493721663292,0.1478591432541242,-0.5548600897615974,-0.2814533512832762,-0.8158122219134084,1.0808684164587563,0.1619476733393011,0.23433419346446038,0.928710320323469,1.3565281152610464,2.4359095527704855,-2.0457235078578595,2.2869221353696547,-3.8377562420428397,4.267440639217444,0.293640126176693,0.913632258454371,1.2658515224868694,-1.4037811381012644,-2.8529659197915636,4.143173242905265,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8333333333333333,1.0,0.0,1.0,0.0,0.5921474292080151,0.0208981455860283,-0.006898957028612087,0.9938986596541839,0.06935959728298893,-0.07489281540406863,0.04178237431412965,0.8181530776242176,-0.17317598172591156,-0.17036254100897585,-0.8001529435602363,0.30276692494081214,-1.217479495382137,-0.3617124502894421,0.6453368102965611,-0.3770487210948665,-0.13432482960210104,0.11596724279886048,-0.5195560452816828,-0.27901744078736024,-0.8077732068562978,1.0902861575672758,0.1500065789414581,0.20968293746384076,0.9629756110710179,1.358193279184764,2.3864132778992464,-2.0600422766433493,2.325234634880771,-3.819258018253834,4.180903328636652,0.2936599245808791,1.0216184989841892,0.9557921802616498,-1.4620497631811114,-3.0749071492504787,4.049872214246042,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8416666666666666,1.0,0.0,1.0,0.0,0.5992179427531396,0.020160989714841156,-0.007361612760146159,0.994438017341228,0.06633749895640743,-0.07318176072951275,0.03656221814004032,0.824913410324706,-0.16433755107617157,-0.15141025093897198,-0.8124730155924644,0.4323686484868533,-1.231873691678584,-0.3503919083973762,0.6649936234949125,-0.39433258829376755,-0.11479546158498301,0.08420484294989362,-0.4851783676176532,-0.2765590192069282,-0.7987852469303386,1.0967982861297838,0.13758017728628258,0.1830857409769524,0.996208190560903,1.3575224516991902,2.325434095537493,-2.1029443772089484,2.3609623033821507,-3.806845456702786,4.04310357865249,0.2985470369909693,1.1392417442528502,0.5691488433348146,-1.5188364208551497,-3.3219685022764978,3.898928362164913,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8499999999999999,1.0,0.0,1.0,0.0,0.606292783188426,0.019403337280386044,-0.0076521467919171355,0.9949851579311257,0.0632491614178207,-0.07087598511995037,0.03131571187343871,0.8288085380742686,-0.15394008221868058,-0.12816057858308358,-0.8221842475449075,0.57462517369654,-1.2463963604393664,-0.3390870760944556,0.684094045222186,-0.41209779404834895,-0.0949754578790652,0.05251981852048071,-0.4521709856374746,-0.27404165683751075,-0.7887858444520837,1.099771971622856,0.12469263859387228,0.15431679575923246,1.0279577504404331,1.3540776385700803,2.2538802546028402,-2.1579920041449276,2.3959416874220802,-3.796751881305716,3.8683317722162838,0.30414791664105545,1.2551803833297415,0.1413574702985132,-1.5653550074282094,-3.586574114304202,3.719765273971176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8583333333333334,1.0,0.0,1.0,0.0,0.6133412361869632,0.01863618166488924,-0.007767619867207736,0.9955340551749369,0.060109517945189456,-0.06797456558700903,0.026043219323786525,0.8289999053278753,-0.14221051222188597,-0.10361183142795695,-0.8290594312534909,0.713304367441044,-1.2600349529188724,-0.32782394775454154,0.7025582944049599,-0.430299121696183,-0.07486310012794833,0.02092564492813169,-0.4207061714140485,-0.2714898872629106,-0.7778655738748429,1.0991542439680924,0.11149092716247909,0.12330950573854904,1.0582042784604226,1.347704085915209,2.172269400208655,-2.2011791533104543,2.4313459732427507,-3.7845550496753786,3.6805311169845867,0.30666128100256596,1.3588713228578153,-0.2842122344682352,-1.590936328809981,-3.8543109715172394,3.5422816720743544,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8666666666666667,1.0,0.0,1.0,0.0,0.6203336069404792,0.017869833036360246,-0.007712616210945809,0.9960758027814212,0.056932975185073766,-0.06450688074470806,0.02074834419026828,0.8255185074818252,-0.1294948617073492,-0.07835951470656852,-0.8333543687962837,0.843687629311305,-1.2716603175544692,-0.3166253413292021,0.7202985352256636,-0.44878411327018985,-0.054453024991686014,-0.010556098974108929,-0.39082880035439815,-0.268930635487468,-0.7661379890711201,1.0950351010483854,0.09817703311370593,0.09007827956727847,1.086995778308339,1.3387302991323435,2.0804896301866793,-2.2248663721171726,2.4673390101672354,-3.7694391651616526,3.4906089224576955,0.3064471580685624,1.4493672197309637,-0.6968711524670468,-1.5912189436729953,-4.117087558839617,3.3697412844218944,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.875,1.0,0.0,1.0,0.0,0.6272433343520463,0.017113042368563983,-0.007492692199316403,0.9966006042395944,0.053732528913515626,-0.060512041337725295,0.015438387838893373,0.8185966345206832,-0.11613953910259592,-0.052617950746356223,-0.8353301694875059,0.964286802440184,-1.2804569974106277,-0.3055117761023358,0.7372331215747379,-0.4673802278981359,-0.033740783291827746,-0.041898341157895855,-0.36252935603975356,-0.2663824346284346,-0.7537094535459935,1.0875397247603082,0.08497061143459583,0.054691379757888764,1.1143666332007875,1.327428363721045,1.9798109829448474,-2.228795570514871,2.5038192375181336,-3.7506259631382983,3.3030054946966736,0.30454868773126975,1.527832786669996,-1.0940060745312774,-1.5654285757995234,-4.3694160165259985,3.1998448480510255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8833333333333333,1.0,0.0,1.0,0.0,0.6340469346538897,0.01637294242188206,-0.007113600170834155,0.9970986114960948,0.05051967601452287,-0.05603250040557657,0.010123249789172128,0.808510315861155,-0.10246723216919165,-0.02657380093863608,-0.8352619120448208,1.0745704412806247,-1.2859111476955394,-0.2945015352671847,0.753295384941411,-0.48593070611210437,-0.012722704366383782,-0.07306653169308057,-0.33577870877612026,-0.26385482402528015,-0.7406741092932868,1.0768016664728641,0.07208655685038054,0.01725467929184517,1.1403265257758561,1.3140938379167189,1.8721226637911914,-2.2152183738021205,2.540716330639134,-3.7271170301318595,3.119334964869388,0.301986605922816,1.595876494787174,-1.4749768652369788,-1.5149026497767613,-4.607165215529222,3.0296861085373106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8916666666666666,1.0,0.0,1.0,0.0,0.6407243112043266,0.015655189131641743,-0.006581165886079525,0.9975603498503445,0.0473043173017443,-0.05111232309726534,0.0048146026544452795,0.7955413538553597,-0.08876840937009275,-0.0004346698055267273,-0.8334314916948088,1.1742854495845225,-1.287738429974269,-0.28361021213705717,0.7684351659712577,-0.5043005341281712,0.008604488885491153,-0.10401695832676018,-0.3105404399585971,-0.261349324529721,-0.7271115119662073,1.0629567770063586,0.05972223393831648,-0.02209470716759827,1.1648614016764094,1.2990621747881215,1.7593839445412862,-2.18685141085604,2.578014034086402,-3.69775756471786,2.9399362604898696,0.29959780639944644,1.6552073455746075,-1.8395902747948334,-1.4422848408652407,-4.8270418339628955,2.8568391537638016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9,1.0,0.0,1.0,0.0,0.6472581660324003,0.014964092190088962,-0.00590154401035496,0.9979770028316719,0.04409489660452679,-0.04579646577615276,-0.0004750106775827893,0.7799329095043225,-0.07529950312464442,0.025564361448614778,-0.8301062161708495,1.2632747143528784,-1.285856402766778,-0.272850499020716,0.7826184506837658,-0.5223782296263717,0.03024419620172292,-0.13469582443837824,-0.2867797711012891,-0.25886152725195605,-0.7130873202003767,1.046141828559617,0.0480484761692932,-0.06319601794086975,1.1879405116719195,1.2826916840922875,1.6434405447948697,-2.146365857401038,2.615742136178532,-3.6613084643662956,2.7643380356985383,0.29797563637342095,1.7074486088567609,-2.1877158133549557,-1.3510345507290347,-5.026535105271043,2.679676206357806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9083333333333332,1.0,0.0,1.0,0.0,0.6536335762625519,0.014302773712123596,-0.005081392888692552,0.998340615479034,0.04089849309554929,-0.040130573688186684,-0.005732870446025596,0.7619033845591825,-0.062282522693502027,0.051168170746757724,-0.8255407198619684,1.3413983695295024,-1.280336631769748,-0.2622320174021857,0.7958258417178389,-0.5400732984181885,0.05220019115513335,-0.16503876606619844,-0.26446813936362146,-0.2563830639234973,-0.6986540351519279,1.026494846783776,0.0372049914261659,-0.105870292255449,1.2095226717823728,1.2653561214277642,1.5259463192569611,-2.096073269653387,2.6539489370796927,-3.6164528372339855,2.591564742879239,0.29748845904876253,1.754109941302735,-2.5191374486146723,-1.244962005072101,-5.2037362470634765,2.4972829508390904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9166666666666667,1.0,0.0,1.0,0.0,0.6598376125199915,0.013673304391646336,-0.004128044937260131,0.9986442481420426,0.037720907875403165,-0.034160942244359976,-0.010946633663278929,0.7416542734771937,-0.0499088357725628,0.076105070773551,-0.8199765063587187,1.4085095949927864,-1.2713692182714926,-0.25176123033025327,0.8080508893380485,-0.5573127841205948,0.07447667848638446,-0.194970038392278,-0.24358702538663513,-0.25390338626781,-0.6838521545119978,1.004156204416039,0.02729910941809151,-0.14992495539192768,1.2295618941859043,1.2474383094523656,1.408365413803987,-2.037867464850447,2.6926792981207948,-3.56175192428137,2.420187742922505,0.2983126451647178,1.7965418055916804,-2.833478191215546,-1.1278690635215691,-5.357244212738758,2.309370904538155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.925,1.0,0.0,1.0,0.0,0.6658590354029956,0.013076803120106908,-0.0030496683380494033,0.9988820955638521,0.03456671898593891,-0.027934533851298387,-0.016104748457018172,0.719379814371671,-0.038344083338246196,0.10009047754017977,-0.8136454928144716,1.4644491270582525,-1.259229562616297,-0.24144137891131295,0.819298598614572,-0.574037756165696,0.0970781794571466,-0.2244012981375546,-0.2241316769815797,-0.25141118650408534,-0.6687116717253999,0.9792702102635169,0.018407173700806415,-0.19515769580109496,1.2480121868580087,1.2293290615704984,1.2919970450690244,-1.973236213733256,2.7319538402384524,-3.495598520518505,2.248320968674115,0.30047936881885007,1.8358954178338105,-3.130147705950832,-1.003278180456991,-5.486091674163488,2.116179041935191,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9333333333333333,1.0,0.0,1.0,0.0,0.6716880654054742,0.012513494376886003,-0.0018554133590066187,0.9990495792351095,0.03143930045861848,-0.021498998448099816,-0.021196737724317644,0.6952751433514535,-0.02773311094001689,0.122831444780126,-0.8067742691927808,1.5090493052794143,-1.2442492057258305,-0.23127241263741163,0.8295841734225322,-0.5902000543494824,0.12000924249035867,-0.2532300137342531,-0.20611500924206655,-0.24889539678749584,-0.6532538975481009,0.9519870759835252,0.010577806410474996,-0.2413598166279858,1.2648315448848242,1.2114283550595846,1.178002478625182,-1.9033004493869732,2.7717479734567836,-3.416181023319844,2.073598461350871,0.3039241017115457,1.8730845919343508,-3.408301105522553,-0.8742533885854028,-5.589693117500453,1.9183801997788352,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9416666666666667,1.0,0.0,1.0,0.0,0.6773162079165016,0.011982727267038367,-0.0005555352267842981,0.9991434171794445,0.028340812076979426,-0.0149026651679798,-0.02621337182390681,0.6695420298174078,-0.018204042150312516,0.14403216707635733,-0.7995872635519448,1.5421440034295912,-1.2267926795629014,-0.22125090632698655,0.838931973258325,-0.6057594303221455,0.14327397901475966,-0.2813376485262187,-0.18957170262573186,-0.2463457848088929,-0.6374935951931607,0.922465191838141,0.003836283891049703,-0.28831924775943585,1.279985190187656,1.1941462606121052,1.067427502777727,-1.8288647442273298,2.8119715065684967,-3.321469028560331,1.8931607042055942,0.30853082351635863,1.9087488136066244,-3.6668038045960127,-0.743306758616205,-5.667812443702747,1.716992510354154,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.95,1.0,0.0,1.0,0.0,0.6827361163309217,0.011482967022169223,0.000838514217093196,0.9991616722354683,0.025272172686736503,-0.008194484123635638,-0.031146757071221935,0.6423926817046961,-0.009870962982588154,0.16340026313918218,-0.7923078388494279,1.563581975606242,-1.2072409779848645,-0.21136997496054322,0.847374631802161,-0.6206811334199379,0.16687543426650028,-0.30858783087692526,-0.17456233083863998,-0.24375321639555653,-0.6214414173213239,0.8908736792402583,-0.001810639566461754,-0.3358233573563649,1.29344808672406,1.1779017316663316,0.9612185012090202,-1.7504690006332102,2.8524497682283267,-3.2092268383548697,1.7036708565710652,0.3141662520412708,1.9432185206421004,-3.9041979142453354,-0.6123750911428002,-5.720541820327224,1.5132914771054784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9583333333333333,1.0,0.0,1.0,0.0,0.6879414872953905,0.011011773141407074,0.002314032576292027,0.9991037775538224,0.022233031819189838,-0.0014239078538195846,-0.03599036670662702,0.6140529296263848,-0.002834971047050952,0.18065362064021437,-0.7851570637801777,1.5732413420293887,-1.1859806424464223,-0.20161921079921435,0.8549522816118087,-0.6349339136660324,0.19081480848523177,-0.33482476249879983,-0.16117718834954745,-0.24110968060820506,-0.6051066198491257,0.8573952266007188,-0.006369967627996966,-0.38366161143155625,1.3052067148060806,1.1631179786734476,0.8602319345287679,-1.6684325550205914,2.892906299697564,-3.0770583829176914,1.5013794815561432,0.32070260437537135,1.9764843813732602,-4.118665569040767,-0.4828473731143594,-5.748279853480845,1.3087184508510274,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9666666666666666,1.0,0.0,1.0,0.0,0.6929269971486923,0.010565778513105962,0.0038570558223967166,0.9989705367857272,0.01922175311174273,0.0053592874708773735,-0.040739034487068754,0.5847663481278907,0.0028164689534525694,0.19552771760386362,-0.7783504199841426,1.5710429928273566,-1.1633962863253817,-0.19198467531598576,0.8617118307109738,-0.6484883426702811,0.21509053926145968,-0.3598721372588868,-0.14953933947937093,-0.23840817298930034,-0.5885000109651028,0.8222292530895788,-0.00985809578503441,-0.4316280215810457,1.3152600609049105,1.1502136589115897,0.7652373545257762,-1.5828823970304229,2.9329458516744915,-2.9224854617188223,1.2822540870426797,0.3280297724767228,2.008172351152715,-4.3079848860494945,-0.35562381064898113,-5.751696772761191,1.1047842491992599,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9749999999999999,1.0,1.0,1.0,0.0,0.6976883029492924,0.010140681841452162,0.00545239410710695,0.9987640964979783,0.016235419988931188,0.012105230962641675,-0.045388920884469844,0.5548006381662749,0.007011815465793353,0.20778348145602352,-0.7720929571096917,1.5569609062768486,-1.1398639852188364,-0.18244898315068786,0.8677062375205716,-0.6613152869498727,0.2396972393464733,-0.38353285352744687,-0.13980628689883612,-0.23564251773359302,-0.5716370806632471,0.7855954784998939,-0.012297031138813318,-0.47952322431090943,1.3236197856260683,1.1395894337219044,0.6769140110392069,-1.4937587108184136,2.9720352364915485,-2.7430594790578366,1.042184644059987,0.3360589894665861,2.0375255379596457,-4.469475008186839,-0.23119070208202686,-5.7316773714310045,0.9029710176757533,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9833333333333334,1.0,1.0,1.0,0.0,0.7022221414872437,0.009731262610299161,0.007083717263175414,0.9984878896054528,0.013269870785830185,0.018764217766616305,-0.04993745152844073,0.5244569958448977,0.009699274338082778,0.21721576817964758,-0.7665733871656738,1.5310279550862724,-1.1157433853332344,-0.17299151808728735,0.8729937308949606,-0.6733843211839213,0.26462445986965216,-0.40558979524318406,-0.13216959541170448,-0.2328071898315239,-0.5545412519991088,0.7477380029531315,-0.01371127415306819,-0.5271559777715624,1.330309577866173,1.131609619754479,0.5958413496657644,-1.400794360399864,3.009479216601766,-2.536503117790263,0.7772647425480916,0.34472014597841716,2.063392653972329,-4.599927972795679,-0.10970041286084434,-5.689238336307077,0.7046397546521099,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9916666666666667,1.0,1.0,1.0,0.0,0.7065265627562269,0.009331424553156309,0.008733690631623287,0.9981465506340347,0.010319768136229732,0.025286978953274617,-0.054383220327852644,0.49408236406287875,0.010851986762145618,0.2236623610488857,-0.7619573862651177,1.4933368081875924,-1.0913674991440239,-0.16358882282144654,0.8776369266816677,-0.6846618596232038,0.28985522628983607,-0.4258079054906179,-0.1268518745230346,-0.22989718196728606,-0.5372472030970417,0.7089300122866325,-0.014125371353160724,-0.5743438632493607,1.3353637815369368,1.1265788063254263,0.5224845486433649,-1.3034704166715727,3.0443897104259876,-2.3008712708203207,0.48412806624181376,0.35395420611110506,2.0842215197056957,-4.695527358593091,0.00894912058039269,-5.625424190848507,0.51095395081731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0,1.0,1.0,1.0,0.0,0.710601329057603,0.008934270763214732,0.010384157915897849,0.9977458057066314,0.007378706652404099,0.03162493904632583,-0.0587258482101342,0.35882914803540406,-0.009075064374010997,0.2429048938838833,-0.7794704273063224,1.3812618863867263,-1.1029598150060758,-0.15421520464853025,0.8817018067056833,-0.6951088281284475,0.31536428837675196,-0.44393764975685607,-0.12410079430767425,-0.22690795306300549,-0.5198042266706805,0.6694792136432467,-0.01356212214339498,-0.6209130476190375,1.3388254770464616,1.2152186524076025,0.34480831603121764,-1.366882908125393,3.047152199985489,-1.1866784828284527,-0.692189409421281,0.3965129477768553,1.9402829997033844,-4.685996602274929,0.15842202260957794,-5.8115253147474215,0.4590225129653147,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0083333333333333,1.0,1.0,1.0,0.0,0.7126880166163133,0.008408542587445103,0.012389306269566776,0.9972938136217915,0.0042197423609349576,0.037221166439207615,-0.0632600045660294,0.23294886913489604,-0.026860517675454804,0.24478817454271998,-0.7775029620807192,1.291747444544522,-1.1046675659667686,-0.14333517861465317,0.8833837319488547,-0.7074432414252937,0.3406410962895942,-0.44558588020442547,-0.13838836468005594,-0.2232886328376718,-0.5049091531019853,0.6308300689153837,-0.011485004309667758,-0.6712026184951511,1.3430141567530254,1.2723293078533193,0.31281659943502405,-1.7616004296889876,3.0082261310476124,-0.10915183321126176,-1.8930188257675804,0.4157887506620067,1.7711425070580988,-4.6360028215772875,0.2857982288282028,-5.977063645434571,0.3818951859311337,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0166666666666666,1.0,1.0,1.0,0.0,0.7146860612539554,0.007947980848611208,0.01416053977318376,0.9967914736033822,0.0012563619466830693,0.04280867207616164,-0.06762098531749537,0.22930338311112675,-0.020394901482947717,0.22357927849415704,-0.7431557032019753,1.274958499436678,-1.063017488847625,-0.13300971618430826,0.8869154166962671,-0.7244688352899307,0.3655013905608788,-0.44575684697704376,-0.15565110807046725,-0.21997814055197204,-0.49028518488637884,0.5922124999502919,-0.008798818329591599,-0.720530775042947,1.3451903968119805,1.2212960864643485,0.5090666682111156,-2.22415568169142,2.955315494815484,0.02081783502844381,-2.084696656973992,0.38950490078023203,1.7644586778994942,-4.617068414411394,0.3669873520948739,-5.809907370263552,0.1263626612305524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.025,1.0,1.0,1.0,0.0,0.7167323031196958,0.007526042487517008,0.01577626951906973,0.9962495736344545,-0.0016137959441652667,0.04824169399538297,-0.0718117121189947,0.2354567614613778,-0.014844658212864084,0.2089233298690814,-0.7216042309572107,1.2266902999756613,-1.022784563732342,-0.12298024384024736,0.8918681764190399,-0.7445125027868174,0.38989635453651894,-0.44523891628728474,-0.1731333089629558,-0.2167968844913346,-0.475501508470327,0.5538789286751938,-0.005368548441419861,-0.7680344079995436,1.345120201106868,1.1910525528545952,0.6630276598590834,-2.5300097674693944,2.891026642555673,0.09594063715512968,-2.056460510245537,0.374542544471243,1.7834300846372508,-4.552587458073492,0.45482314124273215,-5.5746476601167165,-0.13143768751898044,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.033333333333333,0.0,1.0,1.0,0.0,0.7188517459249483,0.007128077872697102,0.017252581410548667,0.9956788364758248,-0.004411715916216557,0.05341100223392284,-0.07583835773845364,0.24408780714348238,-0.010164289138726836,0.19525133164745195,-0.7020670745474963,1.155433247707427,-0.9839971912960586,-0.11315884030339834,0.8979658776939184,-0.7666356647477539,0.4136851679368067,-0.4441578363577916,-0.18992544990789287,-0.21373576481078466,-0.46056135014242466,0.5163360423157337,-0.0012184326422127292,-0.8134415693782256,1.3429997686866642,1.1689389688054748,0.7911063291413911,-2.7437670797716596,2.8095899020349204,0.16606237491139764,-1.9531696948093142,0.35926400988073093,1.7937482061394938,-4.421966838180389,0.5387179586322214,-5.3154429792346285,-0.36282963143088764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0416666666666665,0.0,1.0,1.0,0.0,0.7210532178100075,0.006744527637030386,0.018584659908152616,0.9950901592019308,-0.007147363055894453,0.05823645952750417,-0.07970574198508497,0.2544203732182299,-0.006062454976534938,0.1808730455641188,-0.6831619639468918,1.0663519890263533,-0.9465112453257144,-0.10349792769348945,0.9050532819047298,-0.790241954116345,0.4367228529037676,-0.44247121003876144,-0.20568613720977771,-0.21080915099332243,-0.4456057050346688,0.48017948137218736,0.0036100842024504964,-0.8566251243201207,1.3390730405830198,1.1517717405217442,0.9035547972534519,-2.893433432539587,2.7105603983148807,0.24578944932322266,-1.8226047372453125,0.3419990502600956,1.7834924565211852,-4.215865149649969,0.6176248284410805,-5.043698749596269,-0.5652149903608583,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.05,0.0,1.0,1.0,0.0,0.7233463260051356,0.006367056000398009,0.019762123338984684,0.9944946272712244,-0.009828671895314724,0.06265132366824769,-0.08341849551689356,0.26678796396907417,-0.0023592957512151846,0.1653666361334791,-0.6646139477334623,0.961883462417527,-0.9103733368120388,-0.09396264462803594,0.9130251243148093,-0.8148595552900804,0.45886117457538805,-0.4400613455357379,-0.22030219552864808,-0.20803578063978306,-0.4308364758670716,0.4460716231549009,0.009075314498471945,-0.8975032152048301,1.3335795188473165,1.1383729806594722,1.0050356592982435,-2.990057421763501,2.593489548681404,0.34187869999510845,-1.6848233253767781,0.3223655303506756,1.7462942239988388,-3.92591218094841,0.6916353069238066,-4.763434641447575,-0.7392493991391591,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.058333333333333,0.0,1.0,1.0,0.0,0.7257443850455093,0.005987605001834507,0.020772985845921656,0.993903374534139,-0.012463052994825656,0.06659580778291671,-0.08698133679924565,0.28162469828813474,0.0010883422230193798,0.1486213493037767,-0.6463126031890399,0.8433644859244579,-0.875643424322908,-0.08452504468249825,0.9218038762263672,-0.84007624447907,0.47994767871512434,-0.43677323170550963,-0.23376652596605735,-0.2054363921541445,-0.4165008013013548,0.41474761168971386,0.015137339317847272,-0.9360157016775803,1.3267522172640338,1.1279977867588253,1.0984599431488862,-3.0397639851662017,2.457985712479669,0.45749994876081335,-1.5492536456674906,0.3001367467414223,1.6769064804874945,-3.5431836777309944,0.7609719942183512,-4.477024095357829,-0.8854062280413277,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0666666666666664,0.0,1.0,1.0,0.0,0.7282637978649167,0.005598234469414826,0.02160456607937949,0.9933273800906095,-0.015057733332686955,0.07001441766022436,-0.09039890525057555,0.2992326630844135,0.004399083051853783,0.1305628804439007,-0.628189206701551,0.7116099291845888,-0.842332823556245,-0.07516268151538885,0.9313327900339574,-0.8655222883761837,0.49982760311671587,-0.43243634638972434,-0.24612308962310625,-0.20303350152742602,-0.40288803452561334,0.3870185618593843,0.021758181068777797,-0.9721202834607939,1.318822748379961,1.1200291166627998,1.1861442248777165,-3.0473075931831617,2.30398608505487,0.5936818153254098,-1.4201312638153107,0.2750954710807124,1.5705720438093218,-3.0589307134120127,0.8258700024377212,-4.186652667632225,-1.0034587977496612,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.075,0.0,1.0,1.0,0.0,0.7309228037365686,0.005191065614277699,0.02224347535711116,0.9927772635968045,-0.017619942333509532,0.07285424912314985,-0.09367550899738845,0.3197629554729895,0.007658769103902625,0.11105512865356973,-0.610216454122289,0.5670165231479548,-0.8104020769073625,-0.06585789273811825,0.9415729466409958,-0.8908647043654561,0.5183474467993722,-0.42687853478341947,-0.2574353803629792,-0.20085146763613262,-0.39032460057119944,0.363765433132847,0.02890183935847596,-1.0057932461381174,1.3100279039682061,1.1139549044948756,1.27013395869912,-3.0168339891621176,2.131898182104707,0.750106366674469,-1.298484164989151,0.24701955948084942,1.4235847992119188,-2.465872978860122,0.8865924995780673,-3.8946661578532438,-1.0922758833348434,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0833333333333335,0.0,1.0,1.0,0.0,0.7337403456970558,0.0047581162940607685,0.02267514446598281,0.9922631102717255,-0.020157231455520695,0.07506319467344214,-0.0968148897293682,0.3410908377792787,0.01054111361881075,0.09379224014940196,-0.5949173475324233,0.4314036396184816,-0.7785930416427067,-0.05659676644047426,0.9525016893456094,-0.915802854862219,0.5353592394851276,-0.4199345736118165,-0.26776449237292543,-0.19891650886941187,-0.3791616212054147,0.3459206788783823,0.03653472272841225,-1.0370313860916813,1.3006181503243803,1.112119808569293,1.3437437029922683,-2.9809230896040995,1.9589032095541925,0.9048834774646064,-1.1982622457449743,0.222968201779139,1.2706840140649789,-1.8751827930049592,0.9431449290395465,-3.5782358585354412,-1.2021417940022072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.091666666666667,0.0,1.0,1.0,0.0,0.7367092059294013,0.004293684044795991,0.02295355761742157,0.991780847406708,-0.022679492355106162,0.07677106621245314,-0.09981279861889968,0.3599758669648344,0.012799283401686908,0.08431250132756614,-0.5846321226517623,0.33662846741062713,-0.7455953913793741,-0.0473225625952967,0.9639686750242002,-0.9405467558588577,0.5509958336252754,-0.4117971434923427,-0.2774064177920621,-0.19713533093981364,-0.36914653367011646,0.33251238658276433,0.04462092150913507,-1.0654305104470414,1.2899922074015027,1.1167108720719368,1.3950132316624786,-2.9830789315390294,1.8106244173836727,1.0273096840745177,-1.1411216117680467,0.21169155264290918,1.1734891954854942,-1.4703571337398624,0.9939274469186127,-3.2135454742772263,-1.4001562207750284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1,0.0,1.0,1.0,0.0,0.7398115183850706,0.003799925657933436,0.023163020464145118,0.9913180365807266,-0.02518675200207982,0.07819112525716411,-0.1026660889572446,0.37678448344786186,0.01515587618742529,0.08140626799258316,-0.5762330244410467,0.27637918411035606,-0.7126267072452883,-0.03798491857260865,0.9757519098733174,-0.9655208370545362,0.5655363131081889,-0.4028127455439079,-0.2867831859023929,-0.19538831632536338,-0.3596034679473231,0.3214147266493846,0.0531001801770558,-1.090590477329635,1.2772822133114632,1.1238382952595365,1.425329103092614,-3.0136042226232496,1.684344077220723,1.1231656376402732,-1.121939275421474,0.20764451657503902,1.1363098779079317,-1.2464175784253773,1.0360817804985993,-2.8259599471480135,-1.6596617621190735,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1083333333333334,0.0,1.0,1.0,0.0,0.7430475502929811,0.00328363277803134,0.02333431046100162,0.990870877412643,-0.027668051103713204,0.07939797576643336,-0.10538189928499692,0.39333071742369613,0.018136872196747672,0.08102084316246096,-0.566805213022226,0.22828018018697008,-0.6810061375790962,-0.028591924340971093,0.9877241600757438,-0.9907734929025785,0.5790682349122874,-0.39307771619833815,-0.29610540571575333,-0.19367458899689632,-0.35020803570498427,0.3117387602756747,0.06188895118411172,-1.1125298428995083,1.2623311780328514,1.1302288136807055,1.4425916109050196,-3.0428254932949783,1.5651642733644722,1.2112470888318083,-1.120404981192954,0.20285027700674252,1.1268702733750868,-1.0963613024449648,1.0687653279000897,-2.4438072126087462,-1.9238078141518722,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1166666666666667,0.0,1.0,1.0,0.0,0.7464209223164375,0.002748620632812332,0.023479384849322046,0.9904389150745595,-0.03011748407557655,0.08041711940467121,-0.10796656690828683,0.4101725041492976,0.02154654957404749,0.0816560330224037,-0.5566233984463891,0.18405860522970172,-0.6505811087550287,-0.019147771677930223,0.999795103388401,-1.0162345952761191,0.5916223843309301,-0.38262529406337775,-0.3054566022556088,-0.192007478375251,-0.340822296724405,0.30314203827530184,0.07091293564205729,-1.1313205975397809,1.2452187497422653,1.1364674306254368,1.4500637953389584,-3.0612614970418295,1.4484553405264644,1.2967363557958456,-1.125577815797425,0.19658028589346843,1.1292992497821963,-0.9739161476661329,1.0933176470701034,-2.0719161934676578,-2.1731656038379965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.125,0.0,1.0,1.0,0.0,0.7499366693200423,0.0021961139107547246,0.023602987759741238,0.9900230793838868,-0.032532959194258325,0.08125492239304608,-0.11042439242386079,0.4275888812327504,0.025184276791427776,0.08261782214424672,-0.5459746863333661,0.13984235821667493,-0.6209197284947043,-0.009650800497213813,1.0118918899980598,-1.0417945178532757,0.6032091572543952,-0.3714654436017407,-0.31486503597904375,-0.19039825089867185,-0.33138638154194766,0.29550682448123916,0.08011091196861345,-1.1470617794573026,1.2261117513022182,1.1429399382726861,1.4495096053309475,-3.0652533785673963,1.3319233104873396,1.381981810030204,-1.1322012290705186,0.18904921822417708,1.1359171608480967,-0.8568999971612523,1.1110714635198236,-1.713335588100926,-2.3991472168354777,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1333333333333333,0.0,1.0,1.0,0.0,0.7536004918456218,0.001625374248700932,0.02370531493777182,0.9896253770374005,-0.03491400312893164,0.08190517595307273,-0.11275711801026055,0.44567241993226064,0.02892325988895164,0.08356982821217934,-0.5350326111656015,0.0938653652439568,-0.5916540066094244,-9.877270671878737e-05,1.0239535968105835,-1.0673221515855758,0.6138211061723857,-0.3595922638962077,-0.3243266227401174,-0.18885665807151472,-0.3218903440436034,0.28886037165594763,0.08943079336738768,-1.1598761906747963,1.2052329627950074,1.1497412460585978,1.4419130636619526,-3.0538693935254813,1.214546905715368,1.467778244340473,-1.1374566906987993,0.18054519089244658,1.1430669980871022,-0.7349757930587875,1.1229264778095138,-1.370210189208274,-2.5982976846568517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1416666666666666,0.0,1.0,1.0,0.0,0.7574175902265583,0.0010350631827232774,0.02378586445537224,0.9892478948399734,-0.03726132379020276,0.08235987272600034,-0.11496541944827576,0.4642700918370377,0.032744505170869895,0.08456810625024293,-0.5240575800577997,0.04679192297913018,-0.5628386424780053,0.009511553603762817,1.0359237743924257,-1.0926923410787004,0.6234516056829846,-0.34700247286273284,-0.3338226474906904,-0.18738916438379774,-0.3123352649071626,0.28325722793025937,0.09882635326543868,-1.1698986159441072,1.1828067898912706,1.1570258081913418,1.4273750757052373,-3.0291251859419788,1.0975633312445643,1.5527580135921304,-1.1402453406071578,0.1714082905979636,1.1516643841866192,-0.6114998155833307,1.129276639350172,-1.0431814878952173,-2.7733981693996057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.15,0.0,1.0,1.0,0.0,0.7613913410000221,0.000424861733979226,0.02384660497375391,0.9888917442337883,-0.03957604756106591,0.08261846930117758,-0.11705145524989843,0.4832026682922392,0.036649325263548194,0.08563910111736563,-0.5130209788417145,-0.0009272057863845273,-0.53457832198037,0.019184990763136907,1.0477431814056708,-1.1178075713512754,0.6321138283597951,-0.3337129636696722,-0.3433307117502367,-0.18599985322821533,-0.3026959376404931,0.2786687080628921,0.10825207068989055,-1.1772625488063833,1.1590096599716806,1.1646361476679565,1.4058913073038548,-2.9925751899846054,0.9818408194905981,1.6357119571328949,-1.1393873751624084,0.16162563118827966,1.1627539860847225,-0.48972125635511343,1.130210008068948,-0.7327558535854273,-2.9267314543005662,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.158333333333333,0.0,1.0,1.0,0.0,0.7655242091723565,-0.00020569278535302604,0.0238882815632004,0.9885582717523708,-0.04185836130485446,0.08267658620359288,-0.11901681827621367,0.5023861764549333,0.04060269716844454,0.08664015280552868,-0.5017486400608011,-0.049906335570992236,-0.5067670600600495,0.028922156064895423,1.0593552961808232,-1.1425685942451105,0.6398156193411613,-0.3197406069105179,-0.35281243707673055,-0.18469540386399308,-0.2929560318057506,0.2750952069910075,0.11766318673325447,-1.1821112135038643,1.1340279323195945,1.1722200506027223,1.377712631959418,-2.9443385052285764,0.867081692058882,1.7164219768702305,-1.1331550803123736,0.15105353233447694,1.1755446972769734,-0.3672010479407717,1.1259579029181763,-0.43980049218165895,-3.057777792925389,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1666666666666665,0.0,1.0,1.0,0.0,0.7698177459216844,-0.0008571125080007174,0.023911234450249497,0.9882488119041851,-0.044108499503862225,0.08252844595902811,-0.12086265613954673,0.5229196446098747,0.044816808177369244,0.0884677840599825,-0.4882029531990584,-0.11405894137994602,-0.48066113207952393,0.03872199160651561,1.0707050586049944,-1.1668798797717517,0.6465651898941098,-0.305105930721835,-0.36221662975544294,-0.18348229435597405,-0.2831035260192102,0.2725486905972126,0.12701803573852682,-1.184592557009411,1.1080466967562574,1.1771577549922823,1.3385866685420789,-2.8533450552084316,0.738641781358329,1.796208472322257,-1.084609413523252,0.13538396722283685,1.185420847148806,-0.20454226841241097,1.1141908376233003,-0.1637799917158711,-3.1460693241062954,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.175,0.0,1.0,1.0,0.0,0.7742954216181199,-0.0015297551005395654,0.02392820583542534,0.9879733766826281,-0.046324989951043886,0.08205250949865038,-0.12259685133553518,0.5462563865318755,0.04933860609827702,0.0917163431104754,-0.47098498197971694,-0.2101418095415841,-0.45745414011001256,0.04854145198143346,1.081665073989858,-1.190124345165251,0.6521263156971334,-0.2898037990384803,-0.3708892606354514,-0.18243900441027913,-0.2731990176866038,0.27168616918413396,0.13623303402697615,-1.1848408800324621,1.0815934435844896,1.177326904852317,1.2854571358667988,-2.6854315114071037,0.5805139159054873,1.8766532337797581,-0.9504486728964678,0.11055603441325224,1.1837627510501336,0.052177170946091644,1.093780761584476,0.09401407881779456,-3.1634058843203583,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.183333333333333,0.0,1.0,1.0,0.0,0.7789839005170935,-0.0022285574736551224,0.02394820505947917,0.9877433156186722,-0.04851452850631382,0.08110309661334868,-0.12422467828188655,0.5714464345384321,0.053581897649093393,0.09469651082017408,-0.45308503290354524,-0.32783629315450846,-0.4355172281203314,0.05834410668738756,1.0921293442027744,-1.2116370716285367,0.656240421825868,-0.2738283768255057,-0.3780574409703841,-0.18163969378241984,-0.2633741468350413,0.2734183101129808,0.1452477150982681,-1.183025655695781,1.0553232653509181,1.1758095256390657,1.2251144146536896,-2.4712353475280535,0.40739954041400184,1.955244563938685,-0.7580051219009198,0.08159850677621039,1.1693361029639349,0.38305009695613124,1.0698758245604663,0.32876703666135043,-3.120072685200408,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1916666666666664,0.0,1.0,1.0,0.0,0.7838843054390576,-0.002961234493599318,0.02396356981889286,0.9875606108842715,-0.05068906445265094,0.07964718425335894,-0.12574173776194744,0.596563597374493,0.05719499331643732,0.09596743893165292,-0.4366530364506621,-0.44909218975512255,-0.4131634994805629,0.06813827740875122,1.1020836475674194,-1.2313116009573852,0.6589163080373668,-0.2572163896395022,-0.3835226793338001,-0.1810790292973423,-0.2537100826372049,0.27807033746673615,0.15406429776965058,-1.1793614294214396,1.0295922321644828,1.174895329193283,1.1630727696972398,-2.253689140783357,0.24028018777522808,2.027154827107751,-0.551087654966621,0.053552113585484395,1.1511016788435398,0.7309929689521388,1.0459326639102107,0.5382198157510221,-3.0427574624819087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2,0.0,1.0,1.0,0.0,0.78898712345628,-0.0037318638364105556,0.023967246090063815,0.987423434626192,-0.05285374605874867,0.07769043164918164,-0.12714416663310427,0.6207614975869215,0.06023751972574669,0.09534564443498207,-0.4210351857331983,-0.5685120736097696,-0.389848018209465,0.07792569550727561,1.111513890364395,-1.2491985573082593,0.6602450916221217,-0.24004246304037652,-0.38724223521982776,-0.1807471585559951,-0.24418911885431563,0.2856015262621831,0.16267992616343827,-1.174055325433264,1.0046106409762197,1.1734817959173285,1.098943909486878,-2.04352153962704,0.08450741604623113,2.089532303565506,-0.34047371706841467,0.026565937186757704,1.1371482229605367,1.0683729273849318,1.021495414464516,0.7228851796306746,-2.9411973151673543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2083333333333335,0.0,1.0,1.0,0.0,0.7942799433545649,-0.004543623895951122,0.02395167240829638,0.9873293649168398,-0.05500919843970661,0.0752437547999325,-0.12842542825948075,0.6437807849747339,0.06272678332761397,0.09278413532233216,-0.4057098406428043,-0.6849469329127654,-0.364958922799388,0.0876963073407067,1.1203993793922007,-1.2653702932845026,0.6603247649714706,-0.2223908512467438,-0.3891972412849403,-0.180636263677563,-0.2347576122545293,0.2958765529231517,0.17108922134405918,-1.1673133430942617,0.9805722769116936,1.1705640788528524,1.0318013745667187,-1.8423485014140573,-0.059174172558436045,2.1411332970776797,-0.127646885926731,0.0006389193754863243,1.1314564298110352,1.3851411699562288,0.9965107680857699,0.8834345555613243,-2.8175725445169464,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.216666666666667,0.0,1.0,1.0,0.0,0.7997494592229993,-0.005398969703023668,0.02391039110187098,0.9872753375395716,-0.057154567206534244,0.07232195881599887,-0.12957738076787167,0.6651842639755545,0.06488064460212047,0.08885542982488892,-0.39089050453645907,-0.7944453716375942,-0.339205393870949,0.09743509682148982,1.128710579940507,-1.2799043656651603,0.6592588554128145,-0.20435690808908186,-0.3893696833186066,-0.180736509899737,-0.22533151169079838,0.30868721242812025,0.17928843896486776,-1.1593314161739086,0.9576510985676039,1.1663080542093696,0.9596432147311251,-1.6536380262171901,-0.18704149221456356,2.1782308665466865,0.08576750943806499,-0.024169185190273113,1.1416910113574719,1.6582192934727846,0.9705369057261681,1.0237771766854609,-2.6834107076303426,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.225,0.0,1.0,1.0,0.0,0.8053792317878532,-0.00629447132009978,0.02384616180675153,0.9872545910754243,-0.05928825428438601,0.06896834351697469,-0.13060108306214174,0.684643904330379,0.06692337705739353,0.08414095035440675,-0.3764445827399773,-0.8937337056421295,-0.31340348313646343,0.10713477491086286,1.1363934329710528,-1.292930927054789,0.6572074067678946,-0.18608700347096568,-0.3877677827943059,-0.18103908343073422,-0.21572942873190476,0.3235135411476981,0.18726483643949532,-1.150250390149504,0.9358487651178545,1.1606140607530346,0.8806896030267319,-1.4795074246295181,-0.296738120229072,2.1982266609488494,0.2979653273542593,-0.048209698807434864,1.1733975900882332,1.8697986795829868,0.9428553556539837,1.147732424218102,-2.5490600864525126,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2333333333333334,0.0,1.0,1.0,0.0,0.8111535743945701,-0.007226404988231076,0.023761685188709643,0.9872607564107378,-0.061405182691891505,0.06522415603555047,-0.13149681311491276,0.7022370685185704,0.06889532418694835,0.07871362048769485,-0.36189519686018157,-0.9829705243267671,-0.2873375121795695,0.11677866450070706,1.1433887399909526,-1.304562822742319,0.6543132200756633,-0.1677197970732677,-0.38440359452936895,-0.1815400048798609,-0.20577488518932782,0.33985052375450336,0.19500269489243416,-1.1402025424369402,0.9151667637933953,1.152742000762598,0.7945362329441874,-1.318384494336624,-0.3899272954551858,2.2020530550995527,0.508086979056751,-0.07171938533079736,1.2252058099544272,2.022621881859862,0.9134220170326274,1.2564646259455792,-2.4151034074967326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2416666666666667,0.0,1.0,1.0,0.0,0.8170579248125837,-0.008190630350408745,0.02365978051904616,0.987287662412783,-0.06349965705049049,0.061131009027774186,-0.13226437516298473,0.7180583551542746,0.07084652250170097,0.07265826866910846,-0.34716272069375315,-1.0620506067706859,-0.26087029320592925,0.1263471415902395,1.1496357035201226,-1.3149040019603995,0.6507086185103081,-0.14938611921930647,-0.3792996664766934,-0.18223440651958084,-0.19530933189933097,0.35722390584536245,0.20248853672337244,-1.129309313050411,0.8955970416595757,1.1423812021929425,0.7011139801063759,-1.169335009425998,-0.46786816716657187,2.1907898921373405,0.7145908303970949,-0.09456699488915754,1.2946395777048632,2.1208851207294432,0.8825165502379462,1.3511880525024544,-2.28268474904997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.25,0.0,1.0,1.0,0.0,0.823078773170865,-0.009182661636795224,0.02354313325086027,0.9873294513684665,-0.0655655887219958,0.05673105406243051,-0.1329033315645824,0.7321945469739849,0.07282139011176302,0.0660387571198538,-0.3321970204548761,-1.1308754798081733,-0.23390314963534745,0.13581835120392277,1.1550739729927255,-1.3240517395660856,0.6465154172895538,-0.13120663220431203,-0.37249374735608404,-0.18311612146134687,-0.18419755889424677,0.3751986090999941,0.2097113040630666,-1.1176827415618993,0.8771220179758958,1.1292808186992265,0.6005611960385471,-1.031619509837216,-0.5318600441322396,2.165780013331374,0.9154759161277792,-0.11658458485973688,1.3787054290884448,2.1696173822593003,0.8504282723566048,1.4329270555356999,-2.1528652294959794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2583333333333333,0.0,1.0,1.0,0.0,0.8292034896126828,-0.010197734020687821,0.023414054342270885,0.987380724870138,-0.06759659197932458,0.05206679264627174,-0.13341309535139032,0.7447172424389147,0.07485650341481505,0.05889910726754524,-0.3169563912592632,-1.1894036551323983,-0.20635458915577087,0.14516848856855993,1.1596450567874317,-1.3320976604576864,0.6418442844414375,-0.11328978566378357,-0.3640417345412304,-0.1841774829339098,-0.17233090808119023,0.3933841955496841,0.2166623412626492,-1.1054271954581494,0.8597159545013093,1.1132228303725678,0.49315621180285873,-0.9045891436575593,-0.5832649169651472,2.128597750964509,1.1084336846072307,-0.13757601834314015,1.474151609500468,2.1742883502987556,0.8174441803462823,1.50251177084479,-2.026536765502036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2666666666666666,0.0,1.0,1.0,0.0,0.8354201389749734,-0.011230877267084249,0.023274297137052855,0.9874366765438681,-0.06958607759337779,0.047180815065936264,-0.13379296809206917,0.7556794540609564,0.07697928312470581,0.051269588130814656,-0.30140432083971314,-1.237656539657506,-0.1781527608579494,0.15437206504346557,1.1632932431894398,-1.3391282252937116,0.6367943353401346,-0.09573000302157021,-0.3540198526126302,-0.1854090551003992,-0.1596283654025723,0.41143674827164,0.22333537373550463,-1.0926408787144861,0.8433464052175286,1.0940198500670095,0.37926149055290903,-0.7876397523985901,-0.6234743778143348,2.0810167577270984,1.290920812805303,-0.15731167274249058,1.577689650246535,2.1404159233390607,0.7838437045266583,1.5606110316823996,-1.904441749479573,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.275,0.0,1.0,1.0,0.0,0.8417172734925127,-0.012276976362721662,0.023124951593057455,0.9874932006130658,-0.07152732451201502,0.042115554619841705,-0.13404215997284352,0.7651114293680368,0.07920778078249321,0.043174809754237736,-0.2855046708657468,-1.2757131261444852,-0.14923353384181937,0.16340215273634343,1.1659660816299802,-1.3452249896643296,0.6314530448111986,-0.0786061730349986,-0.342526387661142,-0.18679934414628463,-0.1460360805770813,0.4290577942720018,0.22972640300476016,-1.079417011596776,0.8279752586766498,1.0715119074895247,0.25927301610980447,-0.6801853533506597,-0.6538759491810908,2.0249720105952296,1.4602123123974853,-0.17552816205394284,1.6861454388435593,2.0732811643229354,0.7498871377532307,1.607772735224664,-1.7872252448152093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.283333333333333,0.0,1.0,1.0,0.0,0.8480837042551684,-0.013330811759726313,0.022966419835346346,0.9875469743365263,-0.07341352577640496,0.03691305803335203,-0.13415980716478107,0.7730238374698374,0.08154950575662252,0.034639888116615065,-0.269225619629188,-1.30369980111389,-0.11954457692149836,0.17223059683495764,1.1676144601246032,-1.3504646478495559,0.6258964028537831,-0.06198046951164972,-0.32968298073933877,-0.18833452446796492,-0.13152594142184632,0.44599143434368893,0.23583349269805848,-1.0658446664607417,0.8135593178039418,1.0455774958827175,0.1335781725036389,-0.5816252595997984,-0.675808919796812,1.9625490595611597,1.6134100998070722,-0.19192270535518252,1.7965526307342936,1.9777663397223222,0.7158146538030474,1.6444607313423099,-1.6754718669118462,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2916666666666665,0.0,1.0,1.0,0.0,0.854508354056883,-0.014387136682238002,0.02279842519770888,0.9875955032194175,-0.07523787995920206,0.03161481858373301,-0.13414502110021326,0.7794102342378575,0.0840003982678151,0.02569552796401979,-0.2525430655171921,-1.3217850447699395,-0.08904948677385666,0.18082844433438872,1.1681923845050408,-1.3549187439909929,0.620189562814585,-0.04589702204231261,-0.31563621933102415,-0.18999805590220434,-0.11609353673150975,0.46202056660070717,0.24165664723481095,-1.052009332741071,0.8000507275614523,1.0161435753260946,0.0025235766720976827,-0.49131578786706154,-0.6905329751436562,1.8959697084073526,1.7474585923209884,-0.2061499148867285,1.9061928448026608,1.8583001153108347,0.6818464102258709,1.6710834585246737,-1.5697290050586865,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3,0.0,1.0,1.0,0.0,0.8609800700781572,-0.015440730215230972,0.022620084289967427,0.9876371438697853,-0.07699365637923361,0.026261585578611267,-0.13399693298367182,0.7842422515556925,0.08654447570170072,0.016384226239515624,-0.2354361909678644,-1.3301865577945922,-0.057728302796261316,0.18916632309039255,1.1676565197358049,-1.358653244314007,0.6143875199347222,-0.03038097437152717,-0.3005586708673223,-0.19177035638274373,-0.0997560606751353,0.47696310293220284,0.24719759953515633,-1.0379932754853305,0.7873971677196303,0.9831821839942423,-0.13361571513305748,-0.4085442405443729,-0.6992253876799892,1.8275391716376792,1.8592290976932013,-0.21782725754050936,2.0125919391967075,1.718885521847553,0.6481754677988993,1.6880167527404621,-1.4705273191047263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.308333333333333,0.0,1.0,1.0,0.0,0.8674873998464334,-0.016486440088141756,0.02243003438814313,0.9876711033467389,-0.07867425201785569,0.020893128763121868,-0.13371473686101823,0.7874741363414679,0.08914990554521826,0.006760415368901644,-0.2179021320486214,-1.3291662062391758,-0.025582270991239754,0.1972148140676261,1.1659654559194899,-1.3617278146667324,0.6085358063532519,-0.015438035848351288,-0.2846490677028041,-0.19362851019454616,-0.08255033774489796,0.4906686586314997,0.25245957169812594,-1.0238757201953965,0.7755419389097069,0.9467377957525314,-0.27466640928565766,-0.33249795147920036,-0.7029439215587185,1.7596278812689243,1.945536282864978,-0.22652056488101646,2.113506462819979,1.563156610327524,0.6149887515478442,1.6956160777158091,-1.3783790859371625,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3166666666666664,0.0,1.0,1.0,0.0,0.8740184481441235,-0.017519313805473884,0.022226525073856886,0.9876973972974077,-0.08027336543578173,0.015548099171115074,-0.13329776736980176,0.7890409311309168,0.091768011884431,-0.0031061728353766055,-0.19995582194196604,-1.319036606597813,0.007365422272243467,0.20494528635293474,1.1630787462477106,-1.3641948768386603,0.6026717879087435,-0.0010538430170451,-0.268133066152906,-0.19554569913076067,-0.06453095296146899,0.5030157131043282,0.25744741206095373,-1.0097330075234003,0.7644241829540109,0.9069287312046381,-0.4205756641494629,-0.2622395337913863,-0.7026263586110404,1.694612055302165,2.00323266400688,-0.23174764174366258,2.2069037408670287,1.3944475750927177,0.5824688041807413,1.6942292698369688,-1.2937796788394684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.325,0.0,1.0,1.0,0.0,0.8805606103418482,-0.01853463902855176,0.02200761355074068,0.9877168031632695,-0.08178505169869155,0.010263736631180137,-0.13274553769530278,0.7888549116826784,0.09433282026872182,-0.013127542177342376,-0.18162846364432478,-1.3001679289993162,0.041071922149406026,0.21233029292103672,1.1589558615169988,-1.3660984735632555,0.5968253670430679,0.012805498406684795,-0.2512618566360228,-0.19749097089027387,-0.04576860873044749,0.5139094515497117,0.2621673851011383,-0.9956385656981137,0.7539789442623824,0.8639426054431892,-0.5714307442615629,-0.19668448718604292,-0.6990978511531698,1.6347911871107765,2.0293382065251704,-0.23298365283405842,2.290937097471921,1.2158643148389925,0.5507943990977826,1.6842072600126734,-1.2172125687492552,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3333333333333335,0.0,1.0,1.0,0.0,0.8871003582653081,-0.019528056846781536,0.021771317752272465,0.9877307786335577,-0.0832038811929003,0.005075673210927335,-0.13205779278755042,0.7868097960634064,0.09675969966799405,-0.023199460000260446,-0.16297768261894835,-1.2729787761869729,0.07547549517656435,0.2193443297769879,1.1535549005100179,-1.3674729516250943,0.5910201570561907,0.02619267676813451,-0.23431076271081983,-0.1994287600113283,-0.026348668003603633,0.5232801183516448,0.26662731871258344,-0.9816628865231891,0.74413730680819,0.818047854522358,-0.7274705959250083,-0.134589754076746,-0.6930531516255312,1.5823338144996788,2.021106215202141,-0.2296545135567324,2.363929237291016,1.0303339168222392,0.5201566424019488,1.6659076367592873,-1.1491460616070293,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.341666666666667,0.0,1.0,1.0,0.0,0.8936230191459267,-0.020495648944242648,0.021515789155141424,0.9877413676058189,-0.08452505866019773,1.7728010254992256e-05,-0.13123454143051672,0.7827825716260893,0.09894847424618827,-0.03320144999990231,-0.14408286269073173,-1.2379307945728195,0.1105013119975352,0.2259644238297427,1.1468313515849153,-1.3683416361312013,0.5852744811826424,0.03917772864834611,-0.21757675304932045,-0.2013185461162194,-0.00636978810893056,0.531081683496749,0.2708366624745041,-0.9678734384187923,0.7348265099022653,0.7695764452742826,-0.8890777434210761,-0.07455878972257857,-0.6850699685323391,1.5392030008059374,1.9761293376977525,-0.22114927209682889,2.424363384117379,0.8406317136004504,0.49075286440670274,1.6396988426730763,-1.090033657896663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.35,0.0,1.0,1.0,0.0,0.9001125936757359,-0.021434013287880423,0.021239469276313597,0.9877510948023318,-0.08574452819676141,-0.004878245017155204,-0.13027606582465262,0.7766398543606624,0.10078836274550931,-0.04299998865431902,-0.12504221800189902,-1.1955127055044599,0.1460692859579428,0.2321706038648926,1.1387369381196666,-1.3687155981204706,0.5796023242473184,0.05184606011490013,-0.20137527374919062,-0.20311458121294212,0.014057388398352676,0.5372906469116523,0.2748065331193618,-0.9543345724786378,0.725970079176579,0.7189042247080851,-1.0567571376384288,-0.015065328754131357,-0.6756181207239242,1.5071032436241338,1.8924008213392274,-0.2068318796776336,2.470881059776503,0.6493829743439394,0.4627809880257927,1.605958394910969,-1.0403096222031216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3583333333333334,0.0,1.0,1.0,0.0,0.9065516501627131,-0.02234031516678833,0.020941211995731523,0.9877628571640549,-0.08685904282768935,-0.009582426327300827,-0.12918290054002582,0.7682481121762748,0.10216601502592418,-0.0524540200869699,-0.10596590315345972,-1.1462164599026938,0.1821046341313835,0.23794616090821077,1.1292187326242749,-1.3685927249437702,0.574014179170577,0.06429611604208167,-0.18603673936033333,-0.20476574411084664,0.034811562887344494,0.541904733069148,0.27854967894160065,-0.9411074651702761,0.7174880161988799,0.666420893823817,-1.231092809311467,0.045496449374624603,-0.6650747887799491,1.4874558424476023,1.7683242408062045,-0.18605941295886885,2.50228949673225,0.4590338502802416,0.43642627537296863,1.5650653832158357,-1.000377985065244,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3666666666666667,0.0,1.0,1.0,0.0,0.912921339120671,-0.023212301898005928,0.020620350772712442,0.9877798206910025,-0.08786618164495132,-0.014066983703583781,-0.12795577332957037,0.7574883213298915,0.10297651242492116,-0.06142313655037309,-0.0869658876399641,-1.090505515838252,0.2185508287117806,0.24327761876195622,1.1182187246311421,-1.3679573239642269,0.5685177444343192,0.07663699082236017,-0.1719032030690872,-0.20621557142892327,0.05576221334389018,0.5449412110829897,0.28208030437557796,-0.9282501494250406,0.7092971127588249,0.6124915499969952,-1.4126821418207403,0.10873307918234598,-0.6537446906142219,1.4814141127198346,1.602654469604999,-0.15820599138243574,2.5175799675688517,0.27178960035014077,0.4118415144123111,1.517386726825789,-0.9705924108937403,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.375,0.0,1.0,1.0,0.0,0.9192015753697645,-0.024048271593959513,0.020276690797577827,0.9878053313988504,-0.08876430033498282,-0.018305878400759153,-0.1265955017452381,0.7442752684871661,0.10313684013613647,-0.06977837169059997,-0.06814325320460385,-1.028776537409732,0.2553843332608508,0.2481543534081607,1.1056740302605959,-1.3667805069573977,0.5631184343270066,0.08898635125407892,-0.15932583153358335,-0.20740251063388723,0.07677122901349202,0.5464345597416503,0.28541370418180584,-0.9158176863898463,0.7013114760173176,0.5574124216360693,-1.6020486133571232,0.1761435898156316,-0.6418843260030083,1.4899233427643284,1.3943659116185214,-0.12269167233044886,2.515959343752507,0.08951834477499254,0.38912206464025934,1.4632576063216662,-0.951224692201047,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3833333333333333,0.0,1.0,1.0,0.0,0.9253714340500497,-0.024846989928302247,0.019910410069842618,0.9878428479334286,-0.08955240593461831,-0.022274501497155562,-0.12510284153949175,0.7285814879365767,0.10260101593317658,-0.07741523108749479,-0.049573906748219404,-0.9613167380271177,0.29263034245195585,0.25256782578922404,1.0915179144085234,-1.3650215974672997,0.5578196723342691,0.10146904653509897,-0.14866377120877852,-0.20826043263443075,0.09769486907309863,0.5464331834959062,0.2885656721195823,-0.9038625226530128,0.6934433678888074,0.5013640717637863,-1.7995360218886436,0.24898344893925728,-0.6297291157293561,1.513819698097957,1.1424643947295872,-0.07901527738544134,2.4968982589481263,-0.08638133958677852,0.36827788227633884,1.402957240700864,-0.9424198641005432,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3916666666666666,0.0,1.0,1.0,0.0,0.9314098035188496,-0.025607553258581123,0.01952185947358167,0.987895901139241,-0.09022995283620325,-0.02594912779329041,-0.12347828509636441,0.7104655819447473,0.10137586508904511,-0.08426835343766788,-0.031293782975437945,-0.8882595101572625,0.3303786600166415,0.25651042127089047,1.0756817632291185,-1.36263078280841,0.5526229490648507,0.11421667955571153,-0.14028475828809023,-0.2087194319236446,0.1183861999959608,0.5449948707485374,0.2915516688864115,-0.8924350657114986,0.6856044782823085,0.44436537939457454,-2.0051889614732676,0.32810327607217804,-0.6175220178077723,1.5539490265302602,0.8457830785212139,-0.02679014153967929,2.4601998569859265,-0.2551507532476571,0.34920491470923243,1.3366813352598306,-0.9441361309605134,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4,0.0,1.0,1.0,0.0,0.9372963313700896,-0.026329200686697744,0.019111258580785263,0.9879680827443613,-0.09079656267174273,-0.029306185398478204,-0.12172181062949346,0.6901041020149139,0.09953632543659019,-0.09032706991768027,-0.013284381094465947,-0.8095407638790209,0.3687987106490568,0.2599739154458003,1.058098098383969,-1.3595532095327634,0.5475276387041396,0.12736819697726998,-0.1345673865667583,-0.2087069349934254,0.13869820002286407,0.5421806709417786,0.2943857540314028,-0.8815845003986823,0.6777077657061322,0.38623124598645364,-2.21862625010381,0.4137646588964694,-0.6055419806091789,1.611273508747202,0.5028240747683405,0.03421775541679939,2.406091914118707,-0.4168801034617897,0.3316580749115372,1.2645118993547921,-0.9560688591395583,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.408333333333333,0.0,1.0,1.0,0.0,0.943012685516347,-0.02701108068410192,0.01867828973006975,0.988063061567343,-0.09125167417352123,-0.032321348006034215,-0.1198325865108152,0.6678247485774934,0.09723894544888467,-0.09565097027584724,0.004540882783188344,-0.7248578354559887,0.4081522305259451,0.262947608703998,1.0387046590607216,-1.3557347051601356,0.5425305827213643,0.14107123803483157,-0.13190435704195122,-0.20814913600003127,0.15848773189793924,0.5380468690241742,0.29707930346827044,-0.8713598673889187,0.6696699972966492,0.3265369808015617,-2.4389178959491797,0.5054354669923633,-0.5941301284184419,1.6869239248331898,0.11172060587892052,0.10404920322882649,2.3353403014604,-0.5727523053917394,0.31522778363377024,1.1863841306766165,-0.977561577506536,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4166666666666665,0.0,1.0,1.0,0.0,0.9485441206631822,-0.02765197977814593,0.01822159809379129,0.9881846212804887,-0.09159413047816979,-0.03496846372103529,-0.11780864175337094,0.6457902083012115,0.09531297920412005,-0.10019161733200978,0.02487714208323355,-0.648959752263743,0.44849771075551864,0.26541619845915965,1.017449466784816,-1.3511292850828907,0.5376254698971655,0.1554835957244898,-0.13270537646877628,-0.2069727816062783,0.1776205383805374,0.5326347991852496,0.299639550425299,-0.861811431554072,0.66141507274769,0.25736403267800023,-2.660920785842167,0.6255590722287963,-0.5921629570817832,1.7634972700098968,-0.2600700987071336,0.17388260119250376,2.2604230064261146,-0.7025498058084434,0.2970092438801386,1.0952340585962905,-0.9671153066856664,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.425,0.0,1.0,1.0,0.0,0.9539101828247435,-0.028246400982217118,0.01774218557595096,0.9883335882944987,-0.09181559004460241,-0.037347246240406064,-0.11563649455100124,0.6271773458597699,0.09459966812061585,-0.1040987301896316,0.05056927829160619,-0.6034065991001879,0.48939354240647487,0.26723700924863136,0.9943559792966855,-1.345308720622989,0.5326612001033346,0.17046285920166318,-0.1362388586870701,-0.20525109264682287,0.19616144867170782,0.5263377055940335,0.3020294575329394,-0.8531059664123138,0.6535514088518881,0.16962814589822406,-2.8734087768703898,0.8028019462068858,-0.6101011054514571,1.8110472296629876,-0.5055205325638767,0.231533065860281,2.2004956782934517,-0.7772202801852801,0.27469024407116627,0.9802539818886524,-0.8626534638965322,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.433333333333333,0.0,1.0,1.0,0.0,0.9591508050245896,-0.02879152744339951,0.017241815420999063,0.9885070101429937,-0.09191204517173444,-0.03961214846181632,-0.11330024070962637,0.612301134841001,0.09463681429244446,-0.10787498291009893,0.07917379399783774,-0.5827652394420232,0.5303530694870325,0.26824333422413005,0.9695593205036428,-1.3377492526461092,0.5274571181396412,0.18566771621887293,-0.14113071867817423,-0.20311389717527362,0.21429546635209493,0.5196811278488283,0.30421772115981843,-0.8454738651892612,0.6470375150160811,0.06901174461280801,-3.069100231785087,1.0218188489412006,-0.6415235322654622,1.8299932799266705,-0.635332724183062,0.2804861888683241,2.156432820530447,-0.8090871561989355,0.25140879832534324,0.8426641006314939,-0.6727264263241661,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4416666666666664,0.0,1.0,1.0,0.0,0.9642893191693396,-0.029290680617824964,0.016719573193722102,0.9887023245573593,-0.09188919217463058,-0.04181603194725551,-0.11079489721406088,0.5997788681092994,0.09482877483973391,-0.11174944084207256,0.10795573171356992,-0.5709526633514982,0.5711790840137176,0.26838720499217816,0.9432043087669341,-1.328278406473969,0.5219691412322436,0.20096274720044102,-0.14682773742345448,-0.2005763228323508,0.2321019956805486,0.5128529196573846,0.30621960417169514,-0.8390615647351223,0.6423393017464853,-0.03614531811272248,-3.2480579487884964,1.2549043252125092,-0.6765169026396567,1.8387837783667027,-0.7195410161665072,0.3289320972279669,2.119933805429313,-0.8265903959126275,0.2297036552818632,0.6897769478174531,-0.43844636811604776,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.45,0.0,1.0,1.0,0.0,0.9693412290440302,-0.02974545203652025,0.01617486820199255,0.9889177183488472,-0.09174921804856916,-0.043978317763504936,-0.10811907736383473,0.5889518472206686,0.09520668420762096,-0.11569277517379946,0.1369584164838328,-0.5623755484381586,0.611807108914551,0.2676409122555847,0.9154250213571679,-1.316834180559234,0.5161818364289803,0.21631411252498464,-0.15312306894761601,-0.1976316955548075,0.24962769644258348,0.5059046212502845,0.30804611541451615,-0.8339775827256369,0.6397300755474803,-0.1443294257357608,-3.4111941658515077,1.4926664317010463,-0.712959322147575,1.8460721220684573,-0.7872386050006758,0.3784490714718819,2.088342461248767,-0.8412260195509791,0.20900878140051038,0.5248808149817341,-0.17607354471599113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4583333333333335,0.0,1.0,1.0,0.0,0.9743193130707641,-0.030155783025099536,0.015606973401170062,0.9891517482657542,-0.09149185986251601,-0.04610586501813333,-0.10527254006987989,0.5796085501289568,0.09585976371153579,-0.11972297192550801,0.1663634448246337,-0.5548907237718083,0.6522337078382663,0.2659817145632488,0.8863510726694089,-1.303400632612285,0.5100864858631173,0.23173061590158198,-0.1599483808401324,-0.19426883830781944,0.26690770336802805,0.49883248599820157,0.30970308386170364,-0.8303135511520934,0.6394047426678855,-0.255049656432621,-3.5588522101246634,1.7310222677926523,-0.7503373821784121,1.8554767379038861,-0.8499471052901958,0.42935552401194454,2.060874573032767,-0.8579178271590038,0.1888731446504377,0.3496386697210041,0.10745247363923793,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.466666666666667,0.0,1.0,1.0,0.0,0.979235962132915,-0.030520812024776786,0.015014908666524803,0.9894030782806021,-0.09111569819577152,-0.048200580273629834,-0.10225547561178261,0.5717527325545626,0.09684345678913445,-0.1238852521472577,0.19626926147875617,-0.5476386273372803,0.692447537046376,0.2633900846483743,0.8561108178550901,-1.2879838094293565,0.5036762133926734,0.24723872482338274,-0.16728885403578594,-0.19047577015460843,0.2839756059931296,0.4916059907976344,0.3111940011586901,-0.8281502715636202,0.6415209501081343,-0.3679105572798591,-3.691127163433796,1.9678926329597646,-0.7884940772273108,1.868486084274677,-0.9119937693302926,0.4816891641718052,2.037635976503173,-0.8793108935850558,0.16912345434546783,0.16528934503698522,0.40848987126022474,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.475,0.0,1.0,1.0,0.0,0.9841042008696258,-0.030839383757212402,0.014397453650752318,0.9896703472399013,-0.0906188205502301,-0.05026229789960458,-0.09906833281192827,0.565481114176499,0.09818327564075968,-0.1282351513340017,0.22671493060734804,-0.5402492149447886,0.7324167734320229,0.25984987194191783,0.824832286612179,-1.2706024220629555,0.4969449179093288,0.26287205063949326,-0.1751482769956373,-0.18624068557162268,0.30086830297641426,0.48417730443845064,0.3125218081007948,-0.8275587287348103,0.6462129071888892,-0.48249095879529524,-3.8080736308084306,2.2019757201278978,-0.8273441442657037,1.8856748083205062,-0.9747268924026553,0.535409964495987,2.0191587905864075,-0.9073072353972667,0.149750461286291,-0.026953158193177007,0.7244337589971139,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4833333333333334,0.0,1.0,1.0,0.0,0.9889380692368448,-0.031110286986929955,0.013753186586078731,0.9899521078935918,-0.08999912022820697,-0.052289886445712114,-0.09571180810551187,0.5609199169837895,0.09988315859980555,-0.13283031271593915,0.25770804444926354,-0.5325406106434588,0.7720910600955819,0.25534856866845274,0.792642924008283,-1.2512842140938916,0.48988714432157837,0.2786666382953912,-0.18353430224249687,-0.18155227074634198,0.31762825250290305,0.4764842035410133,0.3136898421801283,-0.8285994908668398,0.6535948460914195,-0.5983419397721329,-3.909818523152553,2.432280181247881,-0.8668019174345576,1.9071830888965902,-1.0382072780676972,0.5904550669404185,2.0061578523085,-0.9435791090847123,0.130836434800351,-0.22578063178562813,1.052862799286567,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4916666666666667,0.0,1.0,1.0,0.0,0.9937526513821691,-0.03133235867599663,0.013080528255453187,0.9902468001568336,-0.08925443385722315,-0.05428167389425528,-0.0921868791931165,0.5581882703359106,0.10192831204127825,-0.13772554762090788,0.28923825743305664,-0.5244030516390932,0.8114052985058378,0.24987750627904895,0.7596686445596365,-1.2300644190421575,0.4824982192854195,0.29465843545443643,-0.1924517316300989,-0.17639976778928237,0.3343042671815559,0.46845098595370543,0.3147024153474673,-0.8313217392645708,0.663760620510332,-0.7149927271030199,-3.996629193662391,2.657963755964694,-0.9067596282830492,1.9328906969458093,-1.101881801249568,0.6467633871525719,1.999387718107719,-0.9897097571120872,0.11252617481416372,-0.42977704963290453,1.3912336498136502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5,0.0,1.0,1.0,0.0,0.9985638756795664,-0.03150453310618191,0.012377791130559175,0.9905527401286803,-0.08838261817679394,-0.05623560887182369,-0.08849484800112864,0.5508820483637186,0.10280915682766065,-0.13828735264135342,0.32155003244875924,-0.5074291074460818,0.8436902128078558,0.24343202321673574,0.7260324374472431,-1.2069848181611467,0.4747744838501942,0.310881483244488,-0.20189899892998966,-0.17077288096046578,0.3509513811380317,0.4599890409224785,0.315565278427031,-0.8357624416940549,0.6767820735883137,-0.8237345417824266,-4.096189812997348,2.89657464029784,-0.9430475544508399,1.9289924809273695,-1.136677638137093,0.7288834837858843,1.6374087561796236,-0.598047901852945,0.00465574110083522,-0.5354287788078271,2.4840178300028737,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5083333333333333,0.0,1.0,1.0,1.0,1.0032703002751882,-0.031617366016871234,0.011709861836935164,0.9908676921936257,-0.08737031539024635,-0.05808557778572396,-0.08469775799429315,0.5638743134752959,0.10850450601871572,-0.14745177562489836,0.35748654314269523,-0.5153926032296978,0.8754203032781831,0.23614859724934184,0.691398814343014,-1.1817881750371935,0.4667807600445722,0.32680831013655925,-0.2113963589323838,-0.1642517097261843,0.361594413117883,0.458483520922823,0.3147800110324812,-0.8402455522447012,0.7051609176770466,-0.9460754853528924,-4.110758787685119,3.117674539640034,-0.9894240687607847,1.982339839175199,-1.1652269606567984,0.7910780002161588,1.1171517785684637,0.14926592408118888,-0.10134475087674177,-0.5485847586792381,3.527494471487993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5166666666666666,0.0,1.0,1.0,1.0,1.0083319383346736,-0.03168140600039704,0.010899926683946017,0.9911803034502679,-0.08621787392195553,-0.060105838261995954,-0.08071785723047092,0.5987670587934636,0.1188437677080359,-0.16797807241574983,0.3944530332561954,-0.5504412241513016,0.9097882976441973,0.2276640984608542,0.6575197909858245,-1.1550235758338128,0.45828408270418114,0.34392048056407465,-0.22131944827426964,-0.1575882476235298,0.3695705774475061,0.46247680632383165,0.313876199245752,-0.8449055210053755,0.7355736481131135,-1.0808127506052345,-4.0302427567428705,3.304588673062745,-1.0434547149701123,2.103323904652481,-1.197736857909369,0.8103922199585606,0.7963776720924953,0.7837544413398845,-0.11270978568985401,-0.5488920962124677,3.712929338829083,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.525,0.0,1.0,1.0,1.0,1.013679688549513,-0.031690959269505964,0.00998072783187939,0.9914864152909385,-0.08493789695749564,-0.06224338657080866,-0.07658983472051917,0.6263214515153458,0.1269743278677639,-0.18505897260433668,0.42831430964070544,-0.573876439405629,0.9388385549251839,0.21813505140592127,0.6242281017306328,-1.1267116971528144,0.44938984812840366,0.36186370854743394,-0.23135863989753994,-0.15074517272687496,0.3748673743194246,0.4715460949451544,0.312901514604317,-0.8493937538482423,0.767043073324198,-1.199692089518949,-3.969308736872237,3.488716432597583,-1.0872044649816992,2.188277698852492,-1.2027658777898271,0.8350023849229804,0.47393543371348046,1.3715515269002354,-0.11951411217012264,-0.5175021496656851,3.8053393984055406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.533333333333333,0.0,1.0,1.0,1.0,1.019251618187211,-0.03164443407289702,0.008971983487462518,0.9917841871107036,-0.08353211901378926,-0.06445585380753475,-0.07233224868909978,0.6474477319774884,0.1331047648158118,-0.19974540000322932,0.4607956229489746,-0.5876011430804202,0.965081934723031,0.20766923030220505,0.5913646453712872,-1.0968783019571864,0.4401640082878195,0.3803917755449495,-0.24136554623743342,-0.1436715412081468,0.3774695013427308,0.48533599843883557,0.31188429737624995,-0.8535305568331369,0.7989959714198726,-1.306862615694997,-3.926287033066902,3.6696211987611527,-1.1239239691612712,2.2476692722276472,-1.195005028872192,0.8659925096519311,0.15237735407621966,1.914399130308273,-0.12298880874210272,-0.4680481672378134,3.837245900812589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5416666666666665,0.0,1.0,1.0,1.0,1.024995489224387,-0.03154138432125439,0.007888899445112571,0.9920725410032024,-0.08200208930980729,-0.06670536468831857,-0.06795678816890154,0.6632697018582492,0.13753461790953314,-0.21239103662845477,0.49209571088323834,-0.5923595496280278,0.9895976278843507,0.19635400781100465,0.5587899845128511,-1.0655513438401285,0.4306577819757158,0.3993248630845614,-0.25127539037874314,-0.1363119642326761,0.37740699688736157,0.503452747116959,0.31085170112528193,-0.8571945566355392,0.8309971716710745,-1.4042798844376814,-3.8989143155516803,3.847039456280652,-1.1550486867432197,2.28818682451849,-1.1826472929510508,0.903411005647653,-0.1629755914178932,2.406452091441984,-0.12346584397040505,-0.40596836388123725,3.8219172465652806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.55,0.0,1.0,0.0,1.0,1.0308688470972818,-0.031381840290476845,0.0067453670951913075,0.9923509479474236,-0.08034957802099826,-0.06895505652985955,-0.06347236878164315,0.6749646597135606,0.14054167740573975,-0.22312183096414492,0.5222776462602319,-0.5882929973734031,1.0128294508086249,0.18426456556157703,0.5263827401120925,-1.0327609776858422,0.42091319684209916,0.4185282226202577,-0.26107633445328426,-0.12861469111401924,0.3747532414857659,0.525443533296202,0.30982653331007654,-0.8602966962311576,0.8626945921959606,-1.4932064011909358,-3.8849003410688776,4.02041865721466,-1.1815329794812224,2.314732931471166,-1.1711904976845178,0.946541587861253,-0.4675013441886955,2.8412904424911445,-0.12152937256588614,-0.33445846758537234,3.767989526453761,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.558333333333333,0.0,1.0,0.0,1.0,1.03683930524145,-0.03116618876004752,0.005554833607447928,0.9926193584515972,-0.07857658734797263,-0.0711679600383016,-0.05888676092234697,0.6837341797088676,0.14236825974124367,-0.23202469932709302,0.5513714270716189,-0.5753575519123136,1.0349628953549186,0.1714672344578224,0.4940416454950365,-0.9985443662198842,0.41096556565102876,0.4379037452757475,-0.27079523200681843,-0.12053627110165523,0.36961530781755,0.5508075878251447,0.30882621158251716,-0.8627688644286288,0.8937969971119705,-1.5746074774224335,-3.8817181008256454,4.188581280628063,-1.2040918328102768,2.331368473759511,-1.1646513835500438,0.9942284218897877,-0.7578850843003704,3.2144419599733642,-0.1178159702407422,-0.25562053259096995,3.6819998082075456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5666666666666664,0.0,1.0,0.0,1.0,1.0428844545522273,-0.030895183434002833,0.004330445638252043,0.9928781634292888,-0.07668538965600373,-0.07330676075800358,-0.05420721746957416,0.690744843591,0.14321010506593052,-0.23919955364707784,0.579385865972341,-0.5534828322401893,1.0560776948260209,0.15802110760453647,0.4616874384316651,-0.9629512896753745,0.40084499962859454,0.45738436384958286,-0.280487190845785,-0.11204421741585611,0.36212182341409305,0.5790175659624247,0.30786293380606417,-0.8645570384410071,0.9240612556660863,-1.6492858805760087,-3.886688684066939,4.349721585674273,-1.2232720255035112,2.34148905970795,-1.1658459475622152,1.045060624141654,-1.032239716779656,3.5240384303424466,-0.11290323695427817,-0.17085033001979166,3.5691382648624326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.575,0.0,1.0,0.0,1.0,1.0489912810270077,-0.0305700071307764,0.003084982807567592,0.9931281510004969,-0.07467861600661628,-0.07533388966283236,-0.04944072278970741,0.6970431328996012,0.14320540769747978,-0.24475970618404802,0.6063096654512495,-0.522635491567258,1.076210228826329,0.14397913644822224,0.4292635007605875,-0.9260490064586463,0.3905776985593036,0.47692856293754665,-0.290225997799522,-0.10311859403262766,0.35241131253788904,0.6095415616641855,0.3069444909666125,-0.8656163699289586,0.9532826348596777,-1.717929187798618,-3.8972030035142793,4.501578224919216,-1.2394761226458262,2.3477522996902778,-1.1764461072118149,1.0974844865249003,-1.2900540756377188,3.770749412617007,-0.10725535561097455,-0.0810469797258273,3.4334524370662534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5833333333333335,0.0,1.0,0.0,1.0,1.0551546993139445,-0.030192329093305333,0.001830792715926165,0.9933704515371876,-0.07255934651182888,-0.07721176634946621,-0.0445940622034674,0.7034900963773004,0.14243001786538884,-0.2488170025645594,0.6321073639879711,-0.4828384730507701,1.0953762018085549,0.1293889544745595,0.39673405503976045,-0.8879249859267209,0.3801870642511641,0.4965135688444208,-0.3000946259659819,-0.09375280930710778,0.3406209221534644,0.6418633895060415,0.30607534454588126,-0.8659078214364375,0.9812854629505239,-1.7811241926398376,-3.910912993203748,4.641634585567236,-1.2529694289341131,2.3520168330285154,-1.1970722455775251,1.1498734638142096,-1.5319786829639748,3.9573125410196286,-0.10120230212602332,0.013227318655730791,3.27793516975853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.591666666666667,0.0,1.0,0.0,1.0,1.0613759015256765,-0.029764386557647637,0.0005797511371281778,0.993606466899393,-0.07033124417006825,-0.07890303253773238,-0.03967387661396689,0.7107506016781852,0.14090180385133827,-0.25146811269737845,0.6567158540301835,-0.43416888969973216,1.1135708514679195,0.11429373323755829,0.36408161754052504,-0.8486884300325257,0.369694874743735,0.5161288434880219,-0.31017720189248077,-0.08395403630239083,0.32687833448848946,0.6754967706811793,0.3052577859311788,-0.8653959146180298,1.0079148876889865,-1.839362716433365,-3.925772573915929,4.767239598653286,-1.2638855002569571,2.355394120133626,-1.2274563492673063,1.2005536489972366,-1.7594250306516201,4.087786154345839,-0.09494943464158245,0.1116316500718284,3.1046606448854286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6,0.0,1.0,0.0,1.0,1.0676607330861045,-0.029289054852991398,-0.0006567049998182131,0.993837788834487,-0.06799866117726754,-0.0803707766284138,-0.034686738486981936,0.7192554774511603,0.13858875184178387,-0.2527725780834738,0.6800516895744391,-0.37675482001262206,1.1307784506633047,0.09873290920067009,0.33130451214116163,-0.8084709926158328,0.35912230591354816,0.5357701375133146,-0.3205522317871037,-0.0737435818238205,0.31129717164260406,0.7099931587451388,0.30449285396852155,-0.8640472939352404,1.0330298070319477,-1.8930730618919054,-3.9401362157201327,4.87576649540064,-1.2722577864477047,2.358258769661359,-1.2666197955288272,1.2478441747969082,-1.9743615029188222,4.16705438803064,-0.08860692348325427,0.21390851349852857,2.914850253789627,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6083333333333334,0.0,1.0,0.0,1.0,1.074017416769598,-0.028769860529064738,-0.001867475033556902,0.9940661136532369,-0.06556670639459808,-0.08157873892596404,-0.029639130456488718,0.7292187211864615,0.13542160712028145,-0.2527419843657369,0.7020129103968279,-0.3107645863443146,1.1469689544937138,0.08274251553935986,0.29841268061185616,-0.7674256551091817,0.34849057830293995,0.5554331563157112,-0.3312875318179612,-0.06315663338910903,0.2939723094398424,0.7449476771483566,0.30378100387312457,-0.8618307727263876,1.056495725252147,-1.9426346185728816,-3.9527239079593346,4.96468082781282,-1.2780389946101234,2.36036732068736,-1.3130839429613206,1.290076314888874,-2.179008126254649,4.2002706823320395,-0.08222499925977456,0.31979649306685287,2.709015448019092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6166666666666667,0.0,1.0,0.0,1.0,1.0804552302201953,-0.028211029891303103,-0.0030416580990997844,0.9942931462541006,-0.06304132113553762,-0.08249144998378118,-0.024537559398842966,0.7406856201796372,0.13130918807261047,-0.25133685382488463,0.7224847349394817,-0.2363980037427144,1.1620895385718633,0.06635566555778873,0.2654257803418394,-0.7257263121522858,0.33782165600337943,0.5751095928581039,-0.34243696416979236,-0.052242309909005934,0.2749803695383599,0.7799976701173394,0.303122437314192,-0.8587173523841262,1.0781800644989326,-1.9883927318201535,-3.962487650920461,5.031521674941737,-1.2811237469692471,2.3610243379607865,-1.3650600252998535,1.3255965657601854,-2.3755107469568095,4.192349873164245,-0.07583912138118154,0.4289860641240062,2.48713823987452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.625,0.0,1.0,0.0,1.0,1.0869830538046203,-0.027617470515620825,-0.0041683696435381055,0.9945205038550232,-0.06042928368528748,-0.08307436933866773,-0.019388611201239674,0.7535423625808205,0.12615251043587788,-0.24845962321004292,0.7413508129733086,-0.1538841269747858,1.1760692512088504,0.04960263667569064,0.2323712197631818,-0.6835669605268194,0.3271385158534525,0.594783561948391,-0.35403853223962545,-0.04106335729310594,0.25438046365722894,0.8148201750344274,0.30251701851677154,-0.8546810049909875,1.0979480292500556,-2.0306879766873527,-3.968578499540707,5.073931751019567,-1.2813848561130936,2.359171040732977,-1.4206072433584238,1.352802917303724,-2.565846734366909,4.147788824325436,-0.06951351972242059,0.5410596968984982,2.2487689538203837,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6333333333333333,0.0,1.0,0.0,1.0,1.0936082199768205,-0.026994736741907072,-0.005236532281236755,0.9947496158523536,-0.05773818854659074,-0.08329400369321198,-0.01419902439742665,0.7675447329164505,0.11985752517886841,-0.24395436720288927,0.7585002438116415,-0.06347846023207526,1.1888171026025267,0.032510865946332845,0.19928280534949427,-0.6411607829686263,0.3164652417348279,0.6144291102036535,-0.3661137515590994,-0.029695594620610534,0.23221625729891143,0.8491274838560967,0.30196387865215163,-0.8496996907691512,1.1156595470626056,-2.0698698338011017,-3.970288935177841,5.089676943886632,-1.278697662722782,2.3534973065403753,-1.4777697790731348,1.370180070647846,-2.7517105988867,4.0705051486732025,-0.06337829437951803,0.6554675953519795,1.9931387194371641,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6416666666666666,0.0,1.0,0.0,1.0,1.1003355563159276,-0.02634896646265135,-0.006234642697347135,0.9949816214780147,-0.05497638619846054,-0.08311802200929741,-0.008975761748695167,0.7823358681381642,0.11234683312650998,-0.23760726919827369,0.7738362332593707,0.034537392993013574,1.2002239024261239,0.015104806112338946,0.1661997375102178,-0.5987390114620422,0.30582688814140613,0.6340085170573972,-0.378668028557511,-0.018227022782308505,0.2085186203424506,0.8826619275123141,0.30146071361044624,-0.8437565450684545,1.1311670079073417,-2.1063131802669104,-3.967035529884619,5.0766956077737495,-1.272967198260958,2.342526444534667,-1.534691818815609,1.376345754756905,-2.934472049036321,3.963783845074378,-0.05766248862899226,0.7715113845229027,1.7192420407644748,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.65,0.0,1.0,0.0,1.0,1.1071665484191593,-0.025686790350705438,-0.0071505201033550585,0.9952172661099548,-0.05215288835871089,-0.08251536763074076,-0.003726067289238425,0.7974560594343049,0.1035701021966969,-0.22914865815091118,0.7872837042571286,0.13985674268660106,1.2101673157327109,-0.0025943537247823238,0.13316554651808396,-0.5565491895057305,0.2952491217638119,0.6534712176125647,-0.39169194853935957,-0.0067564987079954545,0.18330838981497274,0.9151905479406697,0.30100283717500176,-0.8368411676937695,1.1443135810753469,-2.140434955311785,-3.9583906351421514,5.033197844704791,-1.2641540662897566,2.3246840211686637,-1.5897266030708124,1.3701062032199818,-3.1151804364688944,3.830284230934846,-0.05271885829732259,0.8883359997679574,1.4258955985591637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.658333333333333,0.0,1.0,0.0,1.0,1.1140985677258537,-0.02501521745203253,-0.00797104304119314,0.9954567972844791,-0.04927724562714672,-0.08145635939124234,0.001542503970561387,0.8123473092785125,0.09351334089102785,-0.21825742307125634,0.7987953059406928,0.25215172257174606,1.2185203268378135,-0.020569109809524144,0.10022656025784861,-0.5148523807169624,0.2847576537032435,0.6727532507435416,-0.40516347194202457,0.004608080604691191,0.15659894640130237,0.9464999980278949,0.30058206597215753,-0.8289509450723219,1.1549319345499944,-2.1727123491151557,-3.9441601354188704,4.9578182471984915,-1.2522982546981543,2.2983602647786894,-1.6415504495356215,1.3505153243433135,-3.294595189054947,3.672072108078983,-0.04903826588913862,1.0049315394087066,1.1117783908498202,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6666666666666665,0.0,1.0,0.0,1.0,1.1211241393106506,-0.024341503370524424,-0.008681885919883964,0.9956998616565548,-0.04635940722458724,-0.07991276407250325,0.006822096266579234,0.8263999141409809,0.08207080553355231,-0.20287784330925968,0.8085850282170643,0.37889742837330903,1.2257538000317192,-0.03880622621003492,0.06742954426110279,-0.47391888538575566,0.27437748418550933,0.6917772220255428,-0.4190511226982866,0.01575209003105977,0.1283984699973903,0.9763917497419861,0.3001855327435161,-0.8200923087036244,1.1628432209228439,-2.204608864591544,-3.9281326910031122,4.839916211622134,-1.2378310396662262,2.2604996231184615,-1.7000444452547792,1.3176551076048664,-3.4787459786615518,3.474347702964151,-0.049535653145130754,1.1245727851518317,0.7538032597421651,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.675,0.0,1.0,0.0,1.0,1.1282264878116746,-0.02367268228044348,-0.009239239334830483,0.9959504958615586,-0.04340883982649721,-0.07779271741037294,0.012106838408150333,0.8385788896189313,0.06918885394592413,-0.18136739691698786,0.8166240616777772,0.5253214989128172,1.2324351793782597,-0.057312590886049876,0.0347576820744634,-0.43418711052326014,0.2641271363754731,0.7104282444621827,-0.4334975460296042,0.026568999064772295,0.09861984675694317,1.0044057930772974,0.299756471753072,-0.8102080653197914,1.1674953222123639,-2.2379204497290335,-3.9136860162950686,4.671383242374763,-1.2211659215583148,2.2086460372445305,-1.7735608063612773,1.2713867062668516,-3.6728597417988467,3.2279105218738824,-0.05644707884630784,1.2479394295753798,0.33513143723353345,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.683333333333333,0.0,1.0,0.0,1.0,1.1353787498962862,-0.02301727414051549,-0.009607563251941453,0.9962096673784552,-0.0404371016681718,-0.0750243954348528,0.017391938371925948,0.8475420754188043,0.05518087908959933,-0.15604063345205993,0.8224194078196226,0.6783607448672957,1.237727518207561,-0.07610490037218548,0.002201443989518313,-0.39606249801284293,0.2540247188262041,0.7285879893129517,-0.44861046947097455,0.03694186846884063,0.06718414096740952,1.030190258439884,0.29924474809607765,-0.7992933182107014,1.168428744876736,-2.2725334601292873,-3.89686116666058,4.469164149761758,-1.2021627454825312,2.143807023116604,-1.8460252505453578,1.2102033587798318,-3.8689692139969667,2.960999924054084,-0.06675267712893285,1.3652071136504862,-0.11068197419329184,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6916666666666664,0.0,1.0,0.0,1.0,1.142550744817803,-0.02238411612334116,-0.009786989491426645,0.9964702646335313,-0.03745678053126339,-0.07162469299872615,0.022669465070424177,0.8525492689747409,0.040515245417861265,-0.1292946898254788,0.8258307145837608,0.8245978970419191,1.2403308692967332,-0.09518814855487133,-0.03019000403654627,-0.3597010413605642,0.2440910906174309,0.7461583615141261,-0.4642646335386935,0.04673905504443616,0.03413702652366039,1.0537557918115321,0.29864392713425647,-0.7874546134256166,1.1656506226424757,-2.3075234435649166,-3.874257541317834,4.2550215069169814,-1.1809308071142206,2.067002339543458,-1.899348727631256,1.1335301766596813,-4.056236583587564,2.6987353646100543,-0.07773592595315182,1.4689784281077722,-0.5495257102936835,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7,0.0,1.0,0.0,1.0,1.1497118870918432,-0.021780277897672215,-0.009782780815439407,0.9967230749032314,-0.03447870302664744,-0.06763370791467489,0.027928704716315676,0.8534846493575114,0.025569601718061913,-0.10153859489992223,0.8270939995832292,0.9604628330318897,1.2395897133334575,-0.11456362443160076,-0.06236951503244558,-0.3251454728975599,0.23434253870763375,0.7630380283053426,-0.48026628159816215,0.055834038079835314,-0.00041980209238322026,1.075169181183385,0.2979491493301918,-0.7748103444089052,1.159269983038508,-2.342557606296284,-3.8463806247518946,4.039052708767086,-1.1579751833338503,1.9784678445267811,-1.9292916068510402,1.0427680965016768,-4.2292190892276365,2.44397326548746,-0.08956128034274702,1.5591343861083162,-0.9740390049520542,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7083333333333335,0.0,1.0,0.0,1.0,1.1568328458086177,-0.021211260091987053,-0.009600250264776471,0.9969584701511127,-0.031512049616544933,-0.0630983121547062,0.033157239430245095,0.8504113693133203,0.010657948066169744,-0.072929759961021,0.8264472575043442,1.084912467291998,1.2352445645115184,-0.13423077532647607,-0.09429634778241118,-0.2923834962144461,0.2247915042285334,0.7791328255895724,-0.4964194936528775,0.0641185233194641,-0.03634995829680022,1.0944886795696565,0.297151239128544,-0.7614690403238114,1.149416639226608,-2.377519906754,-3.8138425128525584,3.826221623367143,-1.133734831276756,1.8795050016389458,-1.9371379536933653,0.940505111107922,-4.38451454697226,2.1952423527719755,-0.10267044263510772,1.6370442689264775,-1.3827436474024912,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.716666666666667,0.0,1.0,0.0,1.0,1.1638858118502229,-0.020681260227862562,-0.009244496405596223,0.9971670418476647,-0.028564633662083266,-0.058067477864591814,0.038342148762618065,0.8434486563494072,-0.003943800565852973,-0.0436644436543653,0.8241179804830183,1.1976057044264015,1.2273031832377077,-0.1541889562108341,-0.12593355691332156,-0.2613751125081075,0.21544695818635448,0.7943631116659917,-0.5125519141597182,0.07150912326496735,-0.07349504454192088,1.1117565537295846,0.2962379752862733,-0.7475262732601305,1.1362242555817998,-2.412455561466726,-3.7769238691006617,3.6191534889709924,-1.1086298188806916,1.7720087525293327,-1.926032813737928,0.829813324146032,-4.519855049857776,1.9507847263225342,-0.11731969985195545,1.7043209280858385,-1.7753052026046534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.725,0.0,1.0,0.0,1.0,1.170844871063987,-0.02019333905043212,-0.008720711388438785,0.9973399185846524,-0.02564296961845236,-0.05259104405903178,0.04347076020471536,0.832771496346539,-0.017989999808800075,-0.014003513214058322,0.8203389361085017,1.2983785909992869,1.215926194729864,-0.17443836801758816,-0.15724507893408887,-0.23206427139826288,0.20631434058052187,0.8086663047983946,-0.5285200405485097,0.07794874538856464,-0.11168087579442981,1.1270017583416987,0.2951959107976781,-0.7330636915223807,1.1198282191831972,-2.4474866072681634,-3.7355400996985284,3.419329164675095,-1.0830903582363822,1.6580417844305995,-1.8993365269066653,0.7137573984509765,-4.633594893053902,1.7092897288578568,-0.13356195729667175,1.7626543816201434,-2.1514518708014663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7333333333333334,0.0,1.0,0.0,1.0,1.1776862974366324,-0.01974950412507246,-0.008034532572127799,0.9974689765336862,-0.02275228463077246,-0.046719433837965986,0.04853111271123048,0.818604178847832,-0.03126141465316258,0.015738236266257505,0.815350650177158,1.3870990038435367,1.2013627081708396,-0.19498039966530348,-0.1881925585749637,-0.20438629309685594,0.1973954522157481,0.8219971414065017,-0.544207522941496,0.08340507990581696,-0.15072162609281925,1.1402447158772155,0.29401194266466213,-0.7181487002331282,1.1003667244017754,-2.48275175558128,-3.689215349376471,3.227403527152554,-1.0575593381185506,1.5396380601696302,-1.8600645803179683,0.5951183142796854,-4.724540204199577,1.4700307233706988,-0.15128945906817792,1.8137437519989086,-2.510746889114679,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7416666666666667,0.0,1.0,0.0,1.0,1.184388756640954,-0.019350740057890257,-0.007192344862912326,0.997547004876141,-0.01989648607899397,-0.04050363965251026,0.05351222367759441,0.8012115201921358,-0.0435627555456238,0.04520779112001705,0.8094040066853041,1.4636276034321185,1.1839104643950717,-0.21581756394394283,-0.21873200142369673,-0.178274212612387,0.18868835161187936,0.8343269391345551,-0.5595211168871425,0.08786738395989273,-0.19042321253108943,1.151502270397877,0.29267441981320846,-0.7028346289890656,1.0779824376979525,-2.518365566076869,-3.637067694479523,3.043273288075188,-1.032491746998096,1.4187164149663145,-1.8107156792937085,0.47624061452514604,-4.791897297187878,1.232864060279324,-0.17028891095805188,1.8592314555403355,-2.8525530539231037,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.75,0.0,1.0,0.0,1.0,1.1909333845973877,-0.018997003598207045,-0.006201526002613071,0.9975678453512398,-0.017078103148029638,-0.03399526484857147,0.05840423176315828,0.7808857765140184,-0.054720157956677694,0.07402895537776785,0.8027609745383396,1.5278130694933372,1.1638930384637307,-0.23695315909991796,-0.24881035348295574,-0.15366507162893614,0.1801872564324465,0.8456424149892736,-0.5743861175963911,0.09134242348123606,-0.23058658104595056,1.1607924502152043,0.2911737941486946,-0.6871615093074559,1.052824173503057,-2.5543916188817435,-3.5778094233352715,2.866067958977218,-1.0083544089171843,1.2970430517764209,-1.7532595958351682,0.35896869373450213,-4.8352816595647035,0.998199306255656,-0.1902920769609595,1.9006241737351748,-3.1760349054752135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7583333333333333,0.0,1.0,0.0,1.0,1.1973037161955424,-0.018687199245741748,-0.005070638412559443,0.9975265109223872,-0.014298221369251208,-0.027246542194025777,0.06319847165785746,0.7579307130661915,-0.06457848405897072,0.10181534401323834,0.7956927264377484,1.579501412886207,1.1416495339702033,-0.2583907575919719,-0.2783621584792846,-0.13050641329610002,0.17188244479659295,0.8559443233308288,-0.5887421101510619,0.09385019552213443,-0.27101124019050116,1.168138925502138,0.28950288519719247,-0.6711575594268127,1.025048522606699,-2.590827259001021,-3.5097634593568823,2.69412222733113,-0.985625694728855,1.1762196436910055,-1.689201953925703,0.24464604836811732,-4.854755715984594,0.7669542463263523,-0.21101635563834376,1.9392062058709847,-3.4801601138377114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7666666666666666,0.0,1.0,0.0,1.0,1.203485458885108,-0.018419150189610538,-0.0038095736306931276,0.9974192825589023,-0.01155642856343172,-0.020310289589307997,0.06788752380035219,0.7326450587647579,-0.07299873721640689,0.12818060929535552,0.7884749461115259,1.6185533590919152,1.1175332992275473,-0.28013361341660165,-0.3073064111389038,-0.10876303450675064,0.16376016152029893,0.865246075717457,-0.6025394834951528,0.09541985762070468,-0.31149917631236046,1.1735750209873101,0.28765685488805554,-0.6548414058762728,0.9948215049390952,-2.627599206104192,-3.4308892565077054,2.524940966316423,-0.9647938985256399,1.057688421645926,-1.619691325123609,0.1341559849245888,-4.850872240821243,0.5404895098961049,-0.23219325784780254,1.97595311216201,-3.763690586752182,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.775,0.0,1.0,0.0,1.0,1.2094661263899473,-0.018189578458775092,-0.0024296572763554685,0.997243779881225,-0.008850789122819586,-0.013239776868613403,0.07246526992445848,0.7053076082880576,-0.07985604267713903,0.1527455406926545,0.7813804359382945,1.6448675445608665,1.0919164840355546,-0.3021840776937084,-0.33554364608774634,-0.08842406385749298,0.1558025464878323,0.8735724636915942,-0.6157369655697887,0.09608612860421091,-0.3518591108708552,1.1771470840004064,0.28563299756639576,-0.6382250075574458,0.9623203461608293,-2.664569814060739,-3.3388082158327617,2.3551518881242726,-0.9463528701620011,0.9427501511455305,-1.5456491933640026,0.0279864732718052,-4.824704455408749,0.3205172873186912,-0.25358445713023814,2.011452488677379,-4.025161860218372,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.783333333333333,0.0,1.0,0.0,1.0,1.2152345662073567,-0.017994106693804517,-0.0009437237166378651,0.9969989995867534,-0.006177861381028474,-0.006088485313788018,0.07692697328940082,0.6761660512367254,-0.08503871217487086,0.1751421663432299,0.7746693810716518,1.6584077941427013,1.0651973001096573,-0.32454311031761396,-0.36295321473611647,-0.06951050303801276,0.14798761368426558,0.8809585782365492,-0.6283003033845529,0.09588629884190143,-0.3919109172358396,1.178916975775955,0.28343044726921823,-0.6213171977316498,0.9277354739354556,-2.701553290340343,-3.2308198140713995,2.1804404365776247,-0.9307936770883135,0.8325913971525845,-1.4679069574562087,-0.0736939840543982,-4.777847404221051,0.10898272355477356,-0.2749863239057493,2.0458372231226707,-4.262851664160772,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7916666666666665,0.0,1.0,0.0,1.0,1.2207804306253531,-0.01782729190467364,0.0006338308899279288,0.9966853149989171,-0.0035327697840614168,0.0010902498554896994,0.08126939020153026,0.6454314877212216,-0.08844890313986567,0.19501561801301334,0.7685779678905866,1.659231890654721,1.0378067271797151,-0.34720996586604747,-0.38939064298893633,-0.05208338991453257,0.1402893185363604,0.8874489869774707,-0.6402020815273922,0.09485789553663761,-0.43148990094120604,1.1789634627263192,0.2810498921679666,-0.6041277205054013,0.8912728184248164,-2.738339589934564,-3.103906096804585,1.9954751477530481,-0.918591462658026,0.7283161364001378,-1.3873322371625751,-0.1709590262318919,-4.712378586906166,-0.09207850304608023,-0.29622497717740504,2.078735721838756,-4.4747387874838696,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8,0.0,1.0,0.0,1.0,1.2260936565330989,-0.01768269861456283,0.0022870124128289873,0.9963044310696018,-0.0009093385674135733,0.00824370979122765,0.0854909060193192,0.6132807096399884,-0.09000528543736175,0.21202538226899587,0.7633067291463622,1.6475171491142002,1.0102109452690387,-0.37018210348319003,-0.4146849830161929,-0.036252583908795294,0.13267775597329848,0.8930971805098848,-0.6514225073372625,0.09303698173803657,-0.47045056035094235,1.1773823340585203,0.2784933643162615,-0.5866716023676706,0.8531564941440578,-2.774720268765735,-2.954736911268471,1.793865254464978,-0.9101874441661867,0.6309738366111151,-1.304919596865639,-0.2640530156381288,-4.6307682500632055,-0.28069810857371813,-0.31714532028766174,2.109244109414816,-4.658452220803431,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.808333333333333,0.0,1.0,0.0,1.0,1.231164037320621,-0.01755301395567025,0.003998214766424516,0.9958592924082929,0.001699715810856899,0.015320346162332382,0.08959167212630538,0.5798687117530837,-0.0896478831977013,0.22584875754784128,0.7590112185095876,1.6235744417442837,0.9829048045705842,-0.3934553036788097,-0.4386362581767442,-0.0221856356734496,0.12511952780025729,0.8979652175876559,-0.6619507414751529,0.0904570119426688,-0.5086693717755928,1.1742851609167573,0.2757641368298389,-0.5689736520151544,0.8136319480780926,-2.8105042549608608,-2.7797150448535914,1.568253882960383,-0.9059674064485324,0.54157118754387,-1.2218073222728254,-0.35333254200696634,-4.535730596931233,-0.45513534643886633,-0.3375996884548571,2.135927522240184,-4.811207789764731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8166666666666664,0.0,1.0,0.0,1.0,1.235980993144656,-0.017430199005378334,0.005748253132713972,0.9953539484913635,0.00430255359777174,0.022270347945559276,0.09357369763261769,0.5453541721080006,-0.08734478542240713,0.23619072039684166,0.7557992912581128,1.5878374879811998,0.9563905117152124,-0.41702384106587104,-0.4610135670970861,-0.010115019192788911,0.11757829919915627,0.9021233669689493,-0.6717859627084762,0.08714810603792046,-0.5460460702997962,1.169796744951206,0.27286670284201386,-0.5510728103303342,0.772969697647979,-2.8455020652458507,-2.575137762314509,1.3107343520013757,-0.9062401244710064,0.4610484951121818,-1.1391649920796598,-0.43922885701260655,-4.430007999003285,-0.6140199303040195,-0.3574444489998174,2.156859991145339,-4.929724724958402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.825,1.0,1.0,0.0,1.0,1.2405336707015844,-0.017305657656038472,0.007516499053947614,0.9947933910469114,0.006907988945284759,0.02904608806468911,0.09744082109658615,0.5099395372856728,-0.0830996963411901,0.2428049123832846,0.7537401622733985,1.5408116618444174,0.9311362141957383,-0.4408803380995739,-0.481555220881986,-0.0003400631400933371,0.11001552572574051,0.9056493591728589,-0.6809368246764805,0.08313653099245868,-0.5825028384256475,1.1640514954116903,0.2698067293465086,-0.5330259854960654,0.7314698693287859,-2.879448577451297,-2.3375768955839993,1.0138279941257002,-0.911220950485798,0.39019955385872773,-1.0578930402837794,-0.5222386518755382,-4.316088076949698,-0.7564506180096497,-0.3765540354859209,2.169710032102974,-5.010109109993768,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8333333333333335,1.0,1.0,0.0,1.0,1.2448115109637172,-0.017170388840367375,0.009281199263542496,0.9941833923290461,0.009525349740981267,0.03560225694416779,0.10119846568425243,0.3468843099429757,-0.039357886867350665,0.25937770461530624,0.7801343317953907,1.4258863122729968,0.9691110295313737,-0.4650146506900593,-0.49997318202348606,0.0067821140426394255,0.1023912833577263,0.9086266928665948,-0.6894175133798726,0.07844412850666149,-0.6179808715822912,1.157189234651045,0.26659080225058185,-0.5149109764619513,0.6894678791480828,-2.8843450984585783,-1.2789032051617344,-0.13451291892295653,-1.0553391465420854,0.23275868697387292,-1.1082476430698551,-0.6598744397097489,-4.510704145721414,-0.7528177660229085,-0.44814182149487514,1.9541036381633958,-4.95457663094057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.841666666666667,1.0,1.0,0.0,1.0,1.2466279098356423,-0.016831540181230054,0.011412445115916527,0.9934934659275445,0.012461627615374076,0.04144044975471863,0.10534766339948343,0.1910872338051647,0.0005593073401196358,0.2566710561435743,0.7835666638609422,1.3338160677087725,0.9970280573475134,-0.48895275640721686,-0.5028702743013482,-0.0025819451221426124,0.09242653995003909,0.9095286706224235,-0.6994076187276448,0.07213862366396287,-0.6576812408543378,1.1515045326446418,0.2623376989882607,-0.5004575915266755,0.648893592146443,-2.8476898700284825,-0.22312854470209142,-1.384246719498405,-1.1758323591426236,0.22882041096761618,-1.5051718764595257,-0.7697644945428503,-4.698804916347317,-0.7604431462577255,-0.4889093332508876,1.7068285685425388,-4.851036064251331,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.85,1.0,1.0,0.0,1.0,1.2482762048194482,-0.016559906754085644,0.013289462395293246,0.9927676060741756,0.01518511291035623,0.047228983434063725,0.10932207401653955,0.1818404313232534,-0.004952767737359802,0.2326581858651588,0.7451480006003319,1.309046744398768,0.9555675369458971,-0.5124761485238674,-0.5036919911018543,-0.016288664615667324,0.08279407737201591,0.9124403663827217,-0.7145037113208647,0.06561472026428065,-0.6962942868547465,1.1445151822134163,0.25844231336306706,-0.48646383365290896,0.6086172780772273,-2.7881521173316806,-0.03230837799565567,-1.7100705094042719,-1.1483494649663974,0.44339824615236667,-2.00341722005571,-0.8026526328388645,-4.511863934105318,-0.932770680805004,-0.454911298534314,1.6883073440004803,-4.805464685562506,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8583333333333334,1.0,1.0,0.0,1.0,1.249966920502382,-0.01632675265228631,0.014993514717424144,0.992015406812385,0.01780957463326445,0.052828246839140953,0.11312571809114345,0.18831488767463578,-0.011061182233847756,0.21598468058304643,0.7204993705362192,1.2527090357828616,0.9170141105903663,-0.5354219583627449,-0.5034087472679425,-0.031083120278880477,0.07328738220059913,0.9169186413916296,-0.7327979057285733,0.05876107978331513,-0.7328789730894264,1.135958354631225,0.2547558440126888,-0.4723191357933341,0.5688025140537346,-2.708501300459125,0.0849748109665649,-1.767744752702793,-1.1381343090893457,0.6141830506103818,-2.324048922191162,-0.8408038079223518,-4.255676805899329,-1.1049538913648016,-0.42976363508846926,1.709417583467936,-4.720160676136336,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8666666666666667,1.0,1.0,0.0,1.0,1.2517497710200767,-0.016113250091398485,0.01654179648666284,0.9912471193525502,0.020364365628424152,0.05812817492799575,0.1167713848257506,0.19940134112871316,-0.016526531769543634,0.20054945720558304,0.6983662881069066,1.1730438768483396,0.8816611355290153,-0.5576178368648528,-0.5022757442524115,-0.045751077160713874,0.06382517222052682,0.9226767505595614,-0.7532378600240507,0.05160132346557479,-0.7672222336197353,1.126099284024003,0.25127958611159257,-0.45797354059511003,0.5299479334749551,-2.6093329049079395,0.18455263724439286,-1.722210321444199,-1.1355068060533424,0.758323311442628,-2.5430280274956374,-0.875482740518248,-3.985343196854929,-1.2405772558267225,-0.4033036884457847,1.7253791019671516,-4.568129836223505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.875,1.0,1.0,0.0,1.0,1.2536413797591164,-0.015906802733013606,0.017928612403237457,0.9904733775180815,0.022864588034459697,0.06304825301834908,0.12026893558695584,0.2129366495625379,-0.021446142093847737,0.1844089244367102,0.6770627209682857,1.0754444032895398,0.8489379118177706,-0.5789108401112105,-0.5003328699805359,-0.05978662563628379,0.05436226876637676,0.9295573632490067,-0.7751817061868339,0.04416970077467766,-0.7993013597036752,1.115282067034113,0.24803411587192573,-0.44356281742721493,0.49266701678334285,-2.492152483092205,0.2853092649449984,-1.6336721736759747,-1.1375432094893363,0.8866358446492151,-2.6939470783792108,-0.9061212075355651,-3.715726991603767,-1.3347924780368459,-0.37419439908040364,1.7203261285806382,-4.338002799188706,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8833333333333333,1.0,1.0,0.0,1.0,1.2556527262619628,-0.015696814573360807,0.0191422923672848,0.9897049779942727,0.025321910585204388,0.06752196051822745,0.12362702879396455,0.22870632674167912,-0.025988252965872045,0.16707167727548375,0.656195228954108,0.9624363423745043,0.8186663088412472,-0.5991537115830562,-0.49752058983666153,-0.07297894672198012,0.04486611872903788,0.9374540146370484,-0.7981369779970375,0.03649930333998204,-0.8291510168131314,1.1038527427233888,0.24504301279358584,-0.4293014384520994,0.45764788682180996,-2.357331606599533,0.3962258319264489,-1.5280177364021532,-1.1430589195658327,1.003718920991381,-2.7897087966535428,-0.9328465119088415,-3.4515699596958194,-1.3878209181885737,-0.3421372602591577,1.6864045130125804,-4.02064632381731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8916666666666666,1.0,0.0,0.0,1.0,1.2577959863734303,-0.015473416485297625,0.020169645857649434,0.9889526863653776,0.027746884888804887,0.07148960803761284,0.12685397300355417,0.24691890672821468,-0.03031844538289131,0.14841600069226984,0.6356080361888263,0.8353268436454093,0.7908164239839631,-0.6181997002212027,-0.49372910611509513,-0.08525358790965301,0.03531128677361288,0.9462860119321964,-0.8216768527977263,0.028622258909530303,-0.8568275256986055,1.0921517183976368,0.24233182820093976,-0.4154560755436719,0.425656244719721,-2.2050088040666127,0.5217280119393353,-1.417402793107635,-1.1513072834372342,1.1122347874260452,-2.8368299595161406,-0.9557453810887516,-3.1949428432394367,-1.4001441680102822,-0.30687994621735604,1.617822008965577,-3.6067189494581,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9,1.0,0.0,0.0,1.0,1.260085488820308,-0.015227089079734206,0.02099696892750246,0.988227003684813,0.030149613963147855,0.07489554675012697,0.12995786644700513,0.2677860456883488,-0.0345765922842011,0.128363130991189,0.6152187619190755,0.6948725700049314,0.7653602675121154,-0.6359038583174997,-0.48882512297100594,-0.09660232660710737,0.025677664005083978,0.9559912610941491,-0.8454174773223065,0.020570213655169513,-0.8824000642004554,1.0805170065898841,0.23992834702329657,-0.4023377383026731,0.3975359043308416,-2.0355795877380256,0.6636665185290824,-1.307489892360513,-1.16170184226963,1.2142845208209097,-2.8400714812281835,-0.9748770927039418,-2.947325799340701,-1.3716120226917017,-0.26813346380819225,1.5097206734268853,-3.0873333440740836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.908333333333333,1.0,0.0,0.0,1.0,1.2625371324684276,-0.014948488876268068,0.02160989519538619,0.9875379669119999,0.032540091250803635,0.07768640942412473,0.13294633565460715,0.29151188097793435,-0.03878229109921777,0.1066047484332208,0.5949151067370446,0.5405233398051175,0.7418270424251829,-0.6521260266835032,-0.48266799747294375,-0.10704508611566156,0.01594958940245238,0.9665240872792116,-0.8690113774848627,0.012374307364464605,-0.9059496223542839,1.0692915180194418,0.2378629371374699,-0.3902940643198905,0.37420068898515296,-1.8486940855766099,0.8231822292043456,-1.2000158474910314,-1.173683217263127,1.311998175222846,-2.8025025488256583,-0.9906197022977264,-2.710710102505358,-1.2983431636172726,-0.22565907189159073,1.3571049077904718,-2.4508050212783616,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9166666666666665,1.0,0.0,0.0,1.0,1.265168075695603,-0.014626419117221871,0.02199017330211217,0.9868960327181262,0.034928651060023845,0.07980212438485197,0.13582279221891447,0.31619501098451686,-0.04224744577064463,0.08743051437580364,0.5778425556191104,0.3947757593338158,0.7172583972844657,-0.6667154264104432,-0.4751054191509335,-0.11660259073195789,0.006116277050698526,0.9778578973478632,-0.8921258531360675,0.004059885283540738,-0.927578565908878,1.0588779538629296,0.23616736249177006,-0.3797193231728319,0.35668915397620227,-1.6629986163178878,0.9814242730667377,-1.1127146341175456,-1.1905022871434683,1.397506684521479,-2.7558752613087667,-1.0119723329982755,-2.481563386354062,-1.2413036314828663,-0.18950461608453872,1.1973193521566405,-1.8137627470819084,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.925,1.0,0.0,0.0,1.0,1.2679736807878639,-0.014251618509648636,0.02220107037032812,0.9862968554055742,0.03732384756674674,0.08137878179142573,0.13857466325084997,0.3379388430313241,-0.044409921542341954,0.07731462337788568,0.5669911017027074,0.29265657087337804,0.6889858524876069,-0.6798426702888013,-0.4663109262551648,-0.12559033001762065,-0.003892115383272088,0.9898158653545696,-0.9149426318400088,-0.004491898185506653,-0.9473090121268516,1.048603124161394,0.23470452686939425,-0.3703387417839465,0.34397130986712116,-1.5085604038533629,1.107266966543753,-1.0701813279980754,-1.2153573414874679,1.45714853654056,-2.7481182873205423,-1.0470070315037903,-2.249550295019618,-1.2960892714375394,-0.17197497874556267,1.0970860490166412,-1.3771288738054088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.933333333333333,1.0,0.0,0.0,1.0,1.27092748589936,-0.013828087741843617,0.02234102693597337,0.9857264408147308,0.03971877523370593,0.08264835505146706,0.14119154429553837,0.3558370373474322,-0.046228951917619505,0.07447325102292061,0.5584442943847754,0.22831392025545136,0.6592165539815587,-0.6918580998079993,-0.45665096970853764,-0.13443894619859248,-0.014139678640759271,1.0021437062902059,-0.9379278245914099,-0.0133902319081891,-0.9650710708258716,1.0372764660056373,0.23330111284601068,-0.3614345556892212,0.33373700607944545,-1.3827716906798182,1.2017068722801938,-1.0630884359989885,-1.2434011429993257,1.4932151685422723,-2.7752516327170507,-1.0853635538508377,-2.0112148673103025,-1.4446042728174913,-0.16544790984436286,1.0581944651325736,-1.135894501430058,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9416666666666664,1.0,0.0,0.0,1.0,1.2740123924627187,-0.01336743598780948,0.022443302774395612,0.9851798043002795,0.04209696424504046,0.08369342427327191,0.14368023362314142,0.3717666107343766,-0.048577709045060036,0.0740911255373063,0.5486525628469544,0.17784946976047267,0.6305878298292121,-0.7028888651334649,-0.44628247838382823,-0.1433084706176038,-0.024615467766594182,1.014702784830274,-0.9611968257186263,-0.02258129074968728,-0.9808292599153566,1.0245263862811025,0.23194706170532153,-0.35270216736507026,0.32503973484328685,-1.2679446140397155,1.2825421866291153,-1.0686038303485363,-1.270400310157336,1.5150238665888116,-2.807079792264513,-1.1171927853182135,-1.7712504721170252,-1.6204193437648273,-0.15883665686410697,1.045293106184485,-0.9740740092026523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.95,1.0,0.0,0.0,1.0,1.2772230434486884,-0.012876356256896577,0.022520753519622554,0.9846554749467447,0.04445035076483062,0.0845444456931517,0.14604793280612519,0.3871020139492628,-0.0513550742294793,0.07466141522682389,0.538024032630019,0.1323402583955082,0.6032577042217481,-0.7129905100419945,-0.4352752665980524,-0.15224901003773475,-0.03531301714338154,1.027394104066686,-0.9847124877958184,-0.03201011166349266,-0.994591912027822,1.0102694769428902,0.2306538352316089,-0.3440130039194798,0.31750243925940125,-1.1580519241040022,1.3572953501633234,-1.077521014468585,-1.2970161449467768,1.5259826581001823,-2.830870243144834,-1.1429889400281248,-1.5334331759119046,-1.7991504327446028,-0.15084665390920793,1.0434809124415112,-0.8432743787073482,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9583333333333335,1.0,0.0,0.0,1.0,1.2805597081663043,-0.012357566016621243,0.02257848861798907,0.9841535723783498,0.046776007054291135,0.08521093709901692,0.1482998561625111,0.40249705899749016,-0.05440109519182368,0.07559993569508587,0.5269780819815231,0.08811296815437877,0.5769609524834458,-0.7221897305351983,-0.4236608892144395,-0.1612671541920802,-0.04623240351570713,1.0401358291319438,-1.0083779964377069,-0.041631106416822695,-1.0063864795138884,0.9945405457353591,0.22943295080683473,-0.3353108188243784,0.31098516186483105,-1.0506186901996828,1.4292257615355286,-1.0860910695245019,-1.3237857662295256,1.5276311582018876,-2.8418400684047596,-1.1636790067933667,-1.2996003755518237,-1.9706650042197338,-0.1415905557237923,1.0466350682608572,-0.7233204336677168,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.966666666666667,1.0,0.0,0.0,1.0,1.284025085615891,-0.011811733185906613,0.022618494954498105,0.9836749153618968,0.0490734039377257,0.08569367663993377,0.15043954166949275,0.4182302803113382,-0.05762517910471496,0.07665671660099625,0.5157210088851033,0.043613154853792135,0.5514493815435824,-0.7305008215453226,-0.4114548372391269,-0.17035052786314311,-0.05737611324720696,1.0528546233700509,-1.0320764889358978,-0.051404761776715435,-1.016251918287019,0.9774250602058946,0.22829399263621236,-0.3265690861151322,0.30544709869827263,-0.9445972224662302,1.4996275012050986,-1.0925195651833914,-1.3508411397655053,1.5207657237830663,-2.838575918195261,-1.179812121415519,-1.0709614908987009,-2.130571895734208,-0.13125739750543708,1.0522765045104954,-0.6058444560060283,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.975,1.0,0.0,0.0,1.0,1.2876227557255029,-0.011238625961127088,0.022641463964905652,0.9832205952806379,0.051343007161959414,0.08598970159992557,0.15246943251138478,0.43439889874619103,-0.06098323710536456,0.07771171749209946,0.5043282113947088,-0.0018296252512193523,0.5265523020634154,-0.7379330175763021,-0.39866709752768786,-0.1794758136118034,-0.06874642251179888,1.0654819245283282,-1.0556875950742945,-0.061294641773748014,-1.0242358376955334,0.959031014139789,0.22724532751507745,-0.3177728770825368,0.3008877542647306,-0.8395892221272705,1.5688532122150334,-1.0956222259980053,-1.3780804365174935,1.505850230216379,-2.8210551483559776,-1.191664076528973,-0.8484727766732902,-2.2768844492846196,-0.11995280987687429,1.0594939606084164,-0.48755646738312564,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9833333333333334,1.0,0.0,0.0,1.0,1.2913564327934361,-0.010637675186687982,0.0226475563440361,0.9827917694384868,0.053585634064719584,0.08609440566919666,0.15439129204179228,0.45101346051782853,-0.06445222853487372,0.07869753521635549,0.4928117426807511,-0.048510449480480944,0.502159456288803,-0.7444939752474438,-0.3853072837022097,-0.1886108982964432,-0.08034412052249852,1.0779521272069905,-1.0790940747418307,-0.07126582971886498,-1.030393131231574,0.9394769860511509,0.22629477913826446,-0.30891085343832525,0.29732115757522054,-0.7355074777888704,1.6367967646828074,-1.094362701336556,-1.405288606563457,1.4831785430196254,-2.789799000529718,-1.19937936256623,-0.6329588537243103,-2.408634281708677,-0.10771934871482647,1.0680778817146064,-0.36741123365353956,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9916666666666667,1.0,0.0,0.0,1.0,1.2952295967226852,-0.010008230231422876,0.022636738402334867,0.9823895584308767,0.055802172420130566,0.08600243154064141,0.15620644931720254,0.46804218783668156,-0.06801645304244608,0.0795684748714601,0.4811558697847023,-0.09656294996609319,0.4781983249312626,-0.75019147553945,-0.3713871514496411,-0.19771519196741266,-0.0921678992878565,1.0902015669119887,-1.1021842450831232,-0.08128429781651851,-1.034785151924272,0.9188871094446444,0.225450005036497,-0.29997157905396005,0.29476423370383825,-0.6324185059191567,1.7031265905261939,-1.087717368621709,-1.4321941210470432,1.4529449164772368,-2.7455140263819366,-1.2030555051648184,-0.42516027289833946,-2.5252742649050153,-0.09456613331301544,1.07814698788256,-0.24538721809038155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0,1.0,0.0,0.0,1.0,1.2992453009624632,-0.009349671440468048,0.022608937933192148,0.9820149921342879,0.05799346156722239,0.08570805642226131,0.1579159355583643,0.4872238052548923,-0.07220208930586697,0.08124738959771553,0.4671234076433922,-0.1589577464845094,0.4559373921558675,-0.7550342836794297,-0.3569218405267731,-0.20673952110680502,-0.10421402253994924,1.1021678758149445,-1.1248526418481963,-0.09131675480494529,-1.0374791357798796,0.8973890816360673,0.22471867691638087,-0.2909417369736159,0.2932313706070475,-0.5146568903587512,1.768311038546967,-1.0404531171483178,-1.454514780691971,1.411249728302062,-2.658112570170479,-1.1992161535781076,-0.22551380433733836,-2.602637650615749,-0.07529247735957312,1.0885036606440313,-0.08837132899429334,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0083333333333333,1.0,0.0,0.0,1.0,1.3034396969877786,-0.008661787445472103,0.022574021923415375,0.9816774915694204,0.060160270042724305,0.08509617150110363,0.15952644310654335,0.5108613754789953,-0.07737956501637053,0.08442305010536269,0.4491377046082523,-0.25156256347652245,0.436689918888832,-0.7587690903787625,-0.3419153008071916,-0.21505607725321796,-0.11640981229938935,1.113722395717023,-1.1464861212526312,-0.10127123370948697,-1.0385437153298942,0.8755098152677152,0.22419513041383746,-0.2818298513765595,0.29329137822060003,-0.36516369054575115,1.8326467126089363,-0.9095271755452405,-1.468314660701125,1.3553183818810766,-2.4937538807807202,-1.1855055258134504,-0.03683890561679615,-2.607027186645501,-0.04478902324613954,1.0951990408475865,0.14966453436301763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0166666666666666,1.0,0.0,0.0,1.0,1.3078558026361542,-0.007938415614043213,0.022538981719523708,0.9813875962575267,0.062312587402170674,0.08402843851752843,0.16104269273532065,0.5377270646523018,-0.0826801153158567,0.08757455763207866,0.43042272235391127,-0.3647455362812546,0.4189929182051838,-0.7611203451885256,-0.3263777286499575,-0.22189830736589236,-0.12868593355163466,1.1247565155129624,-1.166415206527875,-0.11107518023516946,-1.0380931175401595,0.853938628525309,0.22397219319561187,-0.27268841962615614,0.2957257795130978,-0.19968016921033227,1.894093323214584,-0.7192180184120578,-1.4779932490608678,1.2915216942684493,-2.2816587473374073,-1.1675890713242576,0.13558583820392656,-2.548427159116591,-0.008702918848619845,1.0964167254304125,0.4504054663603174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.025,1.0,0.0,0.0,1.0,1.3125015580289532,-0.0071699307735660555,0.022497576627009287,0.9811467236119642,0.06446408370742718,0.08247344733372404,0.1624611311735099,0.5651533711627482,-0.08741166127514607,0.0892866001197393,0.41333218463787175,-0.48132529816030756,0.4010852171403282,-0.7620970931989347,-0.3103470787536152,-0.22704304422675226,-0.14104303311707048,1.1352477572881639,-1.184513767041588,-0.12073105156489126,-1.0362839513598288,0.8330360292824387,0.22405008176636046,-0.26355623928605265,0.300798135993272,-0.04033589781611724,1.9493570681632588,-0.5122539777361057,-1.4875187383526374,1.2252532942394545,-2.0645170531666412,-1.149755769353883,0.28943378398685216,-2.4561783119351266,0.026963481172110337,1.097346388075282,0.7631780765044116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.033333333333333,1.0,0.0,0.0,1.0,1.3173706262169673,-0.006351658728236968,0.022444063998870528,0.980952735868283,0.06662018417663619,0.08043731945704638,0.1637782607410958,0.5918539450797176,-0.09168789196267907,0.0894853405045118,0.3973459978801592,-0.5946858926630156,0.38264121503396964,-0.7617926101521275,-0.29388844418056986,-0.23043587366149412,-0.1534779125241786,1.1451774037502866,-1.2008238240806524,-0.1302377763910675,-1.0332692211403787,0.8130023233263902,0.22442158454848038,-0.2543993131582348,0.30844541412150467,0.1060508446228936,1.9954680450112616,-0.3015731521086523,-1.4961459096719931,1.1561902736402363,-1.855685416222368,-1.1313137100603752,0.4257953960890726,-2.3450795186087126,0.06189792259128579,1.1057079331724735,1.0572050970656677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0416666666666665,1.0,0.0,0.0,1.0,1.3224515063966487,-0.005482885659927548,0.022375044820178058,0.9808017123580525,0.0687811215758851,0.07794217385309005,0.16499144185483886,0.6172823697073408,-0.09568847217592066,0.08835102733646684,0.3819918592059901,-0.7018378661096782,0.3636105253793367,-0.7603295791218865,-0.27708927800342753,-0.23206926342856313,-0.16597879827827036,1.1545175951821678,-1.2154418573119607,-0.13958628006589752,-1.0291873614250109,0.7939513706389602,0.22508171380954856,-0.2451277737331781,0.31841822094436645,0.23712223330738302,2.030314771003522,-0.09084619451523501,-1.502973763477733,1.083268080985298,-1.659409978412909,-1.1114857396361562,0.5464530051892469,-2.2233641026856965,0.09635870195698337,1.1268511825702017,1.3152412532822833,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.05,1.0,0.0,0.0,1.0,1.327731154075359,-0.004565341670667908,0.022289114539845396,0.9806887663030217,0.07094420258527026,0.0750179231303647,0.1660986904698896,0.6412290584720598,-0.09955273971902921,0.08607645096123512,0.36697741719972304,-0.8012503929817199,0.34397861510557626,-0.7578405729303378,-0.2600498646638445,-0.2319499769034147,-0.1785274752488075,1.1632318717667083,-1.2284806570542008,-0.14876253871833678,-1.0241616710538912,0.7759462549482953,0.2260275629144301,-0.23561846011539808,0.3303661016762094,0.3522254882462428,2.052842925459956,0.11854060357588847,-1.5073270523891713,1.0056276537962994,-1.4768560321838287,-1.0898247564554242,0.6531074091665623,-2.0960299726211673,0.13053666735037495,1.1636393386801842,1.5283515233329137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.058333333333333,1.0,0.0,0.0,1.0,1.3331964556446112,-0.0036022767360054213,0.022186216954034832,0.9806085189521054,0.07310497583538235,0.07169879167980281,0.16709840914363758,0.663996859471015,-0.10298061494017602,0.08238151093155736,0.35184301376063,-0.8950841369647179,0.32160748556326646,-0.7544591543177824,-0.2428752292457616,-0.23009358670229832,-0.19110091581808988,1.1712780560787728,-1.2400561245150246,-0.15775002600682125,-1.0183022379389015,0.7590175377619407,0.2272573249320548,-0.22573378475517503,0.34389074633324834,0.4552619301473415,2.0654202678625833,0.3255278457670613,-1.5080583949785515,0.9232291725531327,-1.3055521280234839,-1.0673984505350538,0.7441527439242268,-1.9555080530718505,0.1632718064686911,1.2127863612925667,1.7077599225695628,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0666666666666664,1.0,0.0,0.0,1.0,1.338837083069302,-0.0025887286114577917,0.022060361295451834,0.980560274101702,0.07525863586338277,0.06799774984379126,0.1679702134242277,0.6857907899126271,-0.10584955218767594,0.07712016442699363,0.3366227723635411,-0.9842657866661542,0.29530847287907025,-0.7502528740945488,-0.22562619353280144,-0.22652451280729702,-0.20366178183178335,1.1786190246425938,-1.2502398591879256,-0.166552512893921,-1.0117591253218208,0.7433544540637644,0.2287487596889083,-0.2154053540938553,0.35882876705236877,0.5482004639173521,2.069511185281846,0.5290612286463531,-1.504580164658612,0.8362032534066,-1.14441440173215,-1.045019606071571,0.8190485825145943,-1.7983722116556922,0.1936006731967277,1.272052848969219,1.8601366514692752,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.075,1.0,0.0,0.0,1.0,1.3446426164882892,-0.0015251607927641636,0.021909217322611776,0.9805406167005744,0.07740142104837439,0.06394224614545559,0.16870242493236767,0.7060653516722722,-0.10887600126274372,0.07106957116150811,0.32180575609590995,-1.0634931699718115,0.26836394229985405,-0.7453224799191599,-0.20838337615773084,-0.22127589955819243,-0.21617725189573342,1.1852147769688828,-1.259129697877227,-0.17516701944134744,-1.004651428230325,0.7290446675676792,0.23048400281866693,-0.20453290393902138,0.37489302385773626,0.6255364519431916,2.0615637022488102,0.7274430043946079,-1.497558556895236,0.7438372854489117,-0.9976006632514878,-1.0207705681496793,0.8835427905235171,-1.6436916861165152,0.22324368364089464,1.3472626025814616,1.962311909411496,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0833333333333335,1.0,0.0,0.0,1.0,1.3506006221446865,-0.0004228203698392787,0.02173808117791231,0.9805410417248906,0.07952692308758304,0.05958730435968139,0.16930471687608967,0.7245360640095313,-0.11239616076629541,0.06468674381100228,0.30704994443652944,-1.1301881096974529,0.24233497026376044,-0.7398272665621622,-0.19126679849532127,-0.21440046273405355,-0.22862109111337062,1.191016312733409,-1.2668665369087837,-0.18356535569641566,-0.9970334121464288,0.7159595926284892,0.23246948774958986,-0.19295097738416428,0.39153396554256037,0.6860360975501734,2.0408267680976455,0.9180657304522133,-1.4867596427361758,0.6456780920886551,-0.8663599689064672,-0.9933851306265723,0.941004588047365,-1.501703789575466,0.2533903046488978,1.4398095415220409,2.0049924564977264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.091666666666667,1.0,0.0,0.0,1.0,1.3566994181362753,0.0007100618746641173,0.021550164183715602,0.980555483370347,0.08162586899526224,0.054980117966826524,0.16978029382571835,0.7413738092850035,-0.11623059822565768,0.0578356511937716,0.2919356020727791,-1.1856860569258056,0.21613422749994965,-0.7338885449599903,-0.17436959668943675,-0.20597480405065555,-0.24095657927466968,1.1959760785036937,-1.2735690306923348,-0.19172343828512364,-0.9889680184295355,0.7040162710747547,0.23470717456281523,-0.18053607824698736,0.40830956479936503,0.7331178800391291,2.010132256403196,1.098078677588122,-1.4714523761144944,0.5420871061849919,-0.7487753229145344,-0.9634678681453501,0.9908076898992535,-1.36869307467949,0.2834242246359103,1.5448880362794448,1.9994390910655235,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1,1.0,0.0,0.0,1.0,1.3629280668114043,0.0018661994003496597,0.021347274697969654,0.9805791055910403,0.0836895773124743,0.050164976920878145,0.1701297957976864,0.7566380340915857,-0.12032524915685716,0.05045864654098636,0.27649160613376733,-1.2305969927817462,0.189316529750498,-0.7276086352281768,-0.15776459422193467,-0.1960991514409182,-0.2531452973819455,1.2000510978364922,-1.279346125624026,-0.19962315349883816,-0.9805199506481079,0.693148041383831,0.23719322482685504,-0.16720284344617353,0.42485795039365243,0.7687929091776047,1.971713941003752,1.2646929093891501,-1.451466440810053,0.43358373500790304,-0.6439159348132373,-0.9316043625297987,1.032849799291029,-1.2434044387272514,0.3127676544640512,1.6582714150755717,1.9540777663320452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1083333333333334,1.0,0.0,0.0,1.0,1.3692755313045697,0.003038591859864318,0.021130201321608526,0.9806080461491247,0.08570961841012416,0.04518452189158251,0.17035281072272188,0.770317981856121,-0.1246408159965873,0.042534721183703245,0.2607328063570532,-1.2652815082828774,0.1616980141564074,-0.7210753298070303,-0.14150769767270754,-0.1848965888941697,-0.2651476866215039,1.2032024740871587,-1.2843009629392221,-0.2072501776606203,-0.9717538551080184,0.6832928637626339,0.23991996880388275,-0.15289822132906117,0.4408775275715658,0.7946239121924359,1.9276518255615755,1.4150116437946691,-1.4267393634171965,0.3205941402351353,-0.5510650403927242,-0.8982253878193691,1.0672017570043457,-1.1255664947037824,0.3409725061216784,1.776379724087483,1.8754024062812702,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1166666666666667,1.0,0.0,0.0,1.0,1.3757305913884719,0.004220503632785466,0.02089889910692017,0.9806392843559354,0.08767789116719737,0.04008034721878584,0.17044866425201885,0.7823571594791243,-0.12912998809658927,0.03407246564256841,0.24466760490138661,-1.2900179900706292,0.1332153458120135,-0.7143649033583028,-0.12563706379590842,-0.17251562404434037,-0.27692428677223213,1.2053943335070778,-1.2885305429639047,-0.21459357662916098,-0.9627332546980355,0.6743885998054346,0.242876099928883,-0.13759651471138215,0.45611465716500693,0.8119521260436446,1.8799982024176898,1.5460629796938563,-1.3972946018172905,0.20341786093330594,-0.4695086977520102,-0.8637029860964895,1.0940292100596638,-1.0153819800787556,0.36760750488198934,1.8960636890728708,1.7687773220358505,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.125,1.0,0.0,0.0,1.0,1.382281220151509,0.00540531672090591,0.0206527580427036,0.9806706392751728,0.08958648467902149,0.03489297678781622,0.17041666349712203,0.7926507799341127,-0.1337270077297144,0.02510642637415364,0.2283032104843672,-1.3050855064920914,0.10386497338980842,-0.7075427943729695,-0.11017439429907938,-0.15912887256593877,-0.2884359299851254,1.2065927717693805,-1.2921261079017556,-0.22164522742889511,-0.9535200349403573,0.6663698307613213,0.2460467605519159,-0.12129715984451332,0.4703571496054966,0.8219865891613298,1.8307472571363654,1.6549435177742895,-1.363233421082446,0.08220106782651282,-0.3984644818496452,-0.828390242598856,1.1135520021723488,-0.9133161959935343,0.39221074559776137,2.014444255311635,1.6389066563599652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1333333333333333,1.0,0.0,0.0,1.0,1.3889143739178385,0.00658665879012455,0.020390748611129904,0.9807007200494345,0.09142786811865859,0.02966182780089637,0.17025633203330426,0.801071853221712,-0.13834158515673692,0.015691720926832867,0.21167889449935307,-1.3107881139203512,0.07369536912731024,-0.7006651268722807,-0.09512460951030233,-0.14493323208143555,-0.2996448437902729,1.2067643513041864,-1.2951716176613988,-0.22840008067247525,-0.9441740546618297,0.6591666632055424,0.2494129456888457,-0.10402244378952157,0.4834297681043397,0.8257757452549686,1.7818918011872333,1.7388056323724421,-1.3247768578975516,-0.04308882298313055,-0.33696681500118064,-0.792666715804824,1.1260312091417402,-0.8199470453689828,0.414251583043474,2.128884794923915,1.4900474252741736,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1416666666666666,1.0,0.0,0.0,1.0,1.3956157133355913,0.007758511292823015,0.02011159188864217,0.9807288782099443,0.09319504259637412,0.024425034044396457,0.16996755335234476,0.8074545847829963,-0.14285850710103826,0.005909810794546534,0.19484242243698113,-1.307492620168726,0.04278726026605004,-0.6937798652853867,-0.08047619761262549,-0.13014877869306474,-0.31051554428341793,1.2058746247196617,-1.2977422214851086,-0.2348563393589755,-0.9347528481213283,0.6527040466718382,0.25295095360264047,-0.08581574659578141,0.4951912733600662,0.824267096348541,1.7352687065310064,1.7951323319210142,-1.2822236310179125,-0.17267436073266307,-0.2838669103969904,-0.7569163822999941,1.1317668562328564,-0.7359378185400911,0.4331463217393372,2.2369192172107324,1.326191112268964,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.15,1.0,0.0,0.0,1.0,1.4023691213040936,0.008915233090690734,0.019814015089587984,0.9807551693227373,0.09488157321306635,0.019219077580641942,0.1695506177176134,0.8116044746297819,-0.14713539273595785,-0.004133018060826825,0.17786776933940224,-1.2956209548700388,0.011257425331571015,-0.6869273419331383,-0.06620346440145222,-0.11501435988275198,-0.32101523764057144,1.2038864452919753,-1.299902732834682,-0.24101535371080848,-0.9253112737246154,0.6469010328965409,0.256632051051168,-0.06674045683600936,0.5055329533088224,0.8182719678531014,1.692497270519162,1.8218420204191046,-1.235972449561763,-0.30699649555747666,-0.23778218239699278,-0.7215456429548028,1.131105075307044,-0.6620222445170687,0.4482462749816185,2.3362411217216534,1.1511302546000524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.158333333333333,1.0,0.0,0.0,1.0,1.4091565474239702,0.010051763727734402,0.01949690395252558,0.980780239799103,0.09648186237118014,0.014078693101536808,0.1690063958958356,0.8133095659232289,-0.15100579792923152,-0.014310844485247429,0.16086226184858432,-1.2756569897754548,-0.020757081624454304,-0.6801419991545017,-0.052267909770639456,-0.099784745019413,-0.3311150851094473,1.2007580164603704,-1.3017052578583919,-0.2468821000748889,-0.9159010968662109,0.6416703425965538,0.2604217248523341,-0.04687839456708719,0.5143767776034004,0.8084682182967251,1.6549473009099425,1.817348812084636,-1.1865111672517659,-0.44670778933402655,-0.19708008979256952,-0.6869903641967806,1.1244179270735377,-0.5989184369335598,0.4588313569462943,2.4246882736916437,0.9685713351075109,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1666666666666665,1.0,0.0,0.0,1.0,1.415957696225655,0.01116368485790442,0.01915946948676916,0.9808052656083862,0.09799123790125873,0.009036466027089839,0.16833624247720524,0.8123392589155948,-0.15428585939547376,-0.024477379531273845,0.14394791821738512,-1.2481459129466401,-0.05311341643193137,-0.6734528716281929,-0.038621009386286514,-0.08472521301467471,-0.3407904237614342,1.1964413154697415,-1.3031874009978914,-0.25246519311408816,-0.9065709749400565,0.6369190589476482,0.2642792403336062,-0.026328985607815294,0.5216758088939476,0.7954358876233347,1.623640720244277,1.7807056802961752,-1.1343702794268984,-0.5926484871052828,-0.1599096876804662,-0.6536880122838679,1.1121005408685414,-0.5473208550896103,0.46413391590204967,2.5002304118776797,0.7821726896371706,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.175,1.0,0.0,0.0,1.0,1.4227498812232091,0.012247314674636378,0.01880141526802721,0.9808318399032503,0.09940605863098863,0.004122726369223231,0.16754205581560652,0.8084596892360089,-0.1567822540332409,-0.03446894647469904,0.12726414579821654,-1.2136503431698342,-0.08565488952839022,-0.6668847343607794,-0.025207231099901504,-0.07010631701447674,-0.35002125643322896,1.1908805416752823,-1.304370419319733,-0.25777690027962,-0.8973660878517352,0.6325483283450603,0.2681572901173683,-0.00520788770245919,0.5274129890973532,0.7796315803495335,1.5992449451364985,1.711563535749344,-1.0801173236319639,-0.745817518242573,-0.12422494582679189,-0.6220648565489295,1.0945845629095774,-0.5079419344106806,0.46335620369357344,2.5610045515129594,0.5954472133788635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.183333333333333,1.0,0.0,0.0,1.0,1.429507988850113,0.013299750573919734,0.01842305408000865,0.9808618685263438,0.10072375785151828,-0.0006344948256146064,0.1666262791152153,0.8014449025827886,-0.1583047110120508,-0.04411193559308256,0.11095630587107269,-1.17273343015121,-0.11823038909012282,-0.6604590119557007,-0.011966926967344875,-0.05619915408551898,-0.35879237915530027,1.184011023499032,-1.3052578167616713,-0.262832940723237,-0.8883278988915635,0.6284533600408035,0.2720018437284991,0.016354423584067364,0.5315999291169287,0.7614183693949572,1.5821174663145117,1.6100573379653587,-1.0243127246390749,-0.9073116486441846,-0.08784760139474823,-0.5925119280811308,1.0723166745889867,-0.48146698294678547,0.4556918374850072,2.605317612923645,0.4117633970133716,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1916666666666664,1.0,0.0,0.0,1.0,1.4362045709779039,0.014318864163546057,0.018025349868079278,0.9808974830794069,0.10194282476113209,-0.005209431259546197,0.16559181741360815,0.7910900761183388,-0.15867903655425297,-0.053231764235398216,0.09516466433456666,-1.125932626384408,-0.1507117396233135,-0.6541944282041968,0.0011613933386736889,-0.04327202804838743,-0.36709313517721354,1.175758680864546,-1.3058345460096454,-0.2676520990809722,-0.8794941432752521,0.6245238786292805,0.2757521540754517,0.0382140725129349,0.5342757123809094,0.7410904159929577,1.5724055662002188,1.4765899964017166,-0.967470635695985,-1.078253552345041,-0.048546188610454344,-0.5653616921953653,1.045737935457185,-0.46852058123310947,0.44034730534362243,2.631656558456194,0.23430865597109607,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2,1.0,0.0,0.0,1.0,1.4428100907577783,0.015303250459557985,0.01760989343148295,0.9809409691472042,0.10306271885102705,-0.009578408073404989,0.16444192023484663,0.7772263815580669,-0.1577603572527123,-0.06166192768003172,0.0800141599144249,-1.0737264957791772,-0.18300603031788926,-0.6481075050224847,0.01423983246932544,-0.03158932081215704,-0.37491688975023335,1.166040130959948,-1.3060669199051789,-0.27225563559315974,-0.8708989333006104,0.6206446836869184,0.27934096548422616,0.06021536622500393,0.5355050733831136,0.718892565656033,1.5701913799143956,1.3115383633680027,-0.9100273562995853,-1.2597108574297078,-0.004124674863605904,-0.5408646938402206,1.0152704475424223,-0.46965242850090627,0.4165656485136393,2.638710832157208,0.0660069852592704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2083333333333335,1.0,0.0,0.0,1.0,1.449293332266095,0.016252132146740268,0.017178810822444244,0.9809947152351288,0.10408372461436985,-0.013719535705891078,0.16318002724384287,0.7597375713084595,-0.15544598117980812,-0.06925329202649903,0.06560589224913632,-1.0165047396106777,-0.21506839036311032,-0.6422128854432629,0.027331249670580284,-0.021413055325587387,-0.3822602577822066,1.1547634999073841,-1.3059032905907055,-0.2766665106449759,-0.8625729691495451,0.6166963381542654,0.2826949148840124,0.0821925863822217,0.5353758288018973,0.695042198181659,1.5756620412106643,1.1149334496063636,-0.852314547416303,-1.4526087284433054,0.047485811787293386,-0.5191696203274665,0.9813068720660101,-0.4853179817428699,0.38364812870974596,2.6254048281754114,-0.09058127528027926,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.216666666666667,1.0,0.0,0.0,1.0,1.4556219946116893,0.017165228078479998,0.016734612345785355,0.9810611852174056,0.105006762140392,-0.01761228753754416,0.1618095735499285,0.738580724285891,-0.15168761293564734,-0.07588299490640352,0.05201151548724947,-0.9545438695410398,-0.24691565169654206,-0.6365234683861237,0.04050086648950318,-0.013007096652050977,-0.38912213220717173,1.1418299854858929,-1.305275489708724,-0.2809084625986175,-0.8545438187661769,0.6125560506578706,0.2857351009627219,0.10397211336126079,0.5339953854617756,0.6697526812494736,1.5892738971568439,0.8861832649800726,-0.7945371776994548,-1.657634904126204,0.10813682584333684,-0.5003081039398127,0.9442048158785066,-0.5158452336703245,0.34097278775009565,2.5909533365707897,-0.23338821943422072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.225,1.0,0.0,0.0,1.0,1.4617635160172184,0.018042598852667825,0.016279994718676985,0.9811429149952302,0.10583317374356434,-0.02123698563261639,0.160333746077798,0.7138145548713059,-0.1465037035011284,-0.0814629855738284,0.0392705697894325,-0.8879892762422094,-0.27864206725671936,-0.6310503407557717,0.05381914795652768,-0.006643334242586177,-0.39550254407719754,1.1271362515052807,-1.3041010101599833,-0.28500497904397276,-0.8468362222182366,0.6080989175930933,0.2883777946798473,0.12537514199173486,0.5314860251446603,0.6432590518614512,1.6118824912586887,0.6239001970812017,-0.7367527934860296,-1.8751300185793163,0.1793697932538052,-0.48418305200076395,0.9042849250336138,-0.5613738052494255,0.2880110510967959,2.5349567899753547,-0.36101410457045846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2333333333333334,1.0,0.0,0.0,1.0,1.4676862041509242,0.01888448067549929,0.015817606464891207,0.9812425328506732,0.10656450307621115,-0.024574216423622734,0.15875517722622504,0.6856376403707691,-0.1399933363443425,-0.085949207671082,0.027388828997193748,-0.8168407102143443,-0.31043774094433074,-0.6258024841884329,0.06736557467714799,-0.002608760034030948,-0.4014013454319389,1.110577818509571,-1.302285993154494,-0.2889781801319636,-0.83947240334895,0.6031998205703801,0.2905352851476685,0.14622139319418337,0.5279784837189346,0.6158464972497013,1.644826368137239,0.3258543633623878,-0.67884725395852,-2.1049528868956235,0.2623024353790582,-0.47055653705455613,0.8618262484890926,-0.6217536404184298,0.2243465198594552,2.4575480531398997,-0.47297026274119913,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2416666666666667,1.0,0.0,0.0,1.0,1.4733607611079818,0.019691109426225428,0.015349773193329893,0.9813628027264906,0.10720226667161196,-0.027604178342860202,0.1570755639281006,0.6544345789399004,-0.13235288430306402,-0.08935341866279517,0.01633321611547811,-0.7409328463580681,-0.34260841006820353,-0.6207862324682767,0.081232920758815,-0.0012124281865463797,-0.4068166649765062,1.0920537033903537,-1.2997293029036656,-0.29284758799488203,-0.8324724514100851,0.5977363569194528,0.29211690334417156,0.16633427621073318,0.5236031874323069,0.5878807294204025,1.689980337676536,-0.010998717305459142,-0.6205036126269659,-2.3463152181652314,0.3574604214994537,-0.45903082906151305,0.8170458647961443,-0.6964024057879081,0.14970327788163762,2.3595829027642603,-0.5699970864796189,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.25,1.0,0.0,0.0,1.0,1.4787622537007892,0.02046251863195375,0.014878153491784542,0.9815066903640277,0.10774768619331551,-0.030305922137777174,0.15529521555432388,0.6233081527954942,-0.12511633894813368,-0.09188304391064867,0.002424593452722973,-0.673165243239397,-0.37546616347066447,-0.6160044720314262,0.09553191363842359,-0.002792071989121934,-0.411743072309055,1.0714725648734837,-1.2963283194628363,-0.29662869394965546,-0.8258549722690143,0.5915931138072483,0.29303033977902915,0.18554777490692104,0.5184785322776077,0.5695984265397258,1.735125851256325,-0.3309497325898323,-0.5511305546302059,-2.591873294339684,0.48214579683817593,-0.44451817242062597,0.7607946062738624,-0.7402629104913894,0.07585765453429372,2.256359156169501,-0.6394553138273307,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2583333333333333,1.0,0.0,0.0,1.0,1.4839182402650666,0.0211921969701271,0.01440100535333553,0.9816769145200819,0.10818886603817467,-0.03276963245284982,0.15340063869706289,0.5971550770767954,-0.12028296295789268,-0.09418274726522192,-0.018607902441181323,-0.6322252370019928,-0.40900497376595346,-0.6112929253592813,0.11015168494642041,-0.006728257063043585,-0.41600217422034297,1.048855815151359,-1.2916935396230294,-0.30025622420189246,-0.8197925413055207,0.5853986417445963,0.2933811975864098,0.20394026214689154,0.5129455988685181,0.5736507226824816,1.758373818758131,-0.5437970024423313,-0.45801401569273925,-2.826072348586024,0.6563785332387351,-0.4213329574197622,0.6784258178620228,-0.6841634556552822,0.020029508077439306,2.1725255481570653,-0.665546332189002,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2666666666666666,1.0,0.0,0.0,1.0,1.488891944218944,0.021875236953011974,0.013913570080662505,0.9818736768253573,0.10851587222297474,-0.03513268431809981,0.15137398298850546,0.5769034758840229,-0.11754189878135278,-0.09678910620863121,-0.04388389890228969,-0.613353234055207,-0.44286092506777686,-0.6064436266533848,0.1248381439510591,-0.01185535536316079,-0.4193766392372673,1.0243713590637167,-1.2853886772421907,-0.3036509099066515,-0.8145478753046472,0.580190389546327,0.29336416491365314,0.22175653404287213,0.507386093407791,0.5936974876729462,1.7615269792806705,-0.6587228947066228,-0.3481262592499368,-3.0400206065200552,0.866445506305551,-0.39291919089344374,0.5708844178306283,-0.533679038795587,-0.021226188447912575,2.1116558459299086,-0.6623893380031709,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.275,1.0,0.0,0.0,1.0,1.4937244988807088,0.022514859811527822,0.013412441940980003,0.9820955320681867,0.10873358817159698,-0.03744285783918163,0.1492092661061416,0.5606871276188997,-0.11578980105627688,-0.09965849128905488,-0.06962525359516611,-0.6026305667717221,-0.47669882661140645,-0.6013979672313988,0.1395104679344316,-0.017706971974820632,-0.42180427854117525,0.9981888050426914,-1.2772527811846035,-0.30680487738344986,-0.8102778010083436,0.5765039910980032,0.2930274277789446,0.23913452624572334,0.5019057765684652,0.6187781952531957,1.7600320487193162,-0.735915678594598,-0.2327129329195543,-3.2347695722509684,1.0905719075471332,-0.36386193946232437,0.4473749607593258,-0.33146510663255135,-0.058765778618543596,2.064699959718334,-0.6529036020485468,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.283333333333333,1.0,0.0,0.0,1.0,1.4984439945149968,0.023112905225048375,0.01289641274053594,0.9823412451089506,0.10884448389934566,-0.03971904073810137,0.14690457544064967,0.5473616301804031,-0.11478591859333041,-0.10262452975123156,-0.09561430205191812,-0.5951807538959076,-0.5104020525217964,-0.5961306567324982,0.15417201142971437,-0.024120616673070756,-0.4232551881192599,0.9704585328595339,-1.2672124787830719,-0.3097152755643569,-0.8070916259586585,0.5746659711024511,0.29238473527001074,0.2561682000381777,0.49650436670698184,0.6463407936046783,1.7609542145423258,-0.8011131550192984,-0.11434383106960655,-3.41203988205786,1.321017196857719,-0.33439779203567777,0.31196239152437855,-0.0954831190976102,-0.09529374778831978,2.0276936329506503,-0.6457935599837339,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2916666666666665,1.0,0.0,0.0,1.0,1.5030721316817564,0.023669507053781867,0.012364807283290737,0.982609828210302,0.10884878795932412,-0.04196892873473408,0.14445925337354365,0.5363721715726125,-0.11448735454517386,-0.10565339027754647,-0.12196187110814195,-0.5890497918544095,-0.5439769793408121,-0.5906256206713209,0.16885970484347035,-0.031058857891808938,-0.423710009059002,0.9413214736750604,-1.2552358279036415,-0.3123781739173778,-0.8050784278162706,0.5749126057797097,0.29143919864913925,0.2729294201282342,0.49114255056873635,0.6756447508429009,1.7670851014784046,-0.8648231007903169,0.005999552526044782,-3.5726178221095317,1.5539103724716163,-0.3044328908917726,0.16656132687953296,0.1661998111891827,-0.13168359279751352,1.9987613339684018,-0.6444615009458643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3,1.0,0.0,0.0,1.0,1.5076279259117908,0.02418386966701513,0.01181687052630624,0.9829004086310976,0.10874551689031976,-0.04419553240491109,0.1418730213416217,0.5275106123682801,-0.11489403304398926,-0.10877808821148689,-0.14876132409890916,-0.5833942912237541,-0.5774450539470765,-0.5848699108851165,0.18362342978768778,-0.03853433501957604,-0.42315519557715914,0.9109149024910417,-1.2413139725752116,-0.3147891570792198,-0.8043156038439996,0.5774359679556041,0.2901900087233855,0.28948088893765106,0.48576334169121743,0.7064253185656089,1.7795051341473145,-0.9311845799834341,0.1277088149465433,-3.716770953147419,1.7869269008394317,-0.27394725949812737,0.012461117614497308,0.44931811438145397,-0.16825196484130944,1.9772681533272085,-0.6507157311141709,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.308333333333333,1.0,0.0,0.0,1.0,1.5121297358950698,0.024654764203225002,0.011251575649064543,0.9832121370057393,0.10853304823248112,-0.046399711683794496,0.13914574316773612,0.5207594626233931,-0.11602089794864892,-0.11206110886065854,-0.17607374922561322,-0.5778077836890919,-0.610813641207056,-0.578851865361894,0.1985181237459256,-0.04657860089153284,-0.42158152880989297,0.8793752911226034,-1.225453712889651,-0.31694396157567994,-0.8048707425226956,0.5824012410194006,0.28863499923511743,0.3058838893503543,0.48029728838350016,0.7385655527462065,1.7986400917331025,-1.0016752508024,0.25030812834465843,-3.84452455653314,2.0183536327034446,-0.24297615239804005,-0.14913193811369796,0.7509806885038484,-0.20508915333273703,1.9633162668510518,-0.666046583614176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3166666666666664,1.0,0.0,0.0,1.0,1.5165963561344427,0.025080759854927644,0.0106675701125517,0.9835441379467263,0.1082093778883406,-0.04858118180356223,0.13627739365820765,0.5161999820880749,-0.11788858557073735,-0.1155782541452037,-0.20394262434732457,-0.5720562292931173,-0.6440717241297332,-0.5725604850060131,0.21360076464990616,-0.05522892253294937,-0.4189833934380815,0.8468394932154893,-1.2076747453634875,-0.3188387596191871,-0.8068011361458945,0.5899523127640016,0.2867718561678399,0.3222028267185019,0.47466256529764783,0.771996621184381,1.824644529350455,-1.0766080757408318,0.3733905304461105,-3.955825072183139,2.246693906289927,-0.21158149651072988,-0.3169073125141386,1.0686728430965875,-0.24217790913864445,1.9574289545918577,-0.6920024638823818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3249999999999997,1.0,0.0,0.0,1.0,1.5210475403847377,0.025460319012677358,0.01006316947250409,0.9838954854146342,0.10777222804621582,-0.0507389073290995,0.13326809042583593,0.5139542528532378,-0.12051491159358398,-0.11941069173301855,-0.2324024968640514,-0.5659716982040651,-0.677191302213984,-0.565985255008821,0.2289288659017665,-0.0645220688205467,-0.4153583533024578,0.8134448732528844,-1.1880088144514855,-0.3204703198508588,-0.810152531064598,0.6002124550710104,0.28459870074947335,0.3385077052602186,0.46876391398546047,0.8066579516151284,1.8575000202812852,-1.1556957036660058,0.4965877110581751,-4.050649798223443,2.4705163115949658,-0.17984667408896593,-0.4893979508988733,1.3998395310780354,-0.2794546782832563,1.9603392606052694,-0.7302427163362724,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3333333333333335,1.0,0.0,1.0,1.0,1.5255041311825484,0.02579183517939734,0.009436375196864475,0.9842651902688395,0.10721909764798966,-0.0528712479600167,0.13011814425276552,0.49853016816469786,-0.1193466410451519,-0.11834401870952381,-0.25989272177486616,-0.546369298926731,-0.7060359390715207,-0.5591161858124276,0.2445590983212609,-0.07449051759404947,-0.4107069315871119,0.7793286632450986,-1.1664994735035714,-0.32183620418733655,-0.8149577686608758,0.6132829716153022,0.2821142781964523,0.35487514772858975,0.46249185335870996,0.8333143675883825,1.8414647909402377,-1.2050597853796774,0.6058273581918072,-4.1824952130385755,2.709189914846677,-0.018193229867234928,-0.614833823975971,2.502428164163595,-0.3389788005387062,1.7550189405010141,-0.5102252655153316,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.341666666666667,1.0,0.0,1.0,1.0,1.5297108705275968,0.02606177252275379,0.008851292106233463,0.9846524240631196,0.1065446590388224,-0.05487096391154223,0.12687401915582117,0.5061164973477094,-0.12495167656545923,-0.1223184010885026,-0.29282110698822594,-0.5402990931218118,-0.7367928887520313,-0.5520966822156813,0.25961994575077046,-0.08460639857687466,-0.4052612306659277,0.7437366197022415,-1.142855649204041,-0.320773540348646,-0.8203997614641975,0.6419195911404036,0.27894905407382825,0.3677580209352355,0.46026015956020494,0.8751649930645211,1.8931892071115082,-1.2835100667626762,0.7337874730355187,-4.233711998987982,2.92422366256031,0.14509423068010618,-0.651612417591787,3.529180923431061,-0.3749808953893552,1.4138824174169973,0.009490843639302637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.35,1.0,0.0,1.0,1.0,1.5343268983224347,0.026288718222858717,0.008187885480342268,0.9850563072055819,0.10572449033911338,-0.05695964044182841,0.12345850775952755,0.5474243052093072,-0.13987619114290628,-0.13583654119116972,-0.32982395962980493,-0.5551382354860791,-0.7725676989794258,-0.5445301025946856,0.2761122517731194,-0.09588235204009407,-0.39847714036985327,0.708766796595299,-1.1177624124608996,-0.3194179670093348,-0.8258179756207389,0.6721026536724866,0.2758645966066297,0.3784398546855397,0.46265003408603167,0.93484313248416,2.049312925367556,-1.4126134266381214,0.8857462355990164,-4.1651013873255165,3.0895045284373746,0.17525884130843106,-0.6299239298030623,3.660885308813988,-0.3731873949426756,1.1411700458694862,0.5557105059354384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3583333333333334,1.0,0.0,1.0,0.0,1.5392873368194446,0.026466335025396113,0.007461875176313953,0.9854736286288295,0.10477516852504792,-0.059086286769619925,0.1198862046018924,0.5818303036243585,-0.15245862417391015,-0.14763563656155687,-0.3635741515745703,-0.559797031822715,-0.8067089545512615,-0.5365159633409453,0.29377516117356306,-0.10814995568751001,-0.39049879340594407,0.6743182632468162,-1.091363907063418,-0.3178525596601722,-0.8308984936275818,0.7029343462873034,0.272729264158117,0.38677752169972696,0.4695220013257956,0.9854798900730377,2.1760082181142493,-1.5216156578730045,1.0236243076339935,-4.109055506293629,3.2405392143234746,0.19835036210577583,-0.5810782147540428,3.710309804475971,-0.38508479455732325,0.8556407344882888,1.0818648466016445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3666666666666667,1.0,0.0,1.0,0.0,1.5445342140526779,0.02659083225489384,0.006682674791439556,0.9859034045449304,0.10369543510243301,-0.06121534361760168,0.11616546540057077,0.6103427794214219,-0.16295538379983063,-0.15821966967494824,-0.39665607279573434,-0.5567252754053774,-0.8398289064063209,-0.528105437760135,0.31237905540835686,-0.12124261300464415,-0.38141673524262004,0.6402825381570718,-1.0637534255555083,-0.3161121276409052,-0.8355026125333063,0.7339411504137527,0.269446516697341,0.39270053359367785,0.48068111486272574,1.0306762469395858,2.277481238202703,-1.6117231305642044,1.1514925005915289,-4.0648471009747515,3.381566383597576,0.217546083440896,-0.5184655539110583,3.7108556100982493,-0.4078832947661615,0.5655105662211024,1.581058552279957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.375,1.0,0.0,1.0,0.0,1.5500202840559145,0.026659701668511962,0.005857587515854707,0.9863447634003596,0.10248399205975647,-0.06331813708819738,0.11230250487013077,0.6340902365538666,-0.1716629867016778,-0.16774888122834536,-0.42919970174085365,-0.5470957347709199,-0.872095225645723,-0.5193380258919522,0.3317331818102748,-0.13501200786358009,-0.3713072517294186,0.6065708115639037,-1.0350044673367917,-0.3142267916028239,-0.8395395861927661,0.7647819397889409,0.26593120924534763,0.396202697803412,0.4958729771971282,1.0714989474247183,2.3578807793846637,-1.6853602080854202,1.2706489818289401,-4.030415397379044,3.5144662400179794,0.23336936691108479,-0.44648071279031143,3.674925183316453,-0.44046568889954396,0.27759523071123615,2.0459123381521906,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3833333333333333,1.0,0.0,1.0,0.0,1.5557069007997752,0.026671131376693233,0.004993580795483994,0.9867968473177967,0.10114020843607184,-0.06536869127166334,0.10830316044683233,0.6540201109550109,-0.17882926485972478,-0.176237214686537,-0.4611586222806343,-0.5313667570140357,-0.903474054566563,-0.510247121969723,0.35167706839810126,-0.14933194980606782,-0.3602392522121377,0.5731089482007544,-1.0051789882218753,-0.3122226381923871,-0.8429439577464781,0.795189903469027,0.2621054218823486,0.39732712077219845,0.5147796538319289,1.1085742875848315,2.4206034761705255,-1.745294621707738,1.3818480743412642,-4.004108551965255,3.6402480543106774,0.24631903076858253,-0.3675911393786935,3.6099159906255918,-0.4820163577618719,-0.003058894096965581,2.469567948982758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3916666666666666,1.0,0.0,1.0,0.0,1.5615628240780663,0.02662378598209153,0.0040978294054161936,0.9872588408561792,0.09966399983263587,-0.06734205217434745,0.10417349133901727,0.6709737715128481,-0.184667905214893,-0.18366274889459427,-0.4924706315058305,-0.509702111906832,-0.9338725587951204,-0.5008617877655384,0.37207657307978353,-0.16410025155870905,-0.3482764504903975,0.5398356690311494,-0.9743336664316138,-0.31012147442334753,-0.845666105182411,0.8249472062993675,0.25789760328264977,0.39615171623512924,0.5370324430135075,1.142368461045692,2.4686456716491314,-1.7943716974260022,1.485656627764591,-3.9843934787517954,3.759202015681762,0.2569017584525579,-0.28338742565999553,3.5208954009010296,-0.5317692686050446,-0.27307734529505523,2.8470467386822973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4,1.0,0.0,1.0,0.0,1.567563506216612,0.026516730351422272,0.00317779442372254,0.987730002897354,0.09805574942992415,-0.06921358633565805,0.09991992217176907,0.6857140409681617,-0.18936214530128598,-0.19000797691966412,-0.5230721892943301,-0.4821458087301404,-0.963195378141814,-0.49120764761896146,0.3928211629255868,-0.17923814476316785,-0.3354783084160612,0.5067023902215578,-0.942525621293846,-0.3079409422181778,-0.847667081507478,0.8538714934840441,0.2532426007389312,0.39277583168394753,0.5622304328099672,1.1732547271663674,2.504661496916544,-1.835238646412326,1.582553001524668,-3.969746902752959,3.8709824381337854,0.26559192311714885,-0.19495466168776066,3.411599672342054,-0.5889341670253667,-0.5306008615214364,3.175621824920618,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.408333333333333,1.0,0.0,1.0,0.0,1.5736904275760897,0.026349420919523477,0.002241141397390887,0.9882096857488604,0.09631628595375204,-0.07095870418635732,0.09554921429579535,0.6989091850311365,-0.19305897628704138,-0.1952678136028853,-0.5528982322926179,-0.4487019163905387,-0.9913651025776179,-0.48130754231276557,0.41382093136172593,-0.19468756233224782,-0.32190056713165305,0.47367322065193346,-0.9098172924627174,-0.30569494237139505,-0.8489153495438737,0.8818072008384017,0.248082033832227,0.3873083685431053,0.5899594734288511,1.2015304718262532,2.530888810968912,-1.8701188887413274,1.6729595509718687,-3.9587005405020115,3.974744394383536,0.2727974490426033,-0.10305500899811859,3.2848276594167403,-0.6526735596045447,-0.7751192966293063,3.454751133413101,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4166666666666665,1.0,0.0,1.0,0.0,1.5799301340830694,0.026121726396690793,0.0012956347752039034,0.988697338389129,0.09444689952854717,-0.07255279670618474,0.0910683694922075,0.7111449597600185,-0.1958681820659708,-0.19945102013007351,-0.5818719264487531,-0.40936608889542453,-1.018320399144881,-0.4711821397551906,0.435002643108402,-0.21040679290885664,-0.3075956492331967,0.44072404787985764,-0.8762798813874537,-0.30339431806746775,-0.84938466499078,0.9086186211409898,0.24236470807885543,0.37985717674012576,0.6198096183668522,1.2274110503581626,2.549154745732857,-1.9007274941286774,1.7572441145321382,-3.9498285654103737,4.069230827503536,0.27884082300915436,-0.008215653499703546,3.1426833460094716,-0.7220703619372221,-1.0071092118671388,3.685567289369307,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.425,1.0,0.0,1.0,0.0,1.586273789347918,0.025834012242335426,0.0003490301822249184,0.9891924872938371,0.0924494342145222,-0.07397121193855563,0.08648459400018757,0.7228577941868101,-0.1978520718828275,-0.20256077766953318,-0.6099102530732128,-0.36415444500879596,-1.044022537648237,-0.46085069147346286,0.4563068437906069,-0.2263663539010591,-0.2926131652227841,0.40784274456176056,-0.8419967786709918,-0.3010475953212425,-0.8490522771022021,0.9341852566052262,0.23604752779993995,0.3705232150119863,0.6513855949183396,1.2510419981567678,2.5607297751147065,-1.9281738445447056,1.8357380830637748,-3.941935796443891,4.1530019619850105,0.283946309389258,0.08915880411243027,2.9865904138955446,-0.796144394323452,-1.2279629793097047,3.8706641188589863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.433333333333333,1.0,0.0,1.0,0.0,1.59271507919802,0.025487127096155422,-0.0005909086028856107,0.9896947176724277,0.09032628407399426,-0.07518942991553568,0.08180512114692526,0.7343305854989114,-0.19902626319794686,-0.20458517833623524,-0.6369143542870023,-0.3131081194582374,-1.0684501355661755,-0.4503314397859111,0.4776814726936471,-0.2425430236512684,-0.27700001451546713,0.37502511793912613,-0.8070631820210369,-0.2986618795776468,-0.8478986849222395,0.9583951280392489,0.22909563484013123,0.359391127084964,0.684320687014502,1.272491834087064,2.566353928920928,-1.9530269261535833,1.9087309355442572,-3.9341065684039114,4.22457657726133,0.28823395215862746,0.18871960912504093,2.8173836214398773,-0.8738464847255129,-1.4397147912791808,4.013602976839077,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4416666666666664,1.0,0.0,1.0,0.0,1.599249699006641,0.02508253324899035,-0.0015164255039113133,0.9902036252873917,0.08808056439763268,-0.07618307696898687,0.0770372210483229,0.7457466896253443,-0.19937215147244647,-0.20549749816262655,-0.6627627396710458,-0.2562884845527528,-1.0915865395736524,-0.43964249423867846,0.49907940927262234,-0.2589168026702855,-0.2608009829637131,0.3422743017550287,-0.7715871690499696,-0.2962436961185987,-0.8459069502834514,0.9811416502958908,0.2214834197211814,0.34652796849066664,0.7182789778656575,1.291753630338116,2.566405163653495,-1.9754731710741846,1.9764732986016782,-3.925572369165701,4.282428537148348,0.29174072810668306,0.29015194911578446,2.6354956433559673,-0.954005149535363,-1.6445956248341131,4.118223977107327,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4499999999999997,1.0,0.0,1.0,0.0,1.6058741939414656,0.02462233652178166,-0.002419691802912322,0.9907187730524365,0.08571614771205813,-0.07692806823559818,0.07218813656417938,0.7571585595494238,-0.1988407640828024,-0.20524187166807123,-0.6873253210930026,-0.19378848429084644,-1.113425354871941,-0.4288022126136092,0.520454892087872,-0.2754675765025048,-0.24405879287210583,0.30959891178636445,-0.7356893730685644,-0.29379953410920207,-0.8430628191036431,1.002320055428515,0.21319554901454185,0.33198120000439546,0.7529577532996241,1.308774436652832,2.560882235572938,-1.9953808129154815,2.039209291392407,-3.9157847259730407,4.325106472151206,0.2944424836397863,0.3931046879422717,2.44097583874215,-1.0353252256270085,-1.8449889289837595,4.188505938040681,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4583333333333335,1.0,0.0,1.0,0.0,1.6125849337444011,0.024109321725431072,-0.003292712626839119,0.9912396400475068,0.08323772739687434,-0.077400725107065,0.0672650316981284,0.7685098981176496,-0.19736259989399896,-0.20373290657237259,-0.7104612040560396,-0.1257280952448769,-1.1339671402691804,-0.41782958696113126,0.5417607798655046,-0.2921731495522102,-0.22681416144050634,0.27701122298881137,-0.6995020611807828,-0.2913363213912689,-0.8393552054844136,1.0218245809415933,0.2042279992940646,0.315778153007604,0.7880874101663355,1.3234615953849826,2.549513876757119,-2.0124503249917116,2.0971818081015443,-3.904376838933872,4.351269442819071,0.2962715787542125,0.49716019137085343,2.2335909706410373,-1.1163763702161367,-2.0432477495521284,4.228278123515026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.466666666666667,1.0,0.0,1.0,0.0,1.619377353705899,0.023546978621566957,-0.004127221769105681,0.9917655668767398,0.08065086189693828,-0.07757788353339282,0.062274961417420484,0.7796691544792104,-0.19485956266824161,-0.20085807027372843,-0.7320244245443677,-0.05225301862508604,-1.1532123498460427,-0.4067445193571928,0.562946790033824,-0.30900841525236666,-0.2091057627370801,0.2445259644707999,-0.6631682156882466,-0.2888616744632985,-0.8347768159141289,1.0395465716058656,0.19458927617760624,0.2979270708451933,0.8234290553582079,1.335697876307066,2.5318681883505856,-2.0263188431912162,2.150644122340941,-3.8910773859306462,4.359674180582167,0.29714746250461777,0.6018321594052978,2.012931884227509,-1.195567700859027,-2.241510800550387,4.240970986046446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.475,1.0,0.0,1.0,0.0,1.6262455247768783,0.022939509507148848,-0.004914564728790318,0.9922956979442915,0.0779619810529303,-0.07743701136823126,0.057224877649561426,0.7904475229849139,-0.1912551773040631,-0.19647987912878034,-0.7518721248772298,0.026464698145945223,-1.171157536653648,-0.39556795568934683,0.5839585830046811,-0.3259451302720638,-0.190970092734824,0.2121599332233006,-0.6268408248377467,-0.2863838636828586,-0.8293246694943253,1.0553734456787185,0.18430187094641415,0.27841963966509753,0.8587702599337763,1.3453596655252709,2.5074244734485007,-2.0366392171502437,2.1998736213194037,-3.875662257795178,4.349172140783562,0.29700566007048956,0.7065629126940065,1.7784832011556784,-1.2711451386282557,-2.4416124251978024,4.2295101678886216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4833333333333334,1.0,0.0,1.0,0.0,1.6331817296323379,0.02229179576760644,-0.0056455879383357915,0.9928289248316318,0.0751783562117643,-0.07695633034114392,0.052121626945797896,0.8006072241788363,-0.18648300864700196,-0.19043855280854688,-0.7698720885355868,0.11022731161538857,-1.1877928099704054,-0.38432185826510495,0.6047371979246323,-0.3429524022048707,-0.1724412023817567,0.17993159350754695,-0.5906820133418539,-0.28391158012879036,-0.8230007673692288,1.0691879582917936,0.1734035238671353,0.25723353042522995,0.8939208914896849,1.3523330805293254,2.4756230405641344,-2.043149610850683,2.245181882005449,-3.857943186467543,4.318728012918014,0.2958225599389963,0.8107227526953631,1.5296647707287692,-1.3412146584185858,-2.645051646761811,4.196295129861887,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4916666666666667,1.0,0.0,1.0,0.0,1.6401762026847204,0.021609341560649652,-0.006310531225983875,0.9933638296666459,0.07230803784637807,-0.07611493339582484,0.04697197554998231,0.8098740709735304,-0.1804944828803948,-0.1825563207082497,-0.785909884722667,0.1988136975978641,-1.2030963721399321,-0.37302907101385807,0.6252189670140833,-0.35999762378624184,-0.15355039470139983,0.14786088011550821,-0.5548620246224465,-0.28145348768387535,-0.8158126236160692,1.080867858524198,0.16194829330610439,0.23433544555240068,0.9287085120981411,1.3565279628526705,2.4359119376183247,-2.045723681122882,2.2869199806686504,-3.837757490586457,4.267443923321905,0.29364025171777386,0.9136268508085199,1.2658658534854972,-1.4037781106907306,-2.852954843494897,4.14317660220166,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5,1.0,0.0,1.0,0.0,1.6472169457349968,0.0208981855962099,-0.006898927269734688,0.9938986309216378,0.06935975787771702,-0.07489289304254103,0.04178265203493797,0.8181526541546517,-0.17317640727670125,-0.1703633506842081,-0.8001522212794896,0.3027607719572675,-1.2174787495697519,-0.3617130588842271,0.6453357302182711,-0.3770477968902521,-0.13432586937061253,0.11596896866443933,-0.5195579479531555,-0.27901757593349413,-0.8077736531890868,1.0902857225165519,0.1500072220222898,0.20968428303364833,0.9629738348597126,1.3581932462372792,2.3864162816724765,-2.0600410938425053,2.3252326588254015,-3.819258974092698,4.180909186734978,0.29365978057755315,1.0216125105476759,0.9558104718622173,-1.462046785014663,-3.0748948695034763,4.049878691776841,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5083333333333333,1.0,0.0,1.0,0.0,1.6542874581565026,0.020161031104906586,-0.007361591774495784,0.9944379881281479,0.06633766349441712,-0.07318186911243926,0.036562497221721696,0.8249130989085904,-0.16433806249955568,-0.15141142785382178,-0.8124724142442704,0.43236113531116405,-1.2318729226838028,-0.3503925169099034,0.6649925717086246,-0.39433164201695026,-0.11479651705430981,0.08420656388062991,-0.4851802048435302,-0.2765591580075828,-0.7987857484402746,1.096798033055235,0.13758084688919334,0.18308719772734275,0.9962064902944218,1.3575225519516432,2.325437717194081,-2.102941587970685,2.360960430340972,-3.8068460738398406,4.043112275861989,0.2985466566066619,1.1392353271699984,0.5691712336275012,-1.5188335708348084,-3.3219547898735446,3.8989377700471595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5166666666666666,1.0,0.0,1.0,0.0,1.6613622990888461,0.019403379474145072,-0.007652135107670911,0.9949851284391822,0.06324932911502894,-0.07087612556406217,0.031315992344782946,0.8288084195266986,-0.1539406734282327,-0.12816185145014067,-0.8221838036061503,0.5746176524713175,-1.2463956073252005,-0.3390876830183664,0.6840930255048391,-0.41209682335643016,-0.09497652886492966,0.05252153410044199,-0.45217274335545565,-0.2740417983233831,-0.7887863977362535,1.099771909743677,0.124693329175043,0.15431836986908926,1.0279561310271652,1.3540779062243224,2.253884383119842,-2.157989484229558,2.3959398100202347,-3.7967525901768013,3.8683415921692212,0.3041476906167928,1.2551745311493678,0.14138022500175484,-1.565353078079905,-3.586559976780201,3.7197748242920636,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.525,1.0,0.0,1.0,0.0,1.6684107542370477,0.018636224076494914,-0.007767617304456845,0.9955340258363755,0.06010968800611758,-0.06797473693067643,0.026043501092942793,0.8289999888482149,-0.14221116542483486,-0.10361314946239938,-0.8290591312257765,0.7132972240043851,-1.2600342816256904,-0.3278245518061647,0.7025573114272886,-0.4302981334207762,-0.0748641868873059,0.02092735404434989,-0.4207078449740432,-0.27149002983063625,-0.7778661729211185,1.0991543701385975,0.11149162892119492,0.1233111981143394,1.0582027373659562,1.3477044998331655,2.1722740896579174,-2.2011775957288537,2.4313440658203085,-3.7845559052748223,3.680541251477618,0.3066612259577173,1.3588661888187814,-0.2841900390675045,-1.590935673311433,-3.8542969206242446,3.542290913908799,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.533333333333333,1.0,0.0,1.0,0.0,1.6754031286648798,0.017869875157487898,-0.0077126224860688515,0.9960757741056316,0.05693314687756351,-0.06450708105453028,0.020748626953021706,0.8255187829745082,-0.12949555817080466,-0.07836086469054916,-0.8333541990408396,0.8436809838223814,-1.2716597803106051,-0.3166259413544803,0.7202975936658044,-0.4487831166185777,-0.05445412776792452,-0.010554397654138388,-0.390830389164162,-0.2689307778907545,-0.7661386279226071,1.0950354090925518,0.09817773461985245,0.09008008785868518,1.0869943129256452,1.338730844627336,2.0804948423552894,-2.224865903920721,2.4673370773496814,-3.7694402018169275,3.49061902744376,0.30644722196860763,1.4493627628465555,-0.696849743617074,-1.5912196737146966,-4.117073931026594,3.3697502950303804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5416666666666665,1.0,0.0,1.0,0.0,1.6823128610959865,0.017113083777237026,-0.007492707023210057,0.9966005767537914,0.05373270158709629,-0.06051226841139849,0.015438671120221474,0.8185970874526057,-0.11614026093128883,-0.05261932344663484,-0.8353301156178324,0.9642806960762798,-1.2804566285836396,-0.3055123710623758,0.7372322254665434,-0.4673792318194549,-0.033741902264811205,-0.041896649319265566,-0.36253086118331385,-0.26638257613115945,-0.7537101268736759,1.0875402077449796,0.08497130102594998,0.054693299263896177,1.1143652422831292,1.327429026037743,1.979816625713573,-2.228796105154557,2.5038172847172095,-3.750627229816856,3.303015436394938,0.30454881238282216,1.5278289261119893,-1.093985508884625,-1.565430665569568,-4.36940305884503,3.199853789534526,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.55,1.0,0.0,1.0,0.0,1.6891164675912518,0.016372982778985416,-0.007113623249717611,0.997098585716094,0.050519849101121894,-0.05603275193463504,0.010123533002078617,0.8085109317721145,-0.10246796293589916,-0.026575185932260492,-0.8352619592612346,1.074564890776091,-1.2859109671247468,-0.29450212425385125,0.7532945374276973,-0.4859297183711537,-0.012723839689304364,-0.07306485148441932,-0.33578013189091305,-0.2638549643510408,-0.7406748124874073,1.076802317277808,0.07208722352702632,0.01725670354460134,1.1403252094178873,1.3140946001084752,1.8721286301102902,-2.21521976228419,2.5407143593624077,-3.7271185852788715,3.119344705024011,0.30198674151187266,1.5958731427473283,-1.4749571576121134,-1.5149059862594714,-4.607153118337159,3.0296951250763993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.558333333333333,1.0,0.0,1.0,0.0,1.6957938513500517,0.015655228173416563,-0.006581196914754975,0.9975603262630832,0.0473044903143635,-0.051112596716078915,0.004814885146485506,0.7955421192604536,-0.08876913445040871,-0.00043605528219049783,-0.8334316252969604,1.1742804644988214,-1.2877384463817814,-0.2836107943939012,0.7684343693017149,-0.5042995611908581,0.008603337057895594,-0.10401529240724676,-0.310541782766247,-0.26134946377262824,-0.7271122411612204,1.0629575884514444,0.059722867921625455,-0.02209258604172314,1.1648601610344025,1.2990630179883178,1.7593901314134475,-2.186853502679648,2.5780120430826376,-3.6977594716003996,2.9399458072641504,0.29959791490834164,1.6552044145131872,-1.839571432037359,-1.4422892570729522,-4.8270307469272735,2.8568483518983623,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5666666666666664,1.0,0.0,1.0,0.0,1.702327714265865,0.01496412972000973,-0.005901582661913668,0.9979769818828998,0.044095069131596845,-0.04579675907944986,-0.0004747295838101895,0.7799338124146695,-0.07530020972720677,0.025562988547542867,-0.8301064221413195,1.2632703022214358,-1.285856615732128,-0.27285107395404595,0.782617706284588,-0.5223772767491478,0.030243027695406263,-0.13469417601109265,-0.2867810351031772,-0.2588616657692351,-0.7130880722455208,1.0461427934105187,0.048049069242477115,-0.06319380890418655,1.1879393486161933,1.2826925883537132,1.6434468587168682,-2.1463685176233938,2.6157401226117214,-3.66131079037427,2.7643474286663885,0.2979756922731658,1.7074460161040883,-2.187697844573986,-1.3510398504935432,-5.026525143168983,2.679685652696171,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5749999999999997,1.0,0.0,1.0,0.0,1.7087031333494214,0.014302809593188028,-0.0050814388049352545,0.9983405975640693,0.040898664795984946,-0.04013088423611395,-0.0057325914198764405,0.7619044141160385,-0.06228319974955133,0.05116682449431599,-0.8255409849357129,1.3413945378112087,-1.2803370336803348,-0.26223258458800597,0.7958251502803294,-0.5400723698179146,0.05219900576809095,-0.1650371389134846,-0.2644693256218072,-0.25638320223474215,-0.6986548075594856,1.0264959577085446,0.0372055370800664,-0.10586800509453952,1.2095215885793387,1.2653570661986724,1.5259526771345588,-2.096076384863037,2.6539468977091505,-3.6164556551403155,2.591574046690712,0.2974884480297102,1.754107611501643,-2.5191203698581965,-1.244967984168015,-5.203727495470115,2.4972926764511794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5833333333333335,1.0,0.0,1.0,0.0,1.7149071791302877,0.013673338540010363,-0.0041280977196796395,0.9986442335986878,0.03772107847452049,-0.03416126756273095,-0.01094635734053921,0.7416554194304683,-0.04990947370809539,0.0761037660603003,-0.8199768178954329,1.4085063517012701,-1.2713697961495976,-0.2517617895174014,0.8080502509034974,-0.5573118831635318,0.07447547599055877,-0.1949684369300979,-0.24358813432499868,-0.2539035249687399,-0.6838529453871601,1.0041574539128821,0.027299602839676865,-0.14992260049535513,1.229560893223713,1.247439273753766,1.4083717419812758,-2.037870943847644,2.6926772304007263,-3.5617553146931615,2.4201970463664084,0.29831256191703903,1.796539672843822,-2.8334620285522982,-1.1278755263410818,-5.357236732563533,2.30938091027574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.591666666666667,1.0,0.0,1.0,0.0,1.7209286121248433,0.013076835501006093,-0.003049727539483452,0.9988820846668861,0.034566888273728176,-0.027934871430559866,-0.01610447542156783,0.7193810665850975,-0.038344673806308786,0.10008922985387911,-0.8136458385528464,1.4644464807517543,-1.2592302997889757,-0.2414419300254432,0.819298012646684,-0.5740368855487087,0.09707695960810306,-0.22439972749170395,-0.22413270818236705,-0.2514113262027915,-0.6687124796787552,0.9792715905660063,0.01840761164104837,-0.1951552839705984,1.2480112704172677,1.229330023950664,1.2920032778629387,-1.9732399859952654,2.731951743385667,-3.4956025741994923,2.2483303856856036,0.3004792143827312,1.8358934277415795,-3.1301324978699374,-1.0032849518844356,-5.48608550504047,2.1161893035998025,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6,1.0,0.0,1.0,0.0,1.7267576527554116,0.012513525002656017,-0.001855478476329103,0.99904957219208,0.031439468289525395,-0.021499345743073047,-0.02119646849630951,0.6952764914295443,-0.02773364658395495,0.12283026993469962,-0.8067746370662345,1.5090472646666457,-1.2442500832243941,-0.23127295578489035,0.8295836388678797,-0.5901992162634528,0.12000800504698655,-0.2532284798334228,-0.20611596123023862,-0.24889553806236106,-0.6532547215914671,0.9519885789483832,0.010578186974936274,-0.2413573589126963,1.2648307149503764,1.2114292935558686,1.178008557003829,-1.9033044626291185,2.7717458495762584,-3.416185842621119,2.0736081322054396,0.30392388097367273,1.8730827035778863,-3.4082869048824693,-0.8742603210343091,-5.589688280024209,1.9183906729232136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6083333333333334,1.0,0.0,1.0,0.0,1.7323858063473194,0.011982756196940272,-0.0005556056950706191,0.9991434141276091,0.028340978371015655,-0.014903019599785851,-0.02621310685314052,0.6695434628519363,-0.01820451642549916,0.1440310808930777,-0.7995876415684459,1.542142576735126,-1.2267936771738535,-0.22125144179951206,0.8389314885967478,-0.6057586265925273,0.14327272376770736,-0.28133615820205593,-0.18957257264560973,-0.24634592818656362,-0.6374944346191238,0.9224668088179652,0.003836606290476553,-0.2883167553043352,1.2799844482993212,1.194147152749524,1.0674333733382446,-1.8288689616510734,2.811969361686414,-3.3214747275102563,1.8931707956384187,0.3085305431071528,1.9087470014395413,-3.6667906803885586,-0.7433137349289084,-5.66780894082792,1.717003134928241,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6166666666666667,1.0,0.0,1.0,0.0,1.737805726237681,0.01148299436327091,0.0008384390285569634,0.999161673239905,0.025272337430997063,-0.008194843084604466,-0.031146496734255125,0.642394188093004,-0.00987137006278234,0.16339928109293808,-0.7923082151053868,1.5635811698200672,-1.2072420749675516,-0.21137050323906495,0.8473741950901837,-0.6206803656243041,0.16687416107509345,-0.3085863919585937,-0.17456311463626498,-0.24375336234390851,-0.6214422715674748,0.8908754009419072,-0.001810375273878866,-0.3358208412598283,1.293447433865847,1.1779025546267896,0.961224115512409,-1.7504733983620713,2.85244761325741,-3.2092335411429342,1.7036815597625932,0.31416591883965617,1.943216776222958,-3.9041859533998946,-0.6123820242636194,-5.720539638475092,1.5133021821778003,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.625,1.0,0.0,1.0,0.0,1.7430111090195517,0.011011799049760615,0.0023139533658467766,0.9991037826068155,0.022233195069064904,-0.0014242687156514793,-0.035990111306350145,0.6140544968766469,-0.0028353058186089616,0.18065275747805642,-0.7851574265857781,1.5732411621592877,-1.1859818180066968,-0.20161973255573223,0.8549518905219546,-0.6349331832318952,0.19081351732199753,-0.3348233838877715,-0.16117787998289984,-0.24110982953923601,-0.6051074883487412,0.8573970429279669,-0.00636976078058377,-0.3836590826122534,1.305206151335618,1.1631187096602353,0.8602372487816656,-1.6684371201839454,2.8929041513387235,-3.077066220634687,1.501391007031997,0.3207022245998936,1.9764827148226494,-4.118654878508148,-0.482854203622845,-5.748278964033257,1.3087291595838346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6333333333333333,1.0,0.0,1.0,0.0,1.7479966309793897,0.010565803194517965,0.0038569733554422473,0.9989705458075672,0.019221914991192676,0.005358927346002393,-0.040738784253936774,0.584767962569833,0.0028162108077688097,0.19552698693609916,-0.778350758084495,1.571043441270013,-1.1633975199791127,-0.19198519141139436,0.8617114825698782,-0.6484876509607032,0.21508923026407217,-0.35987082896917183,-0.1495399311857317,-0.23840832526724362,-0.5885008929870973,0.8222311529667714,-0.009857945334259615,-0.4316254906603826,1.3152595865255776,1.150214275751021,0.7652423296066369,-1.5828871269193234,2.9329437333728077,-2.9224945672891534,1.2822666557149094,0.32802935128558086,2.0081707922516,-4.307975595377423,-0.3556305030844079,-5.751697134540871,1.104794884026119,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6416666666666666,1.0,1.0,1.0,0.0,1.752757949120174,0.010140705551261814,0.005452309212946502,0.9987641093392776,0.016235580689357855,0.012104874208801242,-0.04538867597917053,0.5548022845133496,0.007011637296782072,0.20778289531465644,-0.7720932599773123,1.5569619824034056,-1.1398652571774788,-0.18244949462654855,0.8677059293487319,-0.6613146353472172,0.239695912878211,-0.38353162667592405,-0.13980676905431802,-0.23564267368447633,-0.5716379751445478,0.7855974496716766,-0.012296935831990569,-0.4795207015212679,1.3236193994027199,1.1395899157270901,0.6769186128647942,-1.4937636133953647,2.9720331796076738,-2.7430699804145076,1.0421984740363228,0.33605853095235116,2.0375241368692887,-4.469467272745531,-0.23119724075810735,-5.731678934507549,0.9029815053813106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.65,1.0,1.0,1.0,0.0,1.7572918001669198,0.009731285651763087,0.007083630829165814,0.9984879060509843,0.013270030563215546,0.01876386699989083,-0.04993721204626132,0.5244586565909221,0.009699178283769996,0.21721533654197822,-0.7665736453322148,1.5310296550927531,-1.1157446769998114,-0.1729920261492762,0.8729934594509581,-0.6733837111839592,0.26462311659086674,-0.4055886619760803,-0.13216995661845965,-0.2328073497513711,-0.5545421573726091,0.7477400317543459,-0.01371123268022807,-0.5271534729021751,1.3303092782819328,1.1316099488469056,0.5958455498626547,-1.4007994562031434,3.009477261921896,-2.536515129628587,0.7772800321699569,0.34471965344185895,2.0633914816268217,-4.599921977724593,-0.10970679761283093,-5.689241047103231,0.7046500308639914,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.658333333333333,1.0,1.0,1.0,0.0,1.7615962340304532,0.009331447274238708,0.008733603594676299,0.9981465704079799,0.010319927306406596,0.025286636757724558,-0.05438298630525855,0.4940840187440828,0.010851973434877399,0.22366209134106677,-0.7619575916935526,1.4933391251934667,-1.091368793732774,-0.16358932881243346,0.8776366885131095,-0.684661292950603,0.2898538672435759,-0.4258068788364005,-0.1268521018514854,-0.22989734612711202,-0.5372481171174341,0.7089320833762667,-0.014125382458871084,-0.5743413856396551,1.3353635665837864,1.1265789684246053,0.5224883254301815,-1.303475741821214,3.0443879100463422,-2.3008848857630473,0.4841449751425783,0.3539536825759948,2.084220667985328,-4.695523323380746,0.008942878561976585,-5.625427998097077,0.5109639633069074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6666666666666665,1.0,1.0,1.0,0.0,1.7656710129018276,0.008934293551658503,0.010384071251657431,0.997745828479037,0.007378865584153429,0.031624607961207904,-0.0587256196339446,0.3588359352474219,-0.009074006691174356,0.2429040808961344,-0.7794697480445567,1.3812677986164466,-1.1029592124246765,-0.1542157100088661,0.8817015982081278,-0.6951083068809795,0.3153629150916391,-0.4439367434054644,-0.12410087369941668,-0.22690812170843785,-0.5198051462395203,0.6694813096980001,-0.013562184704195127,-0.620910606203793,1.338825344337048,1.2152142102177466,0.3448148416873664,-1.366873542098852,3.0471530782668332,-1.186737300883829,-0.6921287059931819,0.39651101216438334,1.940290305482133,-4.685998021925933,0.158414450820066,-5.811517142688845,0.45902646264838864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.675,1.0,1.0,1.0,0.0,1.7677577991435038,0.008408571525520136,0.01238920261438984,0.9972938389829109,0.004219910703892693,0.03722087327074617,-0.06325976601287699,0.23295515113600418,-0.026859600703825495,0.2447882648641413,-0.7775032908557499,1.2917521668091378,-1.1046675723984025,-0.14333575864213768,0.8833836025412323,-0.7074425186522505,0.3406397518813565,-0.445585833851131,-0.1383875802847051,-0.22328882925770563,-0.5049099453593986,0.6308321163441678,-0.011485141611869984,-0.6712000046844692,1.3430140076279262,1.2723265348350428,0.31281542368625237,-1.761573493483728,3.0082293599271095,-0.10920779960612359,-1.892958440184205,0.41578801098989815,1.771151252814901,-4.636006540977462,0.2857917701052711,-5.977056567876944,0.3819003267920573,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.683333333333333,1.0,1.0,1.0,0.0,1.7697558488684741,0.00794800630062596,0.014160449017472532,0.9967915014301056,0.0012565203317315193,0.042808380714135126,-0.06762075663566912,0.22930361145134107,-0.020395239973614407,0.2235804591391972,-0.7431574769427227,1.2749597347937958,-1.0630198268822812,-0.1330102677616154,0.8869151886028986,-0.7244678651057083,0.36550007109042426,-0.4457568733988998,-0.1556501810358201,-0.21997832152527289,-0.49028595869260533,0.5922145340150424,-0.008798988535773941,-0.7205282156684087,1.3451903497835822,1.2212987007430196,0.5090563281048044,-2.2241315838356424,2.9553186939006704,0.02081140209511445,-2.0846879798921374,0.38950625227524793,1.7644595319941092,-4.617070851412555,0.36698306173142115,-5.8099165596654245,0.12637554866126166,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6916666666666664,1.0,1.0,1.0,0.0,1.771802088661785,0.007526065958982579,0.015776187348862002,0.9962496033321259,-0.0016136424567363096,0.0482414123731179,-0.07181149275735006,0.23545646324817793,-0.014844943113593287,0.20892414639862406,-0.7216053805504662,1.2266932299651467,-1.0227867482267845,-0.12298078029642069,0.8918678746763123,-0.7445113783828445,0.38989506344636765,-0.44523897714954574,-0.17313237994957406,-0.2167970583864515,-0.4755022864928301,0.5538809354872919,-0.005368757249679632,-0.7680319473455596,1.3451202667722806,1.1910540819804645,0.6630197029467277,-2.5299943054681817,2.8910305084794574,0.09593675963319281,-2.056462941610941,0.3745433783302249,1.7834296113215042,-4.552592435792502,0.4548186024847659,-5.574660360329871,-0.13142478205089958,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6999999999999997,1.0,1.0,1.0,0.0,1.7739215278168,0.007128100181064378,0.017252506928308684,0.9956788674517282,-0.004411566193639992,0.05341073614266477,-0.07583814716710373,0.24408734619060143,-0.010164528942399512,0.19525208959578141,-0.7020681186994943,1.1554373929004385,-0.983999258377312,-0.11315936639527432,0.8979655169853441,-0.7666344368635113,0.4136839128984152,-0.44415792740501325,-0.18992456339600244,-0.2137359318864358,-0.4605621318372469,0.5163379934185007,-0.0012186784943611765,-0.8134392216739066,1.3429999367494005,1.1689400591213215,0.791099734727756,-2.7437565835415145,2.809594700108149,0.16605850941178724,-1.9531757055306282,0.35926487970181775,1.7937482512815373,-4.4219755355771415,0.5387136483673869,-5.315456934762874,-0.3628181058546476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7083333333333335,1.0,1.0,1.0,0.0,1.776122995316831,0.0067445493156609755,0.01858459335202838,0.9950901908630867,-0.007147216540271139,0.0582362131738814,-0.07970553984403538,0.25441979234583995,-0.006062666965460928,0.18087383708595306,-0.6831629735534396,1.0663570675749698,-0.9465132218000178,-0.103498445977732,0.9050528702551083,-0.7902406547752031,0.43672164178150347,-0.44247133532601596,-0.20568530837508453,-0.2108093103914212,-0.4456064823048045,0.48018134322767286,0.0036098035564434824,-0.8566228962582741,1.3390732983413698,1.151772568626574,0.9035490015286451,-2.8934263573968555,2.7105661497483102,0.24578489274584392,-1.8226118892852428,0.342000035188213,1.7834936795141654,-4.21587809178381,0.6176207852333485,-5.043713358954299,-0.5652049799886072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.716666666666667,0.0,1.0,1.0,0.0,1.7784160983996091,0.006367077506359761,0.019762065253949947,0.9944946590228241,-0.009828528148966202,0.062651100526955,-0.08341830150817338,0.26678725241576245,-0.002359490198959209,0.16536748503374354,-0.6646149385129693,0.961889341403441,-0.9103752305176801,-0.09396315691816476,0.9130246670108215,-0.8148582094867922,0.4588600153942204,-0.44006151252591585,-0.22030142821742316,-0.2080359312999656,-0.4308372371786775,0.4460733585554372,0.009075001259527966,-0.8975011109898116,1.3335798537495904,1.1383736156403168,1.005030408109826,-2.9900531382500173,2.59349627316503,0.3418731605242731,-1.6848306452635364,0.32236664837532014,1.7462969819480012,-3.9259298187934446,0.6916315211454295,-4.763449678374306,-0.7392408813937168,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.725,0.0,1.0,1.0,0.0,1.7808141514655003,0.0059876267687655705,0.020772936868152698,0.9939034057861568,-0.01246291161722624,0.06659561095326715,-0.0869811506500525,0.2816238403892575,0.0010881576995343534,0.14862226293979808,-0.6463135818006952,0.8433710948506623,-0.8756452379691718,-0.08452555238372672,0.9218033770569387,-0.8400748737460367,0.4799465796675873,-0.4367734493172781,-0.2337658191294768,-0.2054365329184992,-0.41650153260567113,0.41474917958111546,0.015136995575533973,-0.9360137242311792,1.3267526169848078,1.1279982715372179,1.098455081027634,-3.039762141311586,2.4579934219094435,0.45749331436371166,-1.5492607163873917,0.3001380092686251,1.6769110565175993,-3.5432064728481185,0.7609684527366948,-4.4770394194899525,-0.8853991935220273,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7333333333333334,0.0,1.0,1.0,0.0,1.78333355733906,0.005598256920297128,0.021604526888636937,0.9933274102676275,-0.015057593936573431,0.0700142500257234,-0.09039872670996536,0.2992316488781679,0.004398902702716895,0.13056386483767163,-0.6281901766638913,0.711617229833098,-0.842334559929262,-0.0751631857258778,0.9313322516946154,-0.8655209118419853,0.49982657242604445,-0.4324366239531873,-0.24612244015721302,-0.2030336311454885,-0.40288871957005085,0.3870199173413019,0.021757808805139545,-0.9721184346479774,1.3188232005242233,1.1200294843475067,1.1861396305203153,-3.0473079262422753,2.303994770567829,0.5936740733469914,-1.4201379336922848,0.27509688946419975,1.570578673970322,-3.0589590931409094,0.8258666919730552,-4.186668150971049,-1.0034532789083572,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7416666666666667,0.0,1.0,1.0,0.0,1.7859925552386147,0.005191089169671028,0.022243446682775624,0.9927772921476579,-0.01761980452796166,0.07285411346091616,-0.09367533784299445,0.3197617814996979,0.0076585894179211494,0.1110561940531459,-0.6102174156523887,0.567024503903192,-0.8104037400726989,-0.06585839431126828,0.941572370898944,-0.890863339183408,0.5183464925103844,-0.42687888142816155,-0.2574347846910149,-0.20085158476076254,-0.39032522137283243,0.36376652802876697,0.02890144044175156,-1.0057915267473634,1.3100283956696686,1.1139551798850464,1.270129525143724,-3.016836280613533,2.1319078083298004,0.7500975624030437,-1.2984904427325095,0.24702114522653917,1.4235936370067315,-2.465907257014347,0.8865894041940197,-3.894681664898285,-1.0922719678335868,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.75,0.0,1.0,1.0,0.0,1.788810088197092,0.004758141386091509,0.022675127119823106,0.9922631366776152,-0.020157094822110522,0.0750630937659766,-0.09681472577700766,0.3410897353396479,0.01054097444395239,0.09379298476657019,-0.5949180270825732,0.4314099847405019,-0.7785947675021677,-0.05659726606112702,0.9525010771136775,-0.9158015165188775,0.5353583692315411,-0.4199349979131366,-0.2677639475360882,-0.19891661205837952,-0.379162158953272,0.3459214630577295,0.036534298875039874,-1.0370297957296155,1.3006186677269969,1.1121197117231494,1.3437402543364874,-2.980924086346848,1.9589119651852127,0.9048758938900148,-1.1982666264033004,0.2229691825667668,1.2706911658214126,-1.8752107195982304,0.9431420613571049,-3.5782538827662558,-1.2021341516073036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7583333333333333,0.0,1.0,1.0,0.0,1.791778941190144,0.004293710848103301,0.02295354504299138,0.9917808726358053,-0.02267935624804034,0.07677098344375756,-0.09981264251987995,0.359974946537076,0.012799168210854216,0.0843127412773206,-0.584632557762694,0.3366321369135655,-0.7455971775746381,-0.04732306578254912,0.9639680418045521,-0.9405454072891888,0.5509950252634713,-0.41179761652999464,-0.2774058951310699,-0.1971354317179831,-0.3691470352758089,0.3325130160354631,0.044620474797703306,-1.0654290914601343,1.2899928264762135,1.1167104678185256,1.3950112000510795,-2.983077295643737,1.8106314413294977,1.0273042749652272,-1.1411233191858972,0.21169179402226235,1.173492105038656,-1.4703717054534615,0.9939249732027018,-3.213566091510014,-1.4001429885234007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7666666666666666,0.0,1.0,1.0,0.0,1.7948812464781108,0.0037999537499727315,0.02316301032358987,0.9913180609511675,-0.025186617118430444,0.07819105486172717,-0.10266594034633604,0.3767835935758943,0.01515572319071732,0.08140631834026989,-0.5762335150347463,0.2763819086939602,-0.712628421833164,-0.03798542493081826,0.9757512637811955,-0.9655194714462731,0.5655355599203661,-0.4028132599970495,-0.2867826695225198,-0.1953884154913418,-0.3596039572026277,0.32141526796683845,0.053099715095084904,-1.0905892305881157,1.2772829512516068,1.1238379392479427,1.4253278860641028,-3.0136023227237985,1.684350558193941,1.1231608201205368,-1.121939641380697,0.20764475435977925,1.1363107577244747,-1.2464265948398023,1.036079836541712,-2.8259804362920216,-1.6596475621510587,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.775,0.0,1.0,1.0,0.0,1.7981172710646012,0.0032836618765073352,0.023334301861804463,0.9908709009953446,-0.027667917882046904,0.07939791571142144,-0.10538175776920622,0.39332981866222644,0.018136690548174475,0.08102081811548889,-0.5668057554025293,0.22828258387084144,-0.6810077794779659,-0.028592433461750076,0.9877235065722871,-0.9907721126679188,0.5790675345667037,-0.3930782695279857,-0.2961048891540815,-0.19367468581198677,-0.35020852264706764,0.31173923945479975,0.06188847207339851,-1.1125287653983347,1.2623320337736958,1.1302284814233643,1.442590975724658,-3.042824073862267,1.5651705662832582,1.2112424694291113,-1.1204048141246448,0.20285060022984414,1.1268702928469176,-1.0963681953800641,1.0687638550525134,-2.4438272381083115,-1.9237941426309169,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.783333333333333,0.0,1.0,1.0,0.0,1.8014906355006806,0.002748650628986748,0.023479377439411333,0.9904389378381484,-0.0301173526870142,0.08041706908860699,-0.10796643221290941,0.4101715787809539,0.021546351117689738,0.08165597666453704,-0.5566239677414895,0.18406093308860702,-0.6505826965665551,-0.01914828357376219,0.9997944467099398,-1.0162332060106443,0.591621736025087,-0.3826258855065643,-0.3054560830912639,-0.19200757215417774,-0.3408227856551791,0.30314246471050404,0.07091244601262679,-1.1313196845565876,1.2452197155410916,1.1364670857550678,1.4500636324640714,-3.061260804249719,1.4484615724885574,1.2967317918888066,-1.1255774693008935,0.19658068145055385,1.1292988967101047,-0.9739223222913906,1.093316563076884,-2.0719355856703547,-2.17315300807178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7916666666666665,0.0,1.0,1.0,0.0,1.8050063746234073,0.0021961447922530697,0.023602981401501348,0.9900231012550071,-0.03253282968023406,0.08125488178821773,-0.11042426437140236,0.42758791754731074,0.02518407135315731,0.08261776506436042,-0.5459752791673651,0.13984478274390355,-0.6209212923090308,-0.009651315365832278,1.0118912337800217,-1.0417931260720807,0.6032085607748463,-0.3714660729965056,-0.31486451364242973,-0.1903983411211442,-0.3313868743685659,0.29550720074994324,0.08011041479134658,-1.1470610251595073,1.2261128169724995,1.1429395797305077,1.4495098358700353,-3.0652535593045283,1.3319296064327046,1.3819771934679947,-1.1322009166351776,0.1890496774403838,1.135916769188522,-0.8569064268151383,1.1110707092058398,-1.7133541890974424,-2.3991360797340366,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8,0.0,1.0,1.0,0.0,1.808670188927795,0.0016254061260896654,0.023705309787147747,0.989625397860635,-0.03491387549579452,0.08190514587445008,-0.1127569966215714,0.4456714222777795,0.028923050320817892,0.08356977252661053,-0.5350332093991913,0.09386788109520944,-0.5916555514244457,-9.92905782537296e-05,1.0239529439744404,-1.0673207653323864,0.6138205627989655,-0.3595929322820977,-0.32432609836851684,-0.188856744196838,-0.32189083950203706,0.28886069093025174,0.08943029116605745,-1.1598755877082116,1.205234114212191,1.1497408615512934,1.4419136682032496,-3.053870371958216,1.214553226094981,1.4677736211614567,-1.1374564930070197,0.18054568961628215,1.143066586071727,-0.7349824892613199,1.1229260190047596,-1.3702279422136865,-2.5982879370532608,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.808333333333333,0.0,1.0,1.0,0.0,1.8124872788783044,0.001035096070634985,0.02378586036681672,0.9892479145628784,-0.037261197939755464,0.08235985308639979,-0.11496530459645328,0.4642690737488983,0.032744290210634366,0.08456804231659276,-0.524058175199635,0.046794455755406666,-0.5628401551110126,0.009511032326689277,1.0359231282500758,-1.0926909656047177,0.623451114543096,-0.3470031793104813,-0.3338221218592134,-0.18738924629420617,-0.3123357646007038,0.2832574925955879,0.0988258484414259,-1.1698981575297354,1.1828080180216118,1.1570253945280706,1.4273760665447144,-3.029126810634426,1.0975695750639458,1.5527534946375432,-1.1402452930402474,0.17140881822866438,1.1516638156254044,-0.6115063500029494,1.1292764718918809,-1.0431983866121763,-2.7733895608114167,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8166666666666664,0.0,1.0,1.0,0.0,1.8164610210633938,0.0004248956568137644,0.02384660189533059,0.9888917627836926,-0.03957592348410518,0.08261846029936336,-0.1170513468388649,0.48320163402276584,0.03664910679784274,0.0856390386609256,-0.5130215859936808,-0.0009246112024263731,-0.5345798088060495,0.019184465997214115,1.047742545083519,-1.1178062121762935,0.6321133890500312,-0.333713707371472,-0.3433301865858543,-0.1859999305596936,-0.302696442574947,0.2786689184302026,0.1082515656975888,-1.1772622274850812,1.159010954865334,1.1646357295765155,1.4058926670666239,-2.9925774669773597,0.9818470164338833,1.6357075455227776,-1.1393875801047215,0.16162620218856338,1.1627533167646464,-0.48972780731245336,1.1302101253755705,-0.7327718377375492,-2.9267240418644347,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8249999999999997,0.0,1.0,1.0,0.0,1.8205938805377428,-0.00020565779933751628,0.023888279472748696,0.9885582890547717,-0.041858238988395025,0.08267658813668695,-0.11901671623769743,0.5023851311595172,0.04060247703319306,0.08664009687448979,-0.5017492605290812,-0.04990366217250529,-0.5067685255502105,0.028921627819631205,1.0593546727011862,-1.142567256721007,0.6398152314836607,-0.3197413868851017,-0.35281191486095875,-0.1846954762577301,-0.29295654265462634,0.2750953624737137,0.11766268386435208,-1.1821110214920278,1.134029283990538,1.172219638809639,1.3777143513983692,-2.9443414086162933,0.8670878384961012,1.7164176975197631,-1.1331556202141102,0.15105414536022377,1.1755439532206169,-0.3672076844113048,1.125958285371612,-0.43981553179735844,-3.057771566888836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8333333333333335,0.0,1.0,1.0,0.0,1.8248874085320874,-0.0008570764300061407,0.023911233336821644,0.9882488278885951,-0.04410837893395783,0.08252845916784882,-0.12086256042319735,0.52291846684426,0.04481656211484848,0.08846763328081488,-0.48820380418284315,-0.11405472063891851,-0.48066243431307615,0.038721459977374764,1.0707044509401584,-1.166878568986565,0.6465648530249662,-0.3051067457461426,-0.3622161135894228,-0.18348236147035654,-0.2831040433546034,0.27254879035668084,0.127017537120449,-1.1845924863483706,1.1080480954171867,1.1771576232032255,1.3385892025138313,-2.8533519071505653,0.7386494369758556,1.796204172008099,-1.0846141633109585,0.1353850875782403,1.1854204839986926,-0.20455311083451777,1.1141917544972546,-0.1637941612926097,-3.1460664929895543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.841666666666667,0.0,1.0,1.0,0.0,1.8293650730362532,-0.0015297179185158735,0.023928204341124814,0.9879733903529028,-0.04632487129186995,0.08205254665081774,-0.1225967611421671,0.5462550385283198,0.04933835250265957,0.09171613326681521,-0.4709860025773651,-0.21013566926179514,-0.45745529120182954,0.048540921539684964,1.0816644927430834,-1.190123121840183,0.6521260554332583,-0.2898046506849667,-0.37088881758280806,-0.1824390581314261,-0.27319953458798146,0.27168614395980506,0.13623254643930632,-1.184840924180238,1.081594842440712,1.1773270112275354,1.2854603786594332,-2.6854427670558634,0.5805232831502338,1.8766488913276536,-0.9504585197676763,0.11055764346858121,1.1837632513604102,0.052160341170911506,1.093782073040463,0.09400098230859744,-3.163407325299654,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.85,0.0,1.0,1.0,0.0,1.8340535402595872,-0.0022285186689427446,0.023948203551725385,0.9877433267252987,-0.04851441088524227,0.08110316104777922,-0.12422459383803905,0.5714450536148736,0.05358168120928904,0.09469638780262102,-0.4530859611840904,-0.3278296959793513,-0.4355183936224066,0.05834357683116702,1.0921287905844823,-1.2116359484374961,0.6562402410774701,-0.27382926422401505,-0.37805708891888407,-0.18163973407921352,-0.26337465583192987,0.27341812937619603,0.14524723833779005,-1.183025803309894,1.0553246399955258,1.1758095755167177,1.2251177553817838,-2.4712473199585805,0.40740886087429207,1.9552404570293525,-0.7580162786563793,0.08160008054735546,1.1693371382996687,0.3830311243848805,1.0698771158522746,0.32875531205569075,-3.120076431250385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8583333333333334,0.0,1.0,1.0,0.0,1.8389539338550178,-0.0029611937427348064,0.023963568761085872,0.9875606194560936,-0.050688947437707965,0.07964727627554187,-0.12574165932229722,0.5965622565404218,0.05719480833786855,0.09596741408591832,-0.4366538966457102,-0.44908565386459776,-0.41316469698723607,0.06813774779829693,1.1020831219994465,-1.231310577172826,0.6589162031144965,-0.2572173097344775,-0.38352242222708105,-0.18107905678897018,-0.253710582282987,0.2780699960328864,0.1540638317035109,-1.1793616689793098,1.029593568586539,1.1748953662629076,1.1630762034941533,-2.2537007898426076,0.24028892053634232,2.0271512026191587,-0.5510990894250112,0.05355362215639092,1.1511026053419893,0.7309742492999705,1.0459339685870006,0.5382094172783392,-3.042762556644587,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8666666666666667,0.0,1.0,1.0,0.0,1.8440567412276536,-0.003731821017548736,0.023967245784670604,0.9874234408298922,-0.052853629519292906,0.07769055035306478,-0.1271440943662846,0.6207602111867533,0.06023736847723081,0.09534573406436009,-0.4210360307705623,-0.568505624063272,-0.38984930662960343,0.07792516626888214,1.1115133939760515,-1.2491976282682062,0.6602450564197425,-0.24004341084702907,-0.38724207374263425,-0.18074717370994034,-0.24418961240956338,0.28560103353119554,0.1626794711475734,-1.174055646355255,1.004611930718116,1.1734819086885135,1.0989474619012007,-2.043532770395595,0.08451556773055868,2.08952918156638,-0.3404852931488722,0.026567391247835914,1.137148881251998,1.0683548265819454,1.0214967395966867,0.7228761425009234,-2.9412037955899595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.875,0.0,1.0,1.0,0.0,1.8493495510968445,-0.0045435786998785374,0.023951673503127872,0.9873293687949916,-0.05500908244298265,0.07524390031524877,-0.12842536287317338,0.6437795743515619,0.06272665705718398,0.09278431783659392,-0.4057106601253408,-0.6849407473234037,-0.36496028450253215,0.08769577960977215,1.1203989130311331,-1.2653694566794194,0.6603247959100058,-0.22239182337503782,-0.3891971771128956,-0.18063626693483958,-0.23475810092878702,0.29587590980925216,0.17108877736345568,-1.167313733270961,0.9805735053267063,1.1705642672620198,1.0318051409273687,-1.8423591458895716,-0.05916677668745374,2.141130857734396,-0.1276585354381765,0.0006403078305738941,1.131456441634023,1.3851247851515092,0.9965121242523622,0.883426711757691,-2.817579913613839,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8833333333333333,0.0,1.0,1.0,0.0,1.8548190578361294,-0.00539892229515074,0.02391039346339138,0.9872753394607112,-0.0571544517296815,0.0723221287760329,-0.12957732220418158,0.6651831598897817,0.06488052641949418,0.08885565839743,-0.3908912883748552,-0.7944397433032375,-0.3392067533588231,0.09743457072324914,1.128710146324841,-1.2799036140330324,0.6592589434749516,-0.2043578965514558,-0.3893697159999372,-0.1807365019127641,-0.22533200504899634,0.308686446617054,0.17928800655177943,-1.15933186782596,0.9576522654912187,1.1663082954810513,0.9596473302518893,-1.6536478325017745,-0.1870351237385437,2.1782293662384205,0.08575592599096682,-0.024167849166519817,1.1416898573116414,1.658206252195643,0.9705383451417499,1.023770240251567,-2.683418091507106,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8916666666666666,0.0,1.0,1.0,0.0,1.860448822159039,-0.0062944218783337075,0.023846165305354414,0.9872545913907851,-0.0592881395804097,0.06896853566030581,-0.13060103128174022,0.6846429033989918,0.06692326390461804,0.0841412207481198,-0.37644536921251454,-0.8937286113626519,-0.31340485596331585,0.107134251201123,1.136393035201998,-1.2929302538877823,0.6572075438476968,-0.18608800060439748,-0.3877679116797128,-0.18103906442094825,-0.21572993664025966,0.32351268067917954,0.1872644164491515,-1.150250895933435,0.9358498704682545,1.160614412744051,0.8806941020931314,-1.4795165078175998,-0.2967326677138993,2.1982260548509007,0.29795382003935167,-0.048208389528024975,1.1733953060003643,1.8697888744359759,0.9428568937349396,1.147726333634811,-2.5490674789294965,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9,0.0,1.0,1.0,0.0,1.8662231573294619,-0.007226353735102469,0.023761689677241148,0.9872607554486811,-0.06140506904960196,0.06522436821911468,-0.131496768159471,0.7022361654296857,0.06889521309513805,0.07871392748694697,-0.36189599135934747,-0.982965967925974,-0.2873389077664024,0.11677814426898332,1.1433883813597265,-1.304562222496659,0.6543133990130533,-0.16772079563727413,-0.38440381899928133,-0.18153997507156452,-0.20577541661565693,0.3398495945243203,0.19500228811402842,-1.1402030955987132,0.9151678075090605,1.1527424834273245,0.7945411265660685,-1.3183929143978856,-0.3899226896084018,2.2020532929028946,0.5080756126548747,-0.07171810862552086,1.2252025097033048,2.022615115288872,0.9134236399366552,1.256459310320932,-2.4151107474950284,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.908333333333333,0.0,1.0,1.0,0.0,1.8721275010733005,-0.008190577511448959,0.023659785851797118,0.9872876605024055,-0.06349954478758979,0.06113123895790948,-0.1322643370488148,0.7180575456731163,0.07084641176297912,0.07265860823114839,-0.3471635255201574,-1.0620466080722406,-0.26087171328059156,0.12634662592491175,1.1496353873114324,-1.314903469127747,0.6507088323542234,-0.14938711238934924,-0.37929998480213156,-0.1822343662313736,-0.19530989481187125,0.35722293260066074,0.2024881437814291,-1.1293099074280861,0.8955980246766707,1.1423818235742265,0.7011192648101439,-1.169342790902821,-0.46786435789114345,2.190790912633856,0.7145797231328632,-0.09456576003904704,1.2946354023698354,2.120881185738394,0.8825182416223654,1.3511834477934936,-2.2826919478130625,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9166666666666665,0.0,1.0,1.0,0.0,1.8781483434661923,-0.00918260746129485,0.0235431392921257,0.9873294488167857,-0.06556547817592882,0.05673129943060738,-0.13290330031883127,0.7321938267749571,0.07282127708223823,0.06603912599410765,-0.332197838391583,-1.1308720412245845,-0.23390459908084515,0.13581784132855376,1.1550737024398956,-1.3240512690117061,0.6465156597148676,-0.1312076137600432,-0.37249415694706695,-0.1831160710722153,-0.184198159909493,0.37519761428662685,0.20971092547440118,-1.1176833714688217,0.8771229417121761,1.1292815930767837,0.600566861127958,-1.0316266935085672,-0.5318569561864872,2.165781737146029,0.9154651821338955,-0.11658340062340788,1.3787005488822024,2.16961598986171,0.8504300183306918,1.432923110794806,-2.152872234452967,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.925,0.0,1.0,1.0,0.0,1.8842730546066753,-0.010197678771651507,0.023414060981653533,0.9873807219551037,-0.0675964835009104,0.05206705113444082,-0.13341307100842814,0.7447166083887693,0.07485638624115618,0.05889950336915365,-0.31695722479752786,-1.189400776496,-0.20635607236530726,0.1451679858095248,1.1596448349968984,-1.3320972473528898,0.6418445497511153,-0.11329075010358208,-0.36404223176656664,-0.1841774229084304,-0.1723315523305012,0.3933831990983559,0.21666197742027396,-1.105427855581506,0.8597168207691213,1.113223769627818,0.49316223982407426,-0.9045957638628366,-0.5832624737004033,2.128600088097771,1.108423453326851,-0.13757489575771886,1.474146204360934,2.1742891973024694,0.8174459664768308,1.5025084458219995,-2.0265435325440895,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.933333333333333,0.0,1.0,1.0,0.0,1.890489699305114,-0.011230821219412476,0.023274304296411703,0.987436673507363,-0.06958597154502282,0.04718108436158724,-0.13379295069366093,0.7556789038507197,0.07697916061167921,0.05127001006205865,-0.30140517177181836,-1.2376542180475512,-0.17815428154692375,0.15437157082235073,1.1632930731036302,-1.3391278650760867,0.6367946184865275,-0.09573094562508035,-0.35402043272495276,-0.18540898600151062,-0.15962905650347745,0.41143576757500133,0.2233350249156817,-1.092641564038455,0.8433472161697746,1.0940209634105535,0.3792678607661726,-0.7876458416816412,-0.6234725035601629,2.0810196071206137,1.2909112274585,-0.1573106253165213,1.5776838970322067,2.140418713426965,0.7838455162291996,1.5606082939827193,-1.904448241615082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9416666666666664,0.0,1.0,1.0,0.0,1.896786829770219,-0.012276919794578756,0.023124959233546565,0.987493197656997,-0.07152722125783656,0.0421158324228799,-0.13404214956358176,0.7651109616287972,0.07920765226378862,0.04317525626195719,-0.2855055407863456,-1.2757113559678017,-0.149235095064781,0.16340166853303403,1.165965966009668,-1.3452246780475838,0.6314533413584459,-0.07860708998490519,-0.3425270446422583,-0.18679926666370575,-0.14603682071329777,0.42905684432213864,0.2297260693574273,-1.0794177173484607,0.8279760167422032,1.0715132021849323,0.25927970675594825,-0.6801909442316978,-0.6538745701313364,2.0249752618440624,1.460203527093371,-0.1755272052728868,1.6861395043822753,2.0732856204655072,0.7498889614633203,1.607770557922299,-1.7872314296178193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9499999999999997,0.0,1.0,1.0,0.0,1.9031532570838494,-0.013330754954420047,0.022966427954665525,0.9875469716183862,-0.07341342568471067,0.03691334207142925,-0.134159803792801,0.7730234522680487,0.08154937108432773,0.03464035766207307,-0.2692265103344698,-1.303698574065625,-0.1195461812207988,0.1722301241920996,1.1676144015495626,-1.3504643808132817,0.6258967089843386,-0.06198135792767931,-0.3296837072733966,-0.1883344394227254,-0.13152673143043953,0.4459905279160931,0.2358331742734037,-1.0658453880730834,0.8135600256761443,1.0455789777071407,0.13358516331702042,-0.5816303854789862,-0.6758079645513959,1.9625525961399912,1.6134022752491772,-0.19192185644906878,1.7965466696975843,1.9777722085754357,0.7158164777051684,1.6444590912407486,-1.6754777137202903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9583333333333335,0.0,1.0,1.0,0.0,1.9095779040395588,-0.014387079923181037,0.022798433828705146,0.9875955008507797,-0.07523778339618535,0.03161510662017514,-0.13414502481400534,0.7794099322934281,0.08400025805915116,0.02569601872215596,-0.25254397776983545,-1.3217843507153615,-0.0890511355937329,0.18082798482815304,1.168192385398285,-1.354918517805567,0.6201898752825893,-0.04589788004923867,-0.3156370067214387,-0.18999796427119023,-0.11609437621833803,0.46201971446506257,0.24165634398584676,-1.0520100658277816,0.8000513881801984,1.0161452462881015,0.0025308506498111782,-0.4913204854221531,-0.6905323784454187,1.8959734059096836,1.7474518991120147,-0.20614919405564203,1.9061869978799024,1.858307168415202,0.6818482227782574,1.6710823349581005,-1.5697344851390493,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.966666666666667,0.0,1.0,1.0,0.0,1.9160496178243471,-0.015440673780580512,0.022620093497462596,0.987637141916279,-0.07699356370233199,0.026261875419750266,-0.13399694382835714,0.784242035174056,0.08654433112532944,0.016384735396530584,-0.23543712609726697,-1.330186383106704,-0.057729996779236264,0.1891658782969013,1.1676565823937262,-1.3586530555703176,0.6143878360102483,-0.030381801162517916,-0.300559508954863,-0.19177025932365277,-0.09975694813244115,0.4769623140563465,0.24719731131970799,-1.0379940158237817,0.7873977842571601,0.9831840447735479,-0.13360817052820995,-0.40854855106860377,-0.6992250873568828,1.8275429042246896,1.859223704554892,-0.2178266860865169,2.012586334208263,1.718893552231724,0.648177259909764,1.6880161260688276,-1.4705324040474599,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.975,0.0,1.0,1.0,0.0,1.9225569459933303,-0.016486384255171706,0.02243004425531177,0.9876711018274716,-0.0786741635811847,0.02089341828172201,-0.1337147548787038,0.7874740087286776,0.08914975877873474,0.0067609395065282366,-0.2179030898864482,-1.3291665350496038,-0.02558400956182942,0.19721438557437884,1.1659655825561481,-1.361727660323377,0.6085361238266412,-0.015438831645493846,-0.28464994497885715,-0.19362840903929884,-0.08255127064820031,0.4906679403355913,0.25245929831767616,-1.0238764637266344,0.7755425147794074,0.9467398421937279,-0.27465859993449193,-0.33250192252630484,-0.7029438630254536,1.7596315206479631,1.945532360436949,-0.22652016748276216,2.1135012159052438,1.5631654288819141,0.6149905136178174,1.695615929214811,-1.3783837482968142,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9833333333333334,0.0,1.0,1.0,0.0,1.9290879933557463,-0.01751925883429348,0.022226535703943954,0.9876973961896517,-0.08027328156830871,0.015548386301559546,-0.1332977925920874,0.7890408961114729,0.0917678661894416,-0.0031056377688599007,-0.19995680047126502,-1.3190374209703672,0.007363641109489592,0.20494487566679676,1.1630789390614846,-1.3641947542790893,0.602672104959824,-0.0010546091517185303,-0.2681339696142472,-0.19554559544836547,-0.06453192786735376,0.5030150712043784,0.2574471532133383,-1.0097337503368682,0.7644247217855465,0.9069309536455494,-0.4205675890149818,-0.26224322010505396,-0.702626495763623,1.6946154722346927,2.0032303829759956,-0.2317474465522179,2.2068989569176125,1.3944570077878826,0.5824705255481666,1.6942295812370611,-1.2937838927035927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9916666666666667,0.0,1.0,1.0,0.0,1.935630155326653,-0.018534585164011935,0.022007625052569542,0.9877168024048103,-0.08178497270734114,0.010264019391248448,-0.13274557014261626,0.7888549745659507,0.09433267969332786,-0.013127001473906018,-0.1816294606972489,-1.300169207281624,0.041070101257104294,0.21232990146847133,1.1589561227392318,-1.3660983806584612,0.5968256822305809,0.0128047595584177,-0.2512627719292572,-0.1974908664818358,-0.045769621366240104,0.5139088904653893,0.2621671404101456,-0.9956393040393501,0.7539794499010142,0.8639449917939629,-0.5714223948472563,-0.19668795184412335,-0.6990981423544529,1.6347942598270782,2.0293377226081906,-0.2329836892759013,2.2909328715548316,1.2158741987073696,0.5507960702683912,1.684208012415287,-1.2172163086373144,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0,0.0,1.0,1.0,0.0,1.9421699037881335,-0.019528004312389165,0.021771330231749927,0.9877307781276494,-0.08320380735353036,0.005075949712133176,-0.13205783246678293,0.7868099631170594,0.096759569248661,-0.02319891979997302,-0.16297869448266228,-1.272980494290892,0.07547363830954565,0.2193439588633628,1.153555232480697,-1.3674728868098247,0.5910204692539165,0.026191961845399438,-0.234311674237444,-0.19942865693629716,-0.026349713341439897,0.5232796411828345,0.26662708771781146,-0.9816636167966134,0.744137783308258,0.8180503884090501,-0.7274619552214023,-0.13459306894447298,-0.693053562363295,1.582336430417429,2.0211076686108926,-0.22965481370261387,2.3639256557266,1.03034409748755,0.5201582529997273,1.6659088108043618,-1.1491493028285937,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.008333333333333,0.0,1.0,1.0,0.0,1.9486925660391372,-0.02049559793740283,0.021515802706352723,0.987741367226708,-0.08452499021112846,1.7996467487919563e-05,-0.1312345883337648,0.7827828498708803,0.09894835976615139,-0.03320091723849827,-0.14408388448440473,-1.2379329264881556,0.11049942343848432,0.22596407460862217,1.146831756818875,-1.3683415984742024,0.5852747895245259,0.039177033398708185,-0.21757764411907568,-0.2013184467102127,-0.006370860437463435,0.5310812920901818,0.2708364446268077,-0.9678741571926107,0.7348269615205376,0.769579107238097,-0.8890687870549341,-0.07456203447656407,-0.6850704705559019,1.5392050600621177,1.9761328483991154,-0.22114986978920614,2.42436052465429,0.8406420446674723,0.49075440371855406,1.6397004184349173,-1.0900363766543086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.016666666666667,0.0,1.0,1.0,0.0,1.9551821428473206,-0.021433963976331877,0.02123948397383124,0.9877510944011545,-0.08574446533389447,-0.004877986279450751,-0.1302761199294428,0.7766402511303011,0.10078827037033976,-0.04299947084049291,-0.12504324398030497,-1.195515224355713,0.14606737001043257,0.2321702773173311,1.1387374193631148,-1.368715587384434,0.5796026280779848,0.0518453795131014,-0.20137612676412542,-0.2031144880994506,0.014056295402798269,0.5372903419272924,0.27480632777978736,-0.9543352764893648,0.7259705103640195,0.7189069936385301,-1.0567478356231774,-0.015068588917963588,-0.6756186912927764,1.5071046613242698,1.8924064868681667,-0.20683280966188822,2.4708789914255544,0.649393318171867,0.4627824455819385,1.6059603521151877,-1.0403117959652186,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.025,0.0,1.0,1.0,0.0,1.9616212025990765,-0.022340267686743975,0.020941227889333884,0.9877628565746683,-0.08685898570205258,-0.009582178874350648,-0.12918296181143066,0.7682486344441092,0.10216595078113126,-0.052453524932052284,-0.10596692717772016,-1.1462193394632967,0.182102694474494,0.237945857835931,1.129219292891822,-1.3685927416228352,0.5740144780029797,0.06429544442077935,-0.18603753600460624,-0.2047656602045775,0.03481045608629581,0.541904514059713,0.2785494853865067,-0.9411081513240243,0.717488431587784,0.6664237488510383,-1.2310831290084812,0.045493085918844045,-0.6650754096802003,1.4874565489902762,1.7683321375106498,-0.1860607097271233,2.5022882790764998,0.4590440804456031,0.4364276418663604,1.5650677018020387,-1.0003795933729176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.033333333333333,0.0,1.0,1.0,0.0,1.9679908958815948,-0.023212256354560833,0.020620367885663012,0.9877798197352765,-0.08786613036352152,-0.014066748996700868,-0.1279558417245841,0.7574889747864687,0.10297648152442646,-0.06142267145007859,-0.08696690380727301,-1.0905087324506768,0.21854886764079387,0.24327733979818172,1.1182193672129734,-1.3679573692857867,0.5685180379166481,0.07663632199627267,-0.17190392447228126,-0.20621549992823598,0.05576110005407327,0.5449410766013858,0.28208012181089337,-0.9282508147926641,0.7092975171411375,0.6124944727691811,-1.4126720521174807,0.10872952729159113,-0.6537453469384968,1.4814140517382632,1.6026646579055037,-0.15820768772801974,2.517579649431158,0.2717996059328165,0.4118427829373128,1.5173893878481315,-0.9705934367262326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.041666666666667,0.0,1.0,1.0,0.0,1.9742711375729858,-0.02404822806419936,0.020276709129474064,0.9878053298909678,-0.08876425496543561,-0.01830565781245873,-0.1265955772196813,0.7442760563639467,0.10313684619652834,-0.06977794307244116,-0.06814425659193141,-1.0287800722095002,0.25538235085211025,0.2481540990487507,1.105674758689864,-1.366780582834642,0.5631187222206714,0.08898567861641707,-0.15932645837284784,-0.2074024550000445,0.07677011691014844,0.5464345074919266,0.28541353176879525,-0.9158183281932221,0.7013118743090134,0.5574153988236374,-1.6020380899498443,0.1761397737548176,-0.6418850047413205,1.489922466687747,1.394378444974463,-0.1226937976599296,2.5159599610618946,0.08952803656024022,0.3891232321562399,1.4632605931381804,-0.9512251240137459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.05,0.0,1.0,1.0,0.0,1.9804410028429937,-0.024846948467323826,0.019910429604745598,0.9878428456828378,-0.08955236651433149,-0.02227429633593815,-0.12510292405760254,0.7285824095815009,0.10260106012414331,-0.0774148436520469,-0.04957489421208669,-0.961320579331957,0.29262833569621266,0.25256759644524235,1.091518732380476,-1.365021706389873,0.5578199545042928,0.10146836310773512,-0.14866428372270687,-0.20826039655590148,0.0976937660717715,0.5464332105440565,0.28856550901349737,-0.9038631382403611,0.6934437650742418,0.501367097608606,-1.7995250534545226,0.2489793104943372,-0.6297298042396848,1.5138179620003631,1.1424793307669074,-0.07901785584687238,2.4968998315945585,-0.08637202089367468,0.36827895117099496,1.4029605403762835,-0.9424196986411704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.058333333333334,0.0,1.0,1.0,0.0,1.9864793800353329,-0.025607513908394233,0.019521880193784476,0.987895897952054,-0.09022991938551646,-0.025948939338489515,-0.12347837464310787,0.7104666311738598,0.10137594527831148,-0.08426800933050477,-0.03129475395276837,-0.8882636558783967,0.33037662196987183,0.25651021734222745,1.075682674465622,-1.3626309276597364,0.5526232254833433,0.11421597798308979,-0.14028513619339938,-0.20871941926415905,0.11838511410339109,0.5449949738103653,0.29155151428831183,-0.892435652520284,0.6856048793316606,0.44436845813255577,-2.0051775564292784,0.3280987839657046,-0.6175227022492891,1.553946381676973,0.8458004894828514,-0.02679319001366587,2.4602023844557537,-0.2551418267084693,0.3492058943322651,1.3366849401221925,-0.9441353769513183,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.066666666666666,0.0,1.0,1.0,0.0,1.9923659166703032,-0.026329163487763332,0.019111280486225797,0.9879680784231766,-0.09079653521120312,-0.029306014944993217,-0.12172190722546965,0.6901052653128528,0.0995364353927796,-0.090326767875398,-0.013285338370108146,-0.8095452238375557,0.3687966296637,0.2599737374141183,1.058099106439988,-1.359553393323778,0.5475279094668046,0.127367469469018,-0.13456760889799269,-0.2087069497227959,0.13869713914603407,0.542180846765582,0.29438560725236845,-0.8815850559049913,0.6777081754583865,0.38623439399409487,-2.2186144435076427,0.4137598193899672,-0.6055426444329948,1.6112698978978044,0.5028440534745982,0.034214229453612965,2.4060953698477756,-0.4168715355287467,0.3316589829701122,1.2645158086950703,-0.9560675417987752,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.075,0.0,1.0,1.0,0.0,1.9980822805095726,-0.02701104568915978,0.018678312863104382,0.9880630559096943,-0.09125165274475215,-0.03232119691837947,-0.11983269022938406,0.6678260033303295,0.0972390741878445,-0.09565070480382376,0.004539932363982174,-0.7248626335131476,0.4081500896628773,0.26294745724212903,1.038705767073828,-1.3557349306699036,0.5425308480761267,0.14107047628138653,-0.13190440196882275,-0.20814918210659883,0.158486703600854,0.5380471148848862,0.29707916400448037,-0.8713603890420328,0.669670420301681,0.32654022828200624,-2.438905755793379,0.5054303354865164,-0.5941307510548843,1.6869192818104384,0.11174326294303705,0.10404520397930994,2.335344626235828,-0.5727439959236724,0.3152286473349142,1.1863883526266528,-0.9775597435718852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.083333333333333,0.0,1.0,1.0,0.0,2.0036137260151246,-0.027651947067859367,0.018221622568738015,0.9881846140763829,-0.09159411516789726,-0.034968333495733306,-0.11780875273913148,0.6457913434601921,0.09531304894751721,-0.10019140066142204,0.02487591148042928,-0.6489632363070217,0.44849552602487475,0.2654160745521517,1.017450677176765,-1.3511295543990027,0.5376257302825566,0.1554827908325253,-0.1327052211822754,-0.2069728629898074,0.17761954958329787,0.5326351135001874,0.2996394180412837,-0.861811916694547,0.6614155130655217,0.2573682104420416,-2.660908846846468,0.625551171203802,-0.592162596043011,1.7634936189871742,-0.2600523695266982,0.1738791000924722,2.2604268830606795,-0.7025440819653639,0.2970103489634368,1.0952393642668268,-0.9671174792900095,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.091666666666667,0.0,1.0,1.0,0.0,2.0089797957530537,-0.02824637107112296,0.017742211144113184,0.988333579689924,-0.09181558167512621,-0.037347124347383825,-0.1156366141066195,0.6271782274147167,0.09459966569965705,-0.10409853382159903,0.05056774761667669,-0.6034080846820528,0.4893913456846504,0.26723692741616306,0.9943572862930535,-1.3453090778165069,0.5326614714754099,0.17046203659783943,-0.13623860812760105,-0.20525119710505763,0.19616048498519867,0.5263380468521301,0.3020293364872043,-0.8531063996375857,0.6535517956468475,0.1696334055465576,-2.873397680016374,0.8027905860110884,-0.6100995660823716,1.8110457682874954,-0.5055116874069582,0.23153040546646575,2.2004983561398843,-0.7772179754846764,0.27469155391137257,0.9802607660860296,-0.862661836485834,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1,0.0,1.0,1.0,0.0,2.014220423945187,-0.02879150011450063,0.017241842153309064,0.9885070002983684,-0.09191204333359317,-0.03961203071854772,-0.11330036925725263,0.6123018615502717,0.09463680202024904,-0.10787477936101066,0.07917224999576912,-0.5827660275953361,0.5303508757813684,0.2682432979779277,0.9695607158431588,-1.337749711298818,0.5274574041811837,0.18566688697065023,-0.14113041597239137,-0.20311402289869965,0.21429452218562928,0.5196814805754428,0.30421761060647323,-0.8454742372597799,0.6470378157907578,0.06901731554814772,-3.0690900797313025,1.0218063718754733,-0.6415217038579901,1.8299926871227996,-0.6353274570581424,0.28048362859948384,2.1564349804329286,-0.8090860706830849,0.25141001152672593,0.8426718189674176,-0.6727378022038377,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.108333333333333,0.0,1.0,1.0,0.0,2.019358943115347,-0.029290655724949623,0.01671960112373192,0.9887023135834458,-0.09188919665841688,-0.041815916814007634,-0.11079503487673313,0.5997794922214944,0.09482875519255735,-0.11174923328435071,0.10795418240066829,-0.5709531933492493,0.5711769005058087,0.2683872160086322,0.9432057849641985,-1.3282789716185823,0.5219694430777767,0.20096191471655275,-0.1468273990785701,-0.2005764699617329,0.23210106799241415,0.5128532790074121,0.3062195033459831,-0.8390618693214621,0.6423394989434502,-0.036139567986520627,-3.2480486728976876,1.254891450139688,-0.6765149732633513,1.8387834007578652,-0.7195370870990941,0.32892949615182077,2.119935659380376,-0.826589642912372,0.2297047988570644,0.6897853555564182,-0.4384594984238954,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.116666666666666,0.0,1.0,1.0,0.0,2.024410857286356,-0.029745429550175975,0.01617489736354502,0.9889177063277775,-0.09174922882256532,-0.043978204678921384,-0.10811922417044632,0.5889523884685404,0.09520665159264177,-0.11569256375876988,0.13695684973907,-0.5623759864896729,0.6118049362107167,0.267640971844819,0.915426571294864,-1.3168348537964898,0.5161821546267945,0.21631327698328132,-0.15312270075737627,-0.19763186462950263,0.2496267831753022,0.5059049865269033,0.30804602392075764,-0.8339778146671729,0.6397301574836929,-0.14432352889504507,-3.4111857370740117,1.4926534578393147,-0.7129573360902297,1.8460716854399357,-0.7872351187155835,0.3784464008377514,2.0883440840091083,-0.841225239953739,0.20900988887978866,0.5248898038861682,-0.17608792261985196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.125,0.0,1.0,1.0,0.0,2.0293889449420637,-0.030155762977859636,0.015607003841012887,0.9891517352692368,-0.09149187698217627,-0.04610575380104401,-0.10527269601709925,0.5796090121127847,0.09585971422972739,-0.11972275467628718,0.16636185328078096,-0.5548911354591878,0.6522315461437931,0.26598182386038144,0.8863526893462983,-1.303401413987927,0.5100868208096062,0.23172977614055168,-0.15994798439049648,-0.19426902994777037,0.2669068027258993,0.4988328583415164,0.30970300149397956,-0.8303137059233593,0.6394047002331193,-0.25504363391087637,-3.5588446199961576,1.7310093381113667,-0.7503353517096523,1.8554761289433093,-0.8499437163651385,0.42935277888230594,2.0608759748273258,-0.8579168474396015,0.18887423118531976,0.3496481710358923,0.10743708740150737,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.133333333333333,0.0,1.0,1.0,0.0,2.0343055969491144,-0.03052079447402516,0.015014940445066462,0.9894030643794958,-0.09111572175433297,-0.04820047089798503,-0.10225564068061747,0.5717531115899084,0.09684338846003669,-0.123885026228997,0.19626764194906574,-0.5476390400073938,0.6924453875966287,0.26339024461297106,0.8561124942949281,-1.2879846981613003,0.5036765654316336,0.24723787913233647,-0.16728842936346192,-0.1904759849814642,0.283974716089091,0.49160637240290994,0.3111939277738463,-0.828150345149908,0.6415207756070513,-0.36790443113511095,-3.691120409435249,1.9678798299036693,-0.7884920075575519,1.8684852574982014,-0.9119903581850014,0.481686345857803,2.0376371361635472,-0.8793096018994206,0.16912452351161011,0.1652992968027167,0.40847362575006096,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.141666666666667,0.0,1.0,1.0,0.0,2.039173837897297,-0.030839368767179128,0.014397486840202062,0.9896703325087116,-0.09061885065627494,-0.05026219040813518,-0.09906850697044765,0.5654814037577193,0.09818318778591385,-0.12823491364506517,0.22671328213532754,-0.5402496412383604,0.7324146385410353,0.2598500833414629,0.8248340158557108,-1.270603416822866,0.4969452873503137,0.26287119709885504,-0.17514782369357984,-0.18624092418347366,0.3008674216619584,0.4841776983098594,0.3125217435525064,-0.827558717643314,0.6462125939956204,-0.4824847527842835,-3.808067708664069,2.2019631025139974,-0.8273420397103071,1.885673748638902,-0.9747234348660849,0.5354070763118085,2.0191596724106677,-0.9073055389992679,0.14975151052344815,-0.026942821625675073,0.7244167803691504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.15,0.0,1.0,1.0,0.0,2.044007707684356,-0.03111027462085344,0.013753221268205641,0.9899520924124757,-0.08999915699571909,-0.05228978091660261,-0.0957119913075852,0.5609201102185191,0.09988305156164642,-0.1328300601958355,0.25770636724778606,-0.5325410575356082,0.7720889429544849,0.25534883206656633,0.7926446991505269,-1.2512853131194004,0.48988753143646185,0.27866577494298483,-0.18353381994456333,-0.18155253370960073,0.31762737729593543,0.4764846134195888,0.31368978628257044,-0.8285993921770026,0.6535943886132038,-0.5983356788931993,-3.9098134224108905,2.4322677978007468,-0.8667997831566865,1.907181797541141,-1.0382037933869332,0.5904521126010404,2.006158415487107,-0.9435769213214651,0.13083745781762857,-0.22576998220704247,1.0528452159405877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.158333333333333,0.0,1.0,1.0,0.0,2.0488222904053366,-0.03133234899264727,0.013080564519127166,0.9902467840124523,-0.08925447740063443,-0.054281570428356817,-0.0921870713761796,0.5581883614737853,0.10192818715502025,-0.13772527747772495,0.289236552480022,-0.5244035239310181,0.8114032029971885,0.24987782202657627,0.7596704588155293,-1.2300656201928535,0.48249862429770224,0.2946575603912074,-0.19245122025002873,-0.17640005564012298,0.3343033952534102,0.468451416287835,0.31470236784946687,-0.831321550680098,0.6637600142612968,-0.7149864374020148,-3.996624894826537,2.657951649209682,-0.9067574709277315,1.9328891867913012,-1.1018783313716147,0.6467603697664093,1.9993879227100975,-0.9897069951694626,0.11252716233241755,-0.42976616412436996,1.3912156005098253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.166666666666667,0.0,1.0,1.0,0.0,2.0536335143974904,-0.03150452615800133,0.012377829068946177,0.9905527234145224,-0.08838266860762996,-0.05623550758780716,-0.08849504908387565,0.5508819585308786,0.10280899177365624,-0.1382872187422023,0.3215482036004413,-0.5074297363273648,0.8436885952253341,0.24343239144319942,0.7260342842367513,-1.2069861189659057,0.47477490692099966,0.31088059472283985,-0.2018984588007569,-0.1707731942134939,0.3509505093411037,0.4599894968334311,0.31556523898811073,-0.8357621615790755,0.6767813152883676,-0.8237284576788789,-4.096186246691178,2.896562043098103,-0.9430454070298655,1.9289915495810295,-1.1366757942731598,0.7288796432386124,1.6374319340533405,-0.5980763252165244,0.004661526795495252,-0.5354262045557157,2.4839633838081077,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.175,0.0,1.0,1.0,1.0,2.05833993675365,-0.03161736246725763,0.011709898926592553,0.9908676751779354,-0.08737037392149109,-0.05808547947495967,-0.0846979641014502,0.5638732449259269,0.10850411379652922,-0.14745115340568346,0.3574845945493861,-0.5153918288118775,0.8754187402205551,0.23614901439859495,0.691400688037343,-1.1817895861412184,0.4667812008472045,0.3268074195508912,-0.21139581682124806,-0.1642520615861461,0.3615939274876325,0.45848347753422625,0.3147800599627251,-0.8402453207560266,0.705159403991432,-0.9460688550060958,-4.110759578354382,3.117662915186261,-0.9894215195142642,1.982336193759816,-1.1652259161114564,0.791075193372966,1.1171836580524563,0.14921789701596078,-0.10133920185090295,-0.5485871755171012,3.527442847974769,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.183333333333334,0.0,1.0,1.0,1.0,2.0634015570918733,-0.031681405057529435,0.010899971903341736,0.9911802867304591,-0.08621793940260454,-0.06010573045283165,-0.08071807287880653,0.5987653530203603,0.11884325792179269,-0.16797695583203814,0.3944511362296714,-0.5504393652028241,0.9097865073395199,0.22766457719309782,0.6575216245975116,-1.155025070379468,0.4582845482624286,0.34391953128550345,-0.22131889073594785,-0.1575886076572778,0.36957023697531133,0.4624764617836971,0.3138762522905957,-0.8449052811710271,0.7355720294212804,-1.080805814554614,-4.030246869605101,3.3045786820728162,-1.0434520295671224,2.1033180258867703,-1.1977358065626142,0.8103910889773852,0.7963948834795942,0.7837205555589533,-0.11270936450224589,-0.5488922716493061,3.712920159700499,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.191666666666666,0.0,1.0,1.0,1.0,2.068749293414697,-0.03169096127161934,0.00998077878661887,0.991486398972075,-0.0849379692245922,-0.062243273052562886,-0.07659005808491637,0.6263201290614862,0.12697393743170576,-0.18505809194153086,0.42831252415828897,-0.5738753634491613,0.93883703259037,0.21813558415601805,0.624229906877258,-1.1267132747733382,0.44939033368775244,0.3618627199823374,-0.2313580802639583,-0.15074554343652302,0.37486717554562576,0.47154548679354213,0.31290157055435436,-0.8493935252835151,0.7670414066531069,-1.1996859466681642,-3.969311624269085,3.488706553177181,-1.0872022677708026,2.1882737245019137,-1.2027659620598448,0.8350009265107161,0.47395238155490405,1.37152135737171,-0.11951383542253113,-0.5175040880003445,3.805335527722027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2,0.0,1.0,1.0,1.0,2.0743212122943793,-0.03164443910772951,0.008972038939680817,0.991784171254638,-0.08353219799905306,-0.06445573720094536,-0.07233247879295697,0.6474467265420851,0.13310447588021027,-0.19974466151362133,0.46079391072694265,-0.587600643057734,0.9650805548378172,0.20766981141529509,0.5913664308596935,-1.0968799611598483,0.44016451046624855,0.380390760027202,-0.24136499010361193,-0.14367192554876587,0.37746944333455973,0.4853351510732256,0.3118843550335535,-0.8535303493043662,0.7989942882166475,-1.3068570840895983,-3.926288962016302,3.6696115084811742,-1.1239221308460445,2.247666555623732,-1.1950055624359386,0.8659907029621133,0.1523940760553577,1.9143718505653018,-0.12298867877361341,-0.4680510556487971,3.837245254367805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.208333333333333,0.0,1.0,1.0,1.0,2.080065075129229,-0.03154139240580133,0.007888958536680393,0.9920725256487052,-0.08200217492694807,-0.0667052471369664,-0.06795702439633759,0.6632689492955024,0.13753441332350164,-0.21239040995029274,0.4920940620623772,-0.5923595473293787,0.989596337425231,0.19635463275452475,0.5587917575103196,-1.0655530829653186,0.4306582981736517,0.3993238292427329,-0.2512748396378906,-0.13631236505382113,0.37740707681321506,0.5034516843029638,0.3108517592414608,-0.857194376210995,0.8309954942259037,-1.4042748562102787,-3.8989154569400575,3.8470299773038885,-1.155047130602087,2.288185001865172,-1.1826479146215425,0.9034088780388122,-0.16295932643209166,2.406427775810639,-0.12346585154789702,-0.40597187352274133,3.8219189844113344,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.216666666666667,0.0,1.0,0.0,1.0,2.085938426803442,-0.03138185141376949,0.006745429078946795,0.9923509331097291,-0.08034967017014465,-0.0689549400393279,-0.06347261066052932,0.6749640952161666,0.14054154258241108,-0.22312130536637292,0.5222760569327318,-0.5882934715240349,1.012828228144923,0.1842652304784571,0.5263845065773592,-1.0327627948714502,0.42091372495621376,0.4185271767249549,-0.26107578868063763,-0.12861511091478567,0.37475345456069153,0.5254422806700696,0.30982659084108854,-0.8602965471964119,0.8626929379568364,-1.49320180754977,-3.8849008385053097,4.020409431468166,-1.1815316550801802,2.3147317504487233,-1.1711909664167774,0.9465391912225046,-0.4674857404815458,2.8412693037413472,-0.12152948963635946,-0.3344624299812238,3.7679931656979737,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.225,0.0,1.0,0.0,1.0,2.09190888020699,-0.03116620289026478,0.005554897774024884,0.9926193441228235,-0.07857668591500208,-0.07116784658817002,-0.05888700803952133,0.6837337406896415,0.14236818286882724,-0.23202426860063682,0.5513698956140077,-0.5753584990622405,1.0349617312557036,0.17146793596202858,0.4940434102018978,-0.9985462591075158,0.41096610392231536,0.4379026917502116,-0.2707946890781702,-0.12053671186677939,0.3696156478051893,0.550806172698653,0.3088262677475215,-0.8627687500440154,0.8937953803208699,-1.5746032674836041,-3.8817180943614127,4.188572382699996,-1.2040907040128879,2.3313677355036813,-1.1646515265708157,0.9942258237563426,-0.7578702733789311,3.214424135049141,-0.11781616612412171,-0.25562484730719426,3.6820050157523476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.233333333333333,0.0,1.0,0.0,1.0,2.0979540257361813,-0.0308952005187811,0.004330511299765406,0.9928781495796686,-0.07668549451086547,-0.07330665232932641,-0.05420746944084368,0.6907444691695553,0.14321007710865769,-0.23919921125939983,0.5793843927964244,-0.5534842534463402,1.056076585813132,0.1580218426870637,0.46168920500466903,-0.9629532551597836,0.40084554655599897,0.4573833056500162,-0.2804866474568179,-0.11204468051884663,0.36212228333770935,0.5790160162542219,0.3078629880723532,-0.8645569613181985,0.9240596882193756,-1.6492820142909665,-3.886688319641769,4.349713125727903,-1.2232710671669544,2.3414885987195855,-1.1658456466550093,1.0450579034017273,-1.0322257670403356,3.52402394792221,-0.11290348496790781,-0.17085493601285862,3.569144785567948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.241666666666666,0.0,1.0,0.0,1.0,2.104060848876166,-0.03057002708949878,0.003085049302427804,0.9931281375811029,-0.07467872699292825,-0.07533378824457329,-0.04944097923946862,0.6970427708373146,0.14320542284859128,-0.24475944566534819,0.6063082518241036,-0.5226373865468387,1.0762091734538743,0.14397990239051248,0.42926527154120164,-0.9260510403453841,0.3905782528028661,0.4769275017288714,-0.2902254498557537,-0.10311908014341727,0.3524118850211837,0.6095399051640231,0.30694454299805635,-0.8656163323108964,0.9532811267470024,-1.717925630992062,-3.8972024173131214,4.5015703332567325,-1.2394753170190742,2.3477519929798576,-1.1764453019617416,1.0974817282117675,-1.2900409873942398,3.7707381828150055,-0.10725563490233125,-0.08105183962297202,3.433460079893631,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.25,0.0,1.0,0.0,1.0,2.110224263922697,-0.030192351820414343,0.0018308594048700405,0.9933704384825793,-0.07255946345012076,-0.07721167391963656,-0.04459432277002642,0.703489707456072,0.14243007374329755,-0.24881681854989152,0.6321060121658355,-0.48284083852813553,1.095375199377445,0.129389748837196,0.3967358313827837,-0.887927082938838,0.38018762460568106,0.49651250553301385,-0.30009406915618025,-0.09375331838198384,0.340621600214472,0.641861652634472,0.30607539415731433,-0.8659078253119147,0.9812840228842694,-1.7811209159013686,-3.9109122985049294,4.641627397689989,-1.252968764846235,2.3520166054208493,-1.1970709303063432,1.1498707549587597,-1.5319663952226403,3.957304373202166,-0.10120259864406345,0.01322222858898936,3.2779438031783026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.258333333333333,0.0,1.0,0.0,1.0,2.116445462695161,-0.029764411914434713,0.0005798174061388713,0.9936064541320478,-0.07033136684516046,-0.07890295105692453,-0.039674140940588874,0.7107501579929885,0.14090190103187286,-0.25146800109853085,0.6567145680939791,-0.43417172014415095,1.1135699022794134,0.11429455379215633,0.3640833998994528,-0.8486905837172176,0.36969544005542887,0.5161277784858855,-0.3101766320275261,-0.08395456756077127,0.32687911176747303,0.6754949780507259,0.3052578330206553,-0.8653959618344133,1.0079135234666408,-1.8393596954643194,-3.9257718647349082,4.767233252793921,-1.2638849736053814,2.355393934624941,-1.227454557855947,1.2005510775079833,-1.7594134486739,4.087780804022521,-0.09494974078758434,0.11162634594686249,3.1046701843080537,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.266666666666667,0.0,1.0,0.0,1.0,2.1227302904536,-0.029289082667232093,-0.0006566397442579461,0.9938377762690138,-0.06799878933570803,-0.08037070802727636,-0.034687006223884626,0.7192549620007102,0.13858889315624648,-0.25277253695103247,0.6800504746315967,-0.37675810756885064,1.1307775561015077,0.09873375391279068,0.33130630030386854,-0.8084731953922727,0.35912287504559137,0.5357690711100962,-0.32055164512044604,-0.07374413375685078,0.3112980427365737,0.709991332701514,0.30449289847752126,-0.8640473862128003,1.0330285259560703,-1.8930702756838544,-3.940135568814264,4.875761128521665,-1.27225739814664,2.3582586234103875,-1.266617593946524,1.2478418293799827,-1.9743505157556562,4.167051588531354,-0.08860723555416672,0.21390300842690335,2.914860654223075,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.275,0.0,1.0,0.0,1.0,2.129086969860234,-0.028769890590653,-0.0018674113701511526,0.9940661012014497,-0.06556683973916343,-0.0815786850977339,-0.029639401251477144,0.7292181263994437,0.13542179689073197,-0.2527420142650645,0.702011772365825,-0.3107683213188722,1.1469681171103245,0.08274338253075876,0.2984144737525484,-0.7674278982418565,0.3484911500863182,0.5554320888760587,-0.33128692525996817,-0.06315720373777156,0.2939732698382121,0.7449458378595818,0.3037810457614192,-0.8618309116939649,1.0564945343703587,-1.9426320483053745,-3.9527233871290925,4.964676574786475,-1.2780387492654488,2.36036723765771,-1.31308141823411,1.2900742841443964,-2.1789976220785037,4.20027017113247,-0.0822253153165986,0.31979080101425694,2.709026695709831,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.283333333333333,0.0,1.0,0.0,1.0,2.1355247785507254,-0.028211061954267484,-0.003041596600795541,0.9942931338298395,-0.06304145932511239,-0.0824914127756813,-0.024537832898196933,0.7406849484958764,0.13130943141768603,-0.25133695848889415,0.7224836799498885,-0.23640217471542715,1.1620887615832332,0.06635655310770111,0.26542757718505033,-0.7257285858124981,0.33782222922450056,0.575108525071058,-0.34243633542434787,-0.052242895687777506,0.27498141570193196,0.7799958355537219,0.30312247655557795,-0.8587175395292294,1.0781789708845675,-1.988390359076106,-3.9624873056206473,5.031518664334314,-1.2811236508058166,2.361024365917317,-1.3650572765944602,1.325594935680457,-2.3755006155540292,4.192351399918928,-0.07583943906638968,0.4289802045244806,2.487150348633529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.291666666666667,0.0,1.0,0.0,1.0,2.142052596944554,-0.027617504298421625,-0.00416831088796056,0.9945204913794373,-0.060429426334390475,-0.08307435054556223,-0.0193888870446085,0.7535416236020903,0.12615281255856678,-0.24845980939675097,0.7413498471584419,-0.15388872109060173,1.1760685390457468,0.04960354321282366,0.23237301865887097,-0.6835692538362846,0.3271390892395546,0.5947824949746806,-0.35403787986987584,-0.04106395480976394,0.2543815929123116,0.8148183611915639,0.3025170551103127,-0.8546812416185569,1.0979470401809175,-2.0306857832656173,-3.9685783714759166,5.073930106056495,-1.281384916127647,2.3591712428532308,-1.420604374184825,1.3528017704380377,-2.565836879586469,4.147792167667806,-0.06951383419955492,0.5410536951880562,2.2487819564891254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3,0.0,1.0,0.0,1.0,2.148677757603574,-0.026994771930135962,-0.005236476862518667,0.9947496032592481,-0.0577383352277018,-0.08329400505120466,-0.014199302213914133,0.7675439426166563,0.11985789068751017,-0.24395464477084788,0.7584993727535818,-0.06348346318981857,1.188816460730582,0.032511790053274155,0.1992846043271184,-0.6411630840448899,0.31646581395570644,0.6144280457852785,-0.36611307499409496,-0.029696199513810213,0.23221746770882415,0.849125705014852,0.30196391265225203,-0.8496999779427618,1.1156586701593862,-2.0698678005560294,-3.970289059878729,5.0896767809161485,-1.278697884999046,2.3534977569469473,-1.477766890713187,1.3701794837663195,-2.7517009409534814,4.070510119602804,-0.06337859633796294,0.6554614844633311,1.993152663327633,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.308333333333334,0.0,1.0,0.0,1.0,2.1554050882619573,-0.026349002713192963,-0.006234591239073676,0.9949816087192972,-0.05497653644623503,-0.08311804518945735,-0.008976041153396706,0.7823350481718644,0.11234726545373705,-0.23760765104739917,0.7738354615630143,0.03453199692444645,1.2002233371601814,0.015105746536889841,0.16620153432755883,-0.5987413074876822,0.3058274578229038,0.6340074575904631,-0.37866732804842895,-0.018227630080325286,0.2085199105630869,0.8826601965182773,0.30146074517134663,-0.843756883544168,1.131166251236378,-2.1063112862614144,-3.9670359361341614,5.0766970321789495,-1.272967586572361,2.342527224330855,-1.5346890044667916,1.376345796090511,-2.934462525273671,3.9637902877709275,-0.05766276275360527,0.7715052055654104,1.7192569839878535,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.316666666666666,0.0,1.0,0.0,1.0,2.1622360747145954,-0.025686827297262266,-0.007150473272361091,0.9952172531611262,-0.05215304167587489,-0.0825154142330795,-0.0037263478809027523,0.797455236809332,0.10357060307708646,-0.2291491600669043,0.7872830351813174,0.13985097056920126,1.2101668338718001,-0.0025933980510827515,0.13316733872488237,-0.5565514668419074,0.29524968751283376,0.6534701661907928,-0.3916912250685415,-0.006757102912301698,0.18330975895426296,0.9151888764777008,0.3010028666063586,-0.8368415578500049,1.1443129532258505,-2.140433176906413,-3.9583913419306316,5.033200944083678,-1.2641546207624743,2.324685215089932,-1.5897239420253317,1.370106929382436,-3.1151710001328103,3.8302920214020575,-0.052719082207992596,0.8883298022664188,1.4259116074448475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.325,0.0,1.0,0.0,1.0,2.1691680886388918,-0.025015254711772014,-0.00797100156174885,0.99545678415011,-0.04927740149163458,-0.08145643093961293,0.0015422226100339517,0.8123465162097682,0.09351390989546171,-0.2182580634104367,0.7987947411299063,0.25214559248123314,1.218519935118414,-0.020568139744883703,0.10022834529538163,-0.5148546250862875,0.28475821414352925,0.6727522111752953,-0.4051627270821845,0.004607485409381976,0.15660039389420674,0.9464983968749783,0.3005820938012134,-0.8289513868397277,1.1549314446937922,-2.1727106589363894,-3.9441611466337765,4.9578230817739515,-1.2522989706114696,2.2983619578952763,-1.6415480008313288,1.3505167772340108,-3.2945858073260696,3.672081152275408,-0.04903840969098905,1.0049253809185488,1.1117955382175992,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.333333333333333,0.0,1.0,0.0,1.0,2.17619365538595,-0.024341540551448985,-0.008681850587500595,0.9956998483756748,-0.04635956509734507,-0.07991286201162184,0.006821814570195131,0.8263991857049382,0.08207145307557398,-0.20287880969027317,0.808584543858026,0.37889019127172757,1.2257534462500779,-0.038805242366689245,0.06743131961431943,-0.47392108214567485,0.2743780380026426,0.6917761988223807,-0.4190503584157303,0.01575151004159848,0.12839999549882847,0.9763902290156242,0.30018555977817546,-0.8200928015013624,1.1628428788628105,-2.2046071344640974,-3.928133628916997,4.839923777988488,-1.2378318754795448,2.2605020526887,-1.7000411987518527,1.317657253837426,-3.4787360841583426,3.4743595303461916,-0.04953545270949933,1.1245663042107346,0.7538237541236636,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.341666666666667,0.0,1.0,0.0,1.0,2.1832960003074326,-0.023672719011919727,-0.00923921379588943,0.9959504820225592,-0.043408999223071634,-0.07779284950017257,0.012106556588268588,0.8385782982205991,0.06918957521323522,-0.1813686833577594,0.8166236829199668,0.5253133116932778,1.2324348552763116,-0.05731159198595199,0.034759451480098354,-0.4341892287864794,0.26412768288553684,0.7104272453867736,-0.433496747061382,0.026568439640005742,0.09862145915823436,1.0044043890474148,0.29975650292272177,-0.8102086151028821,1.1674951739291866,-2.2379186212254414,-3.913686882279938,4.6713934359889135,-1.2211668747065951,2.2086492275285474,-1.7735568270148983,1.271389575805541,-3.672849332696456,3.2279246781836535,-0.05644655091162187,1.2479328783495713,0.3351549629723305,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.35,0.0,1.0,0.0,1.0,2.1904482604056668,-0.023017309905586394,-0.009607547773709459,0.996209653261925,-0.04043726186437546,-0.07502456181903387,0.017391656759529073,0.8475416879646701,0.05518164673076116,-0.15604201498686307,0.8224191621620365,0.6783527603812189,1.237727313501936,-0.07610388605377993,0.002203204909653801,-0.39606452487919297,0.2540252567575327,0.7285870192811899,-0.4486096388659786,0.036941336305024164,0.06718583995388754,1.0301889736520184,0.29924478392964843,-0.7992939201955362,1.1684287949123493,-2.272531603435526,-3.8968623523317296,4.469175381317613,-1.202163833602517,2.1438108371552356,-1.8460220418050577,1.2102070518765153,-3.8689590825710236,2.96101402639406,-0.06675210812429944,1.3652012302185645,-0.11065845920195105,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.358333333333333,0.0,1.0,0.0,1.0,2.1976202549754205,-0.02238415049922993,-0.009786983829785087,0.9964702507030659,-0.03745694091124534,-0.07162489183373012,0.022669184181939167,0.852549098214172,0.04051603717681113,-0.12929613063106005,0.8258305889300435,0.8245904186528294,1.2403308324658686,-0.09518711870987742,-0.03018825439209714,-0.3597029724311859,0.24409161899216156,0.7461574260060275,-0.4642637810914663,0.046738557171280996,0.03413880778205065,1.0537546228206491,0.2986439677873168,-0.787455261265906,1.1656508662758207,-2.3075215820667636,-3.8742590395921694,4.25503303998877,-1.1809319995470613,2.0670068041140177,-1.899346757349638,1.133534669349503,-4.056227097964679,2.69874904361449,-0.07773532545182316,1.468973289351232,-0.5495028763664012,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.366666666666666,0.0,1.0,0.0,1.0,2.2047813985069453,-0.021780310553714544,-0.009782784687785772,0.9967230616682935,-0.03447886306254475,-0.06763393680321017,0.027928425185959223,0.8534846959404276,0.025570399542523048,-0.10154008648446104,0.8270939815495031,0.9604559462218705,1.239589865804851,-0.114562579088226,-0.06236777908354903,-0.3251473075460468,0.23434305676508166,0.7630371326830901,-0.48026541815513923,0.05583358079418255,-0.0004179450121904394,1.0751681243789266,0.29794919517211804,-0.7748110320396824,1.159270413639576,-2.342555750321228,-3.8463823957388357,4.039064201398433,-1.1579764556295042,1.9784729137043988,-1.9292908815836707,1.042773272011709,-4.2292104596311715,2.4439865623366153,-0.08956062251754937,1.559129936838357,-0.9740169876421589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.375,0.0,1.0,0.0,1.0,2.21190236002435,-0.021211290772345723,-0.009600263408086515,0.9969584581202785,-0.031512208857931705,-0.06309856852975135,0.03315696194341803,0.8504116289257344,0.010658736332441833,-0.07293129392764114,0.8264473347791575,1.084906198957614,1.2352449110275434,-0.13422971454856455,-0.09429462765441107,-0.292385235741212,0.2247920113983365,0.7791319745677675,-0.49641862911786083,0.06411811170480948,-0.036348033211802216,1.094487732192926,0.2971512907453576,-0.7614697623186001,1.149417249815118,-2.3775180565444383,-3.813844530788692,3.8262328942062287,-1.1337361606466334,1.8795105841683513,-1.9371383255176133,0.9405108133123228,-4.3845069124169616,2.195255367347966,-0.10266970743569637,1.6370404282034912,-1.382722472992306,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.383333333333333,0.0,1.0,0.0,1.0,2.2189553303223275,-0.02068128874067483,-0.009244518562780808,0.9971670315074275,-0.028564791729316155,-0.058067759096953456,0.03834187400668592,0.8434491215846934,-0.003943035808800663,-0.043666007941000604,0.8241181407069256,1.197600065514278,1.2273037181876276,-0.1541878800306333,-0.1259318545966939,-0.26137675930927634,0.21544745408763777,0.794362309085896,-0.5125510569137661,0.07150876101605459,-0.0734930602191398,1.111755713834726,0.2962380333815231,-0.7475270249029575,1.1362250390897042,-2.412453711327714,-3.776926127573546,3.619164433582375,-1.1086311822263646,1.7720147402122888,-1.9260340986467206,0.8298193875101987,-4.519848509122927,1.9507975420125367,-0.11731887885024883,1.7043176089993728,-1.7752848832962975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.391666666666667,0.0,1.0,0.0,1.0,2.2259143951430125,-0.02019336526180956,-0.008720742288223457,0.9973399103865433,-0.025643126200590526,-0.052591347485211055,0.04347048883784087,0.8327721569789147,-0.017989271068556384,-0.01400509241695408,0.8203391665953085,1.298373588777152,1.2159269064075102,-0.17443727640402645,-0.1572433964473035,-0.2320658285148391,0.20631482502789708,0.8086655535713057,-0.5285191974286395,0.07794843482997946,-0.11167884169718433,1.1270010245598017,0.2951959760978535,-0.7330644688352772,1.1198291684268464,-2.4474847492222045,-3.7355426124187634,3.4193397264103966,-1.0830917317293998,1.6580480668329511,-1.899338550355647,0.7137636667104356,-4.633589518372641,1.7093023991899337,-0.1335610520237851,1.7626514952833938,-2.1514324256212936,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4,0.0,1.0,0.0,1.0,2.232755828353954,-0.019749527956390837,-0.00803457191125894,0.9974689708846475,-0.022752439486403157,-0.046719756764787956,0.048530845343843734,0.8186050221715884,-0.03126073311895062,0.01573666005265356,0.815350937716519,1.387094645400495,1.2013635814299222,-0.19497929251767004,-0.18819089813700662,-0.20438776386910307,0.1973959252254811,0.8219964435331119,-0.5442066994196936,0.08340482212789518,-0.15071955219201716,1.1402440871545583,0.29401201584779335,-0.7181494999815676,1.100367831996016,-2.482749881919989,-3.6892181512455395,3.227413689939622,-1.0575606972104512,1.5396445312047047,-1.860067192828403,0.5951246513542413,-4.7245360462721555,1.470043270891801,-0.15128847809350643,1.8137412105779083,-2.510728347711426,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.408333333333333,0.0,1.0,0.0,1.0,2.239458295500507,-0.019350761485351753,-0.007192392291490109,0.9975470021305601,-0.019896639039001133,-0.040503979355679294,0.05351196086214011,0.801212531611921,-0.04356213119914262,0.04520623745992408,0.8094043374887021,1.463623896458912,1.1839114822501728,-0.21581644110269294,-0.21873036563472917,-0.17827560034917872,0.1886888134077229,0.8343262957580507,-0.5595203173091129,0.08786717901921681,-0.19042110913505358,1.1515017457413317,0.2926745014629617,-0.7028354486589787,1.0779836959649893,-2.518363671151804,-3.6370708421219526,3.0432830761225556,-1.0324930665221161,1.41872297585516,-1.8107187600608565,0.47624690986152074,-4.791894385905689,1.2328764777776868,-0.17028786707319665,1.8592291760761248,-2.8525354566251515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.416666666666667,0.0,1.0,0.0,1.0,2.2460029323749398,-0.01899702265364532,-0.006201581112397926,0.9975678458041644,-0.017078254118765995,-0.03399561857101159,0.05840397398881968,0.7808869403374891,-0.05471959970226488,0.07402744473813502,0.80276133428136,1.527810022054187,1.1638941829272333,-0.2369520203702001,-0.24880874550570584,-0.15366637926706048,0.1801877074501125,0.8456418264640312,-0.5743853454207078,0.0913422706255872,-0.23058445862377863,1.160792028450853,0.29117388472990674,-0.6871623470469655,1.0528255743855968,-2.554389700204265,-3.57781299471085,2.8660774382191727,-1.0083556631244157,1.2970496122503383,-1.753263050867595,0.3589748637350501,-4.835280002537451,0.9982115587301177,-0.1902909847631673,1.9006220826033537,-3.176018302962449,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.425,0.0,1.0,0.0,1.0,2.252373273746238,-0.018687216018139198,-0.005070700727971956,0.9975265148038438,-0.014298370335909008,-0.02724690714675359,0.06319821934758442,0.7579320133865914,-0.0645779998673279,0.10181389713946074,0.7956931004032503,1.5794990326759217,1.1416507863257759,-0.258389602772764,-0.27836058221324333,-0.13050764304552584,0.17188288568898263,0.8559437892955564,-0.5887413681569061,0.09385009341480098,-0.27100910917734444,1.1681386050535003,0.28950298505024225,-0.6711584139489228,1.0250500575822818,-2.590825317693983,-3.509767552643239,2.694131507264598,-0.9856268572942256,1.176226122115942,-1.6892057112481895,0.24465203517430478,-4.854755296229778,0.7669662738493299,-0.21101522965707553,1.9392042434500123,-3.4801445672896625,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.433333333333334,0.0,1.0,0.0,1.0,2.2585550269590495,-0.018419164826449622,-0.0038096426021189574,0.9974192900294848,-0.01155657559226061,-0.020310662956397357,0.0678872773082881,0.732646480319087,-0.0729983342418635,0.12817924674671857,0.7884753195485168,1.6185516523469776,1.1175346399154706,-0.2801324423317665,-0.30730487138309315,-0.10876418747931718,0.1637605931618754,0.8652455951659636,-0.602538773941511,0.09541980454515894,-0.31149704689427493,1.1735747996816752,0.28765696423562215,-0.6548422763227987,0.994823164930769,-2.6275972468726985,-3.430893988753784,2.5249502023324224,-0.9647949427483998,1.0576947444091722,-1.6196953283741,0.13416175341981113,-4.8508730146795065,0.5405012316907065,-0.23219211141333518,1.9759512372822186,-3.763676168590857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.441666666666666,0.0,1.0,0.0,1.0,2.2645357056544997,-0.018189591166465364,-0.0024297322753112616,0.9972437910292397,-0.008850934361198394,-0.01324015581739748,0.0724650295324572,0.7053091371662648,-0.07985572733571435,0.15274428254516015,0.7813807945279636,1.6448665147034236,1.0919178923108455,-0.3021828902206423,-0.33554214869247306,-0.0884251396733188,0.1558029699765093,0.8735720350357092,-0.6157362902964745,0.0960861226384645,-0.3518569927553362,1.177146958915012,0.28563311652668666,-0.6382258933275525,0.9623221214391009,-2.6645678445704615,-3.3388137219171634,2.3551612847068464,-0.946353769311073,0.9427562514293619,-1.545653394579145,0.027992007234954597,-4.8247063516169355,0.3205286073082769,-0.2535833018488709,2.011450682538234,-4.025148655469324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.45,0.0,1.0,0.0,1.0,2.270304157273863,-0.01799411773670856,-0.000943804032283594,0.9969990144272626,-0.006178005055064849,-0.006088867011124083,0.07692673920193295,0.6761676753359547,-0.0850384901527656,0.1751410320390825,0.7746697114920705,1.6584074402630606,1.065198753642713,-0.32454190640794084,-0.3629517667483792,-0.06951149940086974,0.1479880303400242,0.8809581993564529,-0.6282996638511634,0.09588633799907485,-0.39190881942122385,1.1789169431368132,0.2834305758714743,-0.6213180982804948,0.9277373540062803,-2.7015513200927743,-3.2308262463257886,2.1804502514539834,-0.9307944049714073,0.8325972133115522,-1.4679113099000807,-0.07368868607776996,-4.777850324858752,0.10899353731174344,-0.27498516968694875,2.0458354924240996,-4.262839772364185,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.458333333333333,0.0,1.0,0.0,1.0,2.2758500340772203,-0.017827301602157238,0.0006337460533338189,0.9966853334750257,-0.003532912192911884,0.0010898682207217117,0.08126916253899161,0.6454331968423119,-0.08844877930119856,0.19501462629373703,0.7685782584617273,1.6592322060174498,1.0378082017824226,-0.3472087455555219,-0.3893892527979029,-0.05208430214908575,0.14028972989365252,0.8874486552575684,-0.6402014787948092,0.09485797787050167,-0.4314878315029821,1.1789635178702078,0.2810500303652375,-0.6041286351204842,0.8912747918996978,-2.7383376288801253,-3.103913625117968,1.9954856958624518,-0.9185919944853299,0.7283216102942558,-1.387336689325367,-0.17095395495435567,-4.7123824107734045,-0.09206830027591817,-0.2962238327121225,2.0787341008724347,-4.474728325086022,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.466666666666667,1.0,1.0,0.0,1.0,2.2811632729512783,-0.017682707335823073,0.002286923937569882,0.9963044530562205,-0.0009094800742834973,0.00824333098014522,0.08549068481051307,0.6132824951013864,-0.09000526361943179,0.21202455107549245,0.7633069704169504,1.6475181200217621,1.0102124149667124,-0.37018086688927626,-0.41468366050034533,-0.03625340446982888,0.1326781637652687,0.8930968928613572,-0.6514219420065862,0.09303710541650226,-0.47044852626744726,1.1773824714655479,0.2784935119929389,-0.5866725299326209,0.85315854858818,-2.7747183260574606,-2.9547457223789086,1.7938769080508583,-0.9101877576325595,0.6309789124170573,-1.3049240892623404,-0.26404815453360736,-4.630772838983672,-0.2806886133192421,-0.31714419369586855,2.1092426607982495,-4.65844332410035,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.475,1.0,1.0,0.0,1.0,2.2862336673014196,-0.017553022112401322,0.0039981236213346,0.995859317718358,0.001699574790482737,0.015319972855110187,0.08959145730191742,0.579870565377707,-0.08964796589280632,0.22584810369750058,0.7590114036150412,1.6235760473403567,0.9829062423078083,-0.3934540509898129,-0.43863501483755135,-0.022186353681571444,0.12511993393310986,0.8979649704645194,-0.6619502136158482,0.09045717529494154,-0.5086673788193766,1.174285374314887,0.2757642938036397,-0.5689745907738467,0.8136340698313587,-2.810502338754534,-2.7797253377254596,1.568267059959314,-0.905967482926906,0.5415758119124181,-1.2218117895953773,-0.3533278699117273,-4.535735805451928,-0.4551266387971653,-0.3375985877447807,2.1359263358287417,-4.811200618658655,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.483333333333333,1.0,1.0,0.0,1.0,2.291050637303441,-0.017430207042893883,0.005748160369455778,0.9953539768840285,0.00430241260892206,0.02226998271291223,0.09357348902293013,0.5453560844429716,-0.08734497338044103,0.23619025877914634,0.7557994157782136,1.5878397018280184,0.9563918910271296,-0.41702257253518515,-0.461012416129103,-0.010115620137173648,0.11757870571648693,0.9021231563932308,-0.6717854718331758,0.08714830758464014,-0.5460441230249794,1.169797027485595,0.27286686886385925,-0.5510737576688085,0.7729718716105357,-2.8455001849915753,-2.575149734426201,1.3107494803398592,-0.9062399500733193,0.46105261984604295,-1.1391693740617637,-0.43922434937054694,-4.430013687837995,-0.614012067318197,-0.35744338182606805,2.156859180584294,-4.9297194680885825,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.491666666666666,1.0,1.0,0.0,1.0,2.295603329654781,-0.01730566604429752,0.007516405795699106,0.9947934222365303,0.006907847503946946,0.029045733350822,0.09744061843824424,0.5099414950507376,-0.08309998817122743,0.2428046544525035,0.7537402233334678,1.5408144560519335,0.9311375120413833,-0.4408790540730058,-0.48155417707798803,-0.0003405290092404576,0.1100159347652212,0.9056491807952868,-0.6809363698502109,0.0831367694720991,-0.5825009402833432,1.1640518398595838,0.26980690410653857,-0.5330269377641085,0.731472078696549,-2.8794467503497434,-2.3375907147825448,1.013845439888359,-0.9112205166916648,0.3902031420942831,-1.057897303848847,-0.5222342803442196,-4.3160941296780635,-0.7564436302993727,-0.376553007751943,2.1697097289022094,-5.010105992053309,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5,1.0,1.0,0.0,1.0,2.2998811852822816,-0.01717039806711025,0.009281106681381714,0.9941834259930479,0.009525207337724008,0.03560191507249149,0.10119826864138443,0.3468925824923706,-0.03936016763107436,0.2593770573926545,0.7801332361140554,1.425892393717158,0.9691089744311487,-0.4650133517076809,-0.49997226137547873,0.006781803860965669,0.10239169710495918,0.9086265420948022,-0.68941709356399,0.07844440291223648,-0.6179790251862805,1.1571896336472722,0.26659098540132686,-0.5149119288537717,0.6894701050763139,-2.8843460866341797,-1.2789591528026578,-0.1344534771722682,-1.0553315091852775,0.23276407485770534,-1.1082391351984544,-0.6598676107769114,-4.5106952852398186,-0.7528169827157294,-0.44813852727533465,1.9541147246818458,-4.9545805463515995,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.508333333333333,1.0,1.0,0.0,1.0,2.3016977077617855,-0.01683155934975726,0.011412334813335168,0.9934935037154127,0.012461470899917173,0.041440144952726285,0.1053474454732061,0.19109506855826547,0.000557263910506263,0.25667140831730395,0.7835667689940277,1.3338209517016337,0.9970266186756584,-0.48895148885024214,-0.5028701629580323,-0.0025814202954449277,0.09242707627879991,0.9095285820429152,-0.6994070221035185,0.07213897595915057,-0.6576791950373402,1.151504890147655,0.26233792865194966,-0.500458359019411,0.6488957362573556,-2.8476932265572907,-0.22318338535994298,-1.3841836855855727,-1.1758259939040834,0.22881766387550906,-1.5051451147785944,-0.7697591156472872,-4.69879649672579,-0.7604418566214743,-0.48890765514392087,1.7068413475473598,-4.851042670847088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.516666666666667,1.0,1.0,0.0,1.0,2.303346011678142,-0.016559922339604165,0.013289366153174303,0.9927676455409528,0.015184967040697304,0.0472286825541018,0.10932186585991097,0.1818409131273558,-0.004952476202293207,0.2326595274142765,0.7451499981750885,1.3090483870643572,0.9555698268016475,-0.5124749054836357,-0.5036919844648111,-0.01628792423212721,0.0827945972065578,0.9124401698260607,-0.7145028454769665,0.06561508431811502,-0.6962923001317103,1.144515602703581,0.2584425244822615,-0.4864645730613157,0.6086193938955291,-2.7881556364544537,-0.03231806331157161,-1.7100546304378894,-1.1483508158476095,0.4433868367058791,-2.003391217410686,-0.8026509328433401,-4.511873892376126,-0.9327624252648459,-0.4549131069828849,1.6883088047005312,-4.805468619700988,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.525,1.0,1.0,0.0,1.0,2.3050367253204183,-0.01632676628601585,0.014993428103315274,0.9920154474342562,0.017809433935403546,0.05282795743380869,0.11312551917042753,0.18831454069335674,-0.011060864946469698,0.21598561345687056,0.7205006900552077,1.2527123701937628,0.9170161792485798,-0.5354207494578164,-0.5034087973465585,-0.031082330802743082,0.07328789601467309,0.9169183626546799,-0.7327968757270299,0.05876146041176157,-0.732877093243609,1.1359588497265742,0.25475604353556824,-0.47231987894106886,0.5688045925956725,-2.7085059626195696,0.08496868881457287,-1.7677425260161717,-1.138134767210286,0.6141741181190952,-2.3240326365669794,-0.8408019005019364,-4.255690283437574,-1.1049457888299319,-0.4297650392727015,1.709417008212819,-4.720166826643979,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.533333333333333,1.0,1.0,0.0,1.0,2.3068195710078094,-0.016113262818887947,0.01654171851856796,0.991247160570785,0.020364228516003315,0.05812790284852157,0.11677119428394066,0.1994007294548459,-0.016526247499382876,0.20055031419172142,0.698367474108782,1.1730484496856066,0.8816629963436653,-0.5576166715272952,-0.5022758396512349,-0.04575029966573007,0.0638256844197197,0.9226764051280456,-0.7532367227530828,0.05160171930974942,-0.7672204715223365,1.1260998395564155,0.2512797738277165,-0.45797428959110204,0.5299499467847961,-2.6093386299141685,0.18454723460104683,-1.7222132288923762,-1.1355068526801266,0.7583158108022592,-2.543017234851046,-0.8754810238058242,-3.985357390363937,-1.240571090165088,-0.40330517464838733,1.7253788767764422,-4.568139735532135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.541666666666667,1.0,1.0,0.0,1.0,2.3087111738499844,-0.015906815253203605,0.0179285433370425,0.9904734187603172,0.022864453669419575,0.06304800252261387,0.12026875279765727,0.21293588733950217,-0.021445883836833247,0.18440981225416145,0.677063861003813,1.0754499223165386,0.8489396107828051,-0.5789097266230525,-0.5003330101032077,-0.05978588461761602,0.054362781803337645,0.9295569595013842,-0.7751804963078807,0.044170110014997835,-0.7992997164163412,1.1152826648904894,0.2480342906247618,-0.44356356432812816,0.4926689303368036,-2.4921591795152276,0.2853036472072168,-1.6336771189775126,-1.1375430059486402,0.886629179114351,-2.693939941876242,-0.9061197049513593,-3.715741130654211,-1.3347884932555942,-0.374196033332061,1.7203271179544677,-4.338017089291304,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.55,1.0,0.0,0.0,1.0,2.3107225137172405,-0.015696827464837873,0.019142232794431162,0.9897050186863089,0.02532177832756056,0.06752173509760832,0.12362685323929141,0.22870543001038884,-0.02598801103842288,0.16707262462700623,0.6561963454349751,0.9624426688554546,0.8186678650604614,-0.599152657852549,-0.49752077886444795,-0.07297825164868861,0.04486663432057569,0.9374535581132848,-0.7981357217843535,0.03649972422722676,-0.8291494903665734,1.1038533646688222,0.24504317327218214,-0.4293021709585276,0.4576496619632744,-2.3573392455011044,0.39621957826800447,-1.528023417004232,-1.1430585354160079,1.0037128330395384,-2.789704581704273,-0.9328452162491828,-3.4515837901023128,-1.3878191088634306,-0.3421390582725642,1.6864071499454492,-4.02066549903499,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.558333333333334,1.0,0.0,0.0,1.0,2.3128657664346655,-0.015473430277175904,0.020169596464855243,0.9889527259409071,0.027746754169882423,0.07148941080837758,0.126853804215105,0.24691786975263808,-0.030318210994215236,0.14841701651626316,0.6356091383742147,0.8353339070272943,0.7908178455191593,-0.6181987140480709,-0.49372935046540767,-0.08525294156768655,0.03531180621307085,0.9462855067187098,-0.8216755726696185,0.02862268974417812,-0.8568261129180464,1.0921523464094323,0.24233197298688572,-0.415456778495704,0.4256578386862204,-2.20501736726477,0.5217209339569817,-1.4174086281458167,-1.1513067621598974,1.1122291281993313,-2.836828285124502,-0.9557442877183222,-3.1949562482971405,-1.4001445218104314,-0.3068819217890889,1.617826601423441,-3.6067434908654263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.566666666666666,1.0,0.0,0.0,1.0,2.315155260653771,-0.015227104277971778,0.020996930442784143,0.9882270415973222,0.03014948424264756,0.07489538061884794,0.1299577039890791,0.26778486150828434,-0.034576358627433454,0.12836422233090683,0.6152198540447266,0.6948803338209161,0.7653615602637329,-0.6359029473069618,-0.4888254299651649,-0.09660172878445222,0.025678188284577404,0.9559907102499403,-0.8454161932030952,0.020570652765254726,-0.8823987611715257,1.0805176226386484,0.23992847457569733,-0.4023383942681369,0.3975372704488506,-2.035589042412629,0.6636585533248462,-1.3074956414310468,-1.1617012157132647,1.2142791753100823,-2.840072077979332,-0.9748761975350445,-2.9473386935035717,-1.3716145686267645,-0.26813563274189656,1.5097274563161656,-3.0873636782459513,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.575,1.0,0.0,0.0,1.0,2.3176068951869624,-0.014948505979809285,0.021609868400386232,0.987538002644157,0.03253996199015757,0.07768627720293697,0.13294617913318776,0.29151053760838963,-0.038782062687973,0.10660594325507813,0.5949161979931027,0.5405318885950959,0.7418282556762701,-0.6521251980882814,-0.48266837457666023,-0.10704453559153733,0.015950119284516437,0.9665234929738779,-0.8690101073026074,0.012374753118594045,-0.9059484244764393,1.0692921035989862,0.23786304577452078,-0.3902946542237679,0.37420177738212124,-1.848704499866347,0.8231732960409732,-1.2000214808460254,-1.173682517986731,1.3119930176628003,-2.8025053069753336,-0.990618967418719,-2.710722344429606,-1.2983482823001502,-0.22566144196721816,1.3571141755217708,-2.4508419302535644,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.583333333333333,1.0,0.0,0.0,1.0,2.3202378283443026,-0.014626438828007795,0.021990159343691067,0.9868960656762523,0.034928521688696604,0.07980202966847398,0.1358226416629277,0.3161937247972349,-0.042247292755401594,0.08743133101049175,0.5778432984180191,0.3947826101262126,0.7172598036343587,-0.666714688971401,-0.4751058750311487,-0.11660208679855265,0.0061168129847985545,0.9778572605443203,-0.8921246149860175,0.004060336641609408,-0.9275774669120191,1.0588784846003125,0.23616745054291036,-0.3797198246761074,0.35668990494462455,-1.6630079258987474,0.9814164447069107,-1.1127182593419147,-1.1905011327350998,1.397502678708531,-2.7558769013913165,-1.01197083793159,-2.4815755011601737,-1.2413044742358137,-0.189506101736297,1.197326796978453,-1.8137929404825814,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.591666666666667,1.0,0.0,0.0,1.0,2.323043424812751,-0.014251641109481822,0.022201061384038993,0.9862968866594386,0.03732371773958507,0.08137870649967326,0.13857451998649387,0.33793780721907163,-0.044409829339397626,0.07731485816781816,0.5669915386173321,0.292660513591309,0.688987452974083,-0.6798419968532605,-0.46631143383154505,-0.12558983991390257,-0.0038915662610685604,0.9898152042856867,-0.9149413889924627,-0.004491427513599118,-0.9473080161624422,1.048603695695056,0.2347046107455825,-0.37033920760746036,0.3439718950407449,-1.50856752496084,1.1072614431326744,-1.0701822287350213,-1.2153557927268157,1.4571461572646838,-2.748117036662605,-1.0470048641291898,-2.2495628634336606,-1.29608256558424,-0.17197538555189962,1.0970889868182865,-1.3771445421434658,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6,1.0,0.0,0.0,1.0,2.3259972225914947,-0.01382811249959356,0.0223410203905284,0.9857264707491288,0.039718646067648126,0.0826482928970491,0.1411914080276784,0.35583615107572475,-0.04622883105850832,0.0744732987934673,0.5584448035104922,0.22831680502391852,0.6592181065730947,-0.6918574810540816,-0.45665151764560413,-0.13443845727746967,-0.014139116893981707,1.002143029832065,-0.9379265655970609,-0.013389744427210422,-0.9650701813025802,1.0372771085072419,0.23330119411704536,-0.36143500822913593,0.3337374959089001,-1.3827780162582592,1.2017023281961647,-1.0630883192782703,-1.2433996612512217,1.4932136773882254,-2.7752496935884063,-1.0853617276188479,-2.0112276480394975,-1.4445952442785481,-0.1654482557625453,1.0581954985870357,-1.1359042468724878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.608333333333333,1.0,0.0,0.0,1.0,2.3290821222917257,-0.0133674624230648,0.022443297709806683,0.9851798330464491,0.042096836337983876,0.08369337289864356,0.14368010391882366,0.3717657774515705,-0.04857756020847027,0.07409110192446874,0.5486531298134546,0.17785196336380146,0.6305893068523455,-0.7028882971242315,-0.4462830616949423,-0.1433079785685404,-0.02461489394858892,1.0147020989088238,-0.9611955505522695,-0.022580789640579916,-0.9808284769631005,1.0245271082904135,0.23194713981620674,-0.3527026159643431,0.3250401575928701,-1.267950593718894,1.2825380740876147,-1.0686033932283578,-1.2703988669282225,1.5150230136075127,-2.8070781254369037,-1.1171913070112314,-1.7712631916615829,-1.6204098125050859,-0.1588370765648328,1.0452933379609164,-0.9740814092509897,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.616666666666666,1.0,0.0,0.0,1.0,2.3322927664774302,-0.012876384158045543,0.022520749556616107,0.9846555025210879,0.04445022435332367,0.08454440429481444,0.14604780933837602,0.38710118634341834,-0.05135490785658336,0.07466136352841318,0.5380246289416911,0.1323426319400896,0.6032591189028569,-0.7129899909493965,-0.4352758830774772,-0.15224851383127563,-0.035312431342785416,1.0273934133921903,-0.9847112010210093,-0.03200959954406428,-0.9945912344969399,1.0102702782988238,0.23065390950763148,-0.344013452596454,0.31750280575471695,-1.1580577389063684,1.3572914304423889,-1.0775205346667567,-1.297014699545838,1.5259823357775337,-2.8308692230309274,-1.142987750811418,-1.5334457154821668,-1.799141141479046,-0.15084714752924444,1.0434807937440327,-0.8432809172431877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.625,1.0,0.0,0.0,1.0,2.3356294242768203,-0.01235759531861321,0.022578485607569754,0.9841535987457967,0.04677588220007972,0.08521090551531978,0.1482997387101072,0.40249621626920773,-0.054400917678694094,0.0755998738135697,0.5269786923712315,0.08811533536344249,0.5769623202105832,-0.7221892594393376,-0.4236615378542358,-0.1612666541463197,-0.04623180560768622,1.0401351378384494,-1.0083767042694516,-0.04163058548743688,-1.00638590555447,0.9945414225990961,0.22943302069071933,-0.33531126940194256,0.31098547563881695,-1.0506244176684154,1.4292219355829838,-1.0860906693095358,-1.3237843040172388,1.5276313131776131,-2.841839819019154,-1.1636780685861294,-1.2996126630818905,-1.9706562702859176,-0.1415911110520257,1.0466347838362433,-0.7233267289989198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.633333333333333,1.0,0.0,0.0,1.0,2.3390947946195007,-0.011811763890295219,0.02261849284262925,0.9836749404660462,0.049073280627793175,0.08569365498130216,0.15043943008253574,0.4182294145393741,-0.05762499357284749,0.07665665276566373,0.5157216272099557,0.04361556437251457,0.5514507133098752,-0.7305003979105368,-0.4114555174844275,-0.17035002498643456,-0.05737550307640606,1.0528539352784838,-1.0320751980046619,-0.05140423402049977,-1.0162514455483047,0.9774260071273918,0.2282940576567644,-0.3265695395325166,0.3054473602714016,-0.944602893952784,1.4996237362262266,-1.0925193159800484,-1.3508396625391104,1.520766325856644,-2.8385764591830753,-1.1798114149159558,-1.0709734715908192,-2.130563860084429,-0.13125800687315836,1.0522761261102576,-0.6058507582926809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.641666666666667,1.0,0.0,0.0,1.0,2.3426924574155157,-0.011238658095944378,0.022641462736917112,0.983220619058265,0.0513428853550627,0.08598969009486156,0.15246932668416152,0.4343980081261881,-0.060983045094538696,0.0777116560612108,0.5043288360742336,-0.0018271522294693032,0.5265536049701217,-0.7379326410052174,-0.39866780891713205,-0.17947530941265383,-0.06874579998333806,1.0654812432693934,-1.0556863119225028,-0.061294109069369475,-1.024235463414317,0.9590320249310222,0.22724538724283336,-0.3177733339667716,0.3008879630006056,-0.8395948470758974,1.5688495075052478,-1.0956221855509614,-1.3780789540816203,1.5058512605145324,-2.8210564576711405,-1.191663592171843,-0.8484844040607165,-2.2768771782608566,-0.11995346986384103,1.0594935101388347,-0.48756286582950503,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.65,1.0,0.0,0.0,1.0,2.3464261269707394,-0.010637708788015107,0.02264755600059726,0.9827917918266462,0.05358551371187279,0.08609440459915511,0.15439119189622744,0.45101254618275055,-0.06445203098148904,0.07869747895756904,0.4928123741766172,-0.04850790348529779,0.5021607349261468,-0.7444936453618017,-0.38530802569267336,-0.18861039474561725,-0.08034348564443307,1.0779514562870594,-1.0790928056325142,-0.07126529389003049,-1.03039285228265,0.9394780541563775,0.2262948331590337,-0.308911314363536,0.29732131250757654,-0.7355130549346822,1.6367931352050058,-1.0943629252737064,-1.4052871325615182,1.4831799890496011,-2.7898010410571183,-1.1993790947049559,-0.6329700864407339,-2.4086278103366654,-0.1077200582706922,1.0680773581131775,-0.36741774497545787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.658333333333333,1.0,0.0,0.0,1.0,2.35029928320868,-0.010008265335262705,0.022636738948524242,0.9823895793705358,0.05580205347331235,0.08600244121217815,0.1562063547935826,0.4680412523869262,-0.06801625073206638,0.07956842589810086,0.48115650940231663,-0.09656032660227357,0.4781995824083405,-0.7501911919207954,-0.37138792333038195,-0.19771469150054893,-0.0921672521926967,1.0902009097535534,-1.1021829959401215,-0.0812837606477854,-1.0347849648549958,0.9188882280920778,0.22545005293832182,-0.2999720446648853,0.2947643339176813,-0.6324240285846949,1.703123058932443,-1.0877179131405807,-1.4321926712260176,1.4529467698337717,-2.745516757073889,-1.2030554490781464,-0.4251710732057612,-2.5252686158767634,-0.09456689252213102,1.078146378952537,-0.2453938251404819,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.666666666666667,1.0,0.0,0.0,1.0,2.3543149796060954,-0.00934970807924102,0.022608939373225643,0.9820150115723632,0.057993343982961305,0.08570807715485346,0.1579158466102517,0.4872226614948064,-0.0722018256164006,0.08124724681056965,0.46712429362783403,-0.1589536642014438,0.45593848657684377,-0.7550340458382133,-0.35692264137713264,-0.2067390266312936,-0.10421336349820003,1.1021672357842889,-1.1248514182504123,-0.09131621804133293,-1.0374790368360793,0.8973902438917648,0.22471871828366485,-0.2909422080476604,0.29323141542190184,-0.5146640286173554,1.768307546655361,-1.040457710461491,-1.45451380254503,1.4112524046826325,-2.6581192225368167,-1.199216684776463,-0.22552414618337124,-2.6026354040729105,-0.07529384550546303,1.0885030956084796,-0.08838156900472294,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.675,1.0,0.0,0.0,1.0,2.358509364090805,-0.008661825613865321,0.022574023189967374,0.981677508557169,0.06016015377297661,0.08509621529378363,0.15952635905607823,0.5108599581593223,-0.07737925490678839,0.08442283902021429,0.44913877524764056,-0.25155666107604413,0.4366908502468215,-0.7587689257310847,-0.34191613088612594,-0.21505565334157378,-0.11640914890178053,1.1137217831649306,-1.1464849829824018,-0.10127070539405979,-1.0385437006247187,0.8755109713575293,0.22419515551323077,-0.281830326404744,0.2932913077676026,-0.36517265663345677,1.8326432825116634,-0.9095368127264286,-1.4683141383170597,1.3553217823976782,-2.493764963014531,-1.185506533505994,-0.03684852277449302,-2.6070294422763296,-0.04479100337825115,1.0951988216303654,0.149649153200081,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.683333333333334,1.0,0.0,0.0,1.0,2.362925457182251,-0.007938455975120844,0.02253898311385811,0.9813876105835622,0.06231247143277614,0.08402850856414219,0.16104261375650836,0.5377255667669517,-0.08267983686327758,0.08757441606628388,0.4304236918381531,-0.36473919204600713,0.4189938464180701,-0.7611202567821043,-0.3263785866686049,-0.2218979735100674,-0.12868526580348436,1.1247559321575835,-1.1664141676339879,-0.11107466026643283,-1.0380931788823209,0.8539397531871593,0.223972201560694,-0.272688894353821,0.2957255679752365,-0.19968908832871612,1.8940901362917884,-0.7192291245699378,-1.4779927208464156,1.2915252461569127,-2.281670676390979,-1.1675900580815293,0.13557722555803675,-2.5484317558389202,-0.008704899710784142,1.0964167646283307,0.4503883428824551,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.691666666666666,1.0,0.0,0.0,1.0,2.36757120014767,-0.00716997371680225,0.02249757852487671,0.9811467353272325,0.06446396755839363,0.08247354390811727,0.16246105748330902,0.5651518913064111,-0.08741141316003119,0.08928654462482029,0.413333077737642,-0.48131901770244445,0.4010861726113582,-0.76209707720323,-0.31034796194792946,-0.2270428054177394,-0.14104236091588745,1.1352472039342125,-1.184512827588918,-0.12073053969541861,-1.0362840801987514,0.833037108760214,0.22405007385138437,-0.26355671366093847,0.30079778014897685,-0.04034421533157362,1.9493543019576376,-0.5122654386094844,-1.4875182295608054,1.225256968991717,-2.0645287159047765,-1.1497567577161758,0.2894261548809718,-2.45618419792762,0.026961548848389305,1.0973462132505973,0.7631613481173161,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7,1.0,0.0,0.0,1.0,2.3724402564630926,-0.00635170437687192,0.022444066648276268,0.9809527451500163,0.0666200677328007,0.08043744163760977,0.16377819250660955,0.5918525259042416,-0.09168766332630973,0.08948536290970764,0.397346846295937,-0.5946798953979948,0.3826422026274321,-0.7617926603709638,-0.2938893483026443,-0.23043573082022548,-0.15347723629616444,1.1451768816407788,-1.2008229795657341,-0.13023727289503575,-1.0332694096343047,0.8130033498883656,0.22442156070816716,-0.25439979079964437,0.3084449237771918,0.10604332251742177,1.9954658455233432,-0.30158465688097047,-1.4961454765320692,1.15619412965966,-1.8556964521295027,-1.131314752558424,0.4257886562977742,-2.3450861274381496,0.06189602425245133,1.1057071814062291,1.0571899803909957,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.708333333333333,1.0,0.0,0.0,1.0,2.377521125467198,-0.005482933971641083,0.02237504834361428,0.9808017194516999,0.0687810049237211,0.07794232016209407,0.1649913791991268,0.6172810283730972,-0.09568825431367114,0.08835111647506876,0.3819926826876574,-0.7018322595320671,0.3636115456311045,-0.7603296884946062,-0.27709019785587374,-0.2320692163657556,-0.1659781188580886,1.1545171060952069,-1.2154411017910765,-0.13958578557139234,-1.0291876025937885,0.7939523399695781,0.2250816742555919,-0.24512826063750132,0.31841761315549344,0.23711557204472156,2.03031322204569,-0.09085764849969757,-1.5029734480895292,1.0832721738911921,-1.6594202794719815,-1.1114868688389308,0.5464470561332524,-2.2233711022258706,0.0963568239335083,1.126849637320082,1.3152284072633746,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.716666666666667,1.0,0.0,0.0,1.0,2.382800762694908,-0.004565392502868032,0.022289118969979163,0.9806887714909454,0.07094408592800358,0.07501809179557864,0.16609863348859444,0.641227800704131,-0.09955252617835052,0.08607659723305179,0.3669782277769693,-0.8012452364347402,0.3439796690177916,-0.7578407341702185,-0.2600507946018828,-0.2319500249618871,-0.17852679376432326,1.1632314178722987,-1.2284799842236005,-0.14876205404235127,-1.0241619586987505,0.7759471648512678,0.22602750777372563,-0.23561896351097633,0.33036539723158137,0.3522196948540701,2.052842058107356,0.11852925792051494,-1.5073268860930529,1.005632020753695,-1.4768655777466488,-1.0898259889081874,0.6531021645175006,-2.096037150232559,0.1305348024229841,1.1636369056385076,1.528341260414332,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.725,1.0,0.0,0.0,1.0,2.388266054518531,-0.0036023298815402215,0.02218622226783724,0.980608522533184,0.07310485945016679,0.07169898075455525,0.16709835791780558,0.6639956475888309,-0.10298044412954008,0.08238175342250552,0.3518438492092841,-0.895079143844088,0.32160880201779063,-0.7544593602470384,-0.24287616355408448,-0.230093728733747,-0.19110023362630615,1.171277639774435,-1.240055528086854,-0.15774955205319546,-1.0183025665184968,0.7590183874657022,0.22725725429597496,-0.22573431221019286,0.3438899674957323,0.45525658735630525,2.0654198034166815,0.3255166626771072,-1.50805847132353,0.9232337832041404,-1.3055611959677993,-1.067399656610107,0.7441484593364889,-1.9555164208838338,0.16327008819043476,1.2127834678587324,1.7077507684047666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.733333333333333,1.0,0.0,0.0,1.0,2.393906672626138,-0.0025887848049390566,0.022060368150059136,0.9805602758614054,0.07525851999495595,0.06799795980359538,0.16797017006999673,0.6857896375820512,-0.1058494005183709,0.0771204819389573,0.33662359256597535,-0.9842611279660196,0.29530995847226593,-0.7502531243809467,-0.22562713121160477,-0.22652474725060198,-0.20366110161971543,1.1786186475923677,-1.2502393374897305,-0.16655204831918638,-1.0117594843764757,0.7433552245032039,0.22874867591023287,-0.2154059057133308,0.3588279100383275,0.5481957517643377,2.0695112270974385,0.529050271784467,-1.5045804553050857,0.8362081205166616,-1.1444228521559108,-1.0450208229777969,0.8190450691450923,-1.7983811715573461,0.1935990731793491,1.2720493442391878,1.8601292647735435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.741666666666666,1.0,0.0,0.0,1.0,2.3997121974251256,-0.0015252192869958958,0.02190922535502799,0.9805406171977243,0.07740130585800688,0.06394247365456157,0.1687023886610813,0.70606430392321,-0.1088758145617128,0.07106990106236943,0.32180654632491984,-1.0634892476917504,0.2683653335195188,-0.7453227643842995,-0.20838430976912717,-0.2212762242040059,-0.21617657454805758,1.1852144417830461,-1.2591292422894524,-0.17516656576949208,-1.0046518153660786,0.7290453679397464,0.23048390551563078,-0.2045334898062064,0.3748921219086247,0.6255327843404768,2.061564528101057,0.7274323962734397,-1.4975590153926277,0.7438424716515657,-0.9976081899983935,-1.0207719655591525,0.8835396123772443,-1.6436997695311661,0.22324204287364757,1.3472580208985618,1.9623081141585474,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.75,1.0,0.0,0.0,1.0,2.4056701951234003,-0.00042288068233303,0.02173809017085345,0.9805410413293917,0.07952680909498276,0.05958754673872288,0.16930468740575697,0.7245351082041277,-0.11239595505649644,0.06468709679113388,0.30705075485374084,-1.1301848187155696,0.24233635299699696,-0.7398275779752721,-0.1912677224099205,-0.214400873979378,-0.2286204185429259,1.1910160221198938,-1.2668661406563704,-0.18356491441183892,-0.9970338241701883,0.7159602283443511,0.23246937662479367,-0.19295160536502143,0.39153304527430327,0.6860332228729971,2.040828198255203,0.918055629550748,-1.486760338656895,0.6456835884208578,-0.8663667225961147,-0.9933866823189469,0.9410018030338718,-1.501711302328006,0.2533886517088363,1.439804154300845,2.004991548559245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.758333333333333,1.0,0.0,0.0,1.0,2.4117689837632748,0.000710000152545579,0.021550174005931996,0.980555482372191,0.08162575668273019,0.05498037275220038,0.16978027107977126,0.7413729400668603,-0.1162303774738331,0.05783603156086982,0.2919364307154036,-1.1856833534031321,0.21613563659089685,-0.7338888773364162,-0.1743705064648738,-0.20597529704482676,-0.2409559135256725,1.1959758349233938,-1.2735686876660544,-0.19172301047480786,-0.9889684519821808,0.7040168462342796,0.23470704971077805,-0.1805367539011923,0.40830864771794545,0.7331156709802067,2.0101341635015184,1.0980692307439666,-1.4714533221723398,0.5420928833352567,-0.7487813645501395,-0.9634695360460893,0.990805309901861,-1.36870012219247,0.2834225971081561,1.5448820965513173,1.9994405411773808,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.766666666666667,1.0,0.0,0.0,1.0,2.417997625689157,0.001866136654360075,0.021347285281572925,0.9805791042230031,0.08368946714374975,0.05016524176122794,0.17012977978456825,0.7566372507027725,-0.12032501554136579,0.05045905631546621,0.2764924517723087,-1.2305948529241257,0.1893179797405638,-0.7276089834589353,-0.15776548635156185,-0.1960997201336452,-0.25314464057913155,1.2000509035088147,-1.2793458300655394,-0.19962274001260708,-0.9805204023384906,0.6931485596411433,0.23719308657659627,-0.16720357042249948,0.4248570542939263,0.7687912728704616,1.9717162111717956,1.2646842693093936,-1.451467642639744,0.4335897670912159,-0.6439213058571003,-0.9316061208716941,1.032847823554468,-1.2434110532955645,0.3127660782889041,1.658265132300415,1.9540811803679026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.775,1.0,0.0,0.0,1.0,2.4243450840361134,0.0030385284593486776,0.021130212649489628,0.9806080445968515,0.08570951083045955,0.04518479450063507,0.17035280147738419,0.7703172856070882,-0.12464057173378029,0.042535160673580125,0.26073366792340935,-1.2652799161943493,0.16169951036565167,-0.7210756894552418,-0.14150856961201053,-0.1848972258896702,-0.26514704090300156,1.2032023310415807,-1.2843007094303394,-0.20724977915600276,-0.9717543215896063,0.6832933286793536,0.23991981768225978,-0.1528990016961854,0.4408766673907438,0.7946227723946864,1.9276543447509094,1.4150039733445026,-1.4267408211080779,0.32060040738974394,-0.5510697802520959,-0.8982272153360288,1.0672001781083051,-1.125572675386215,0.3409710045908654,1.776373277472208,1.875407469779018,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.783333333333333,1.0,0.0,0.0,1.0,2.4308001386018434,0.004220439937294861,0.02089891119990876,0.9806392827598931,0.08767778660812449,0.04008062536420643,0.17044866181405133,0.7823565547599608,-0.12912973613352383,0.03407293361675836,0.2446684821569834,-1.2900169311467777,0.13321688969186068,-0.7143652705856905,-0.1256379139390467,-0.1725163205779035,-0.2769236542642662,1.2053942436319771,-1.2885303264030743,-0.2145931936015409,-0.9627337327033522,0.674389015051373,0.2428759366531107,-0.137597349131296,0.4561138454569099,0.8119514137929396,1.8800008603314173,1.546056439826637,-1.3972963121900772,0.2034243505517086,-0.4695128461998488,-0.863704863929845,1.0940280171840122,-1.0153877070716089,0.36760610167745844,1.8960572408212872,1.7687837654736038,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.791666666666667,1.0,0.0,0.0,1.0,2.4373507625253716,0.005405253081550775,0.0206527709476422,0.9806706377313147,0.0895863835582258,0.03489325829604856,0.17041666790025944,0.7926502731013227,-0.1337267522474781,0.025106920361674577,0.22830410229393033,-1.305084965106304,0.10386656361522052,-0.7075431658920261,-0.11017522193982024,-0.15912961855922625,-0.2884353127728362,1.2065927368841092,-1.2921259235336702,-0.22164486022150018,-0.9535205213032061,0.6663702002281601,0.24604658604355076,-0.12129804768249727,0.4703563968153039,0.8219862431370739,1.8307499451934097,1.654938265548247,-1.3632353755396787,0.08220777664044387,-0.3984680858232048,-0.828392151406766,1.1135511821844313,-0.9133214401498901,0.39220946740333773,2.0144379544575735,1.6389142384769395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8,1.0,0.0,0.0,1.0,2.443983912193018,0.006586595541583847,0.0203907623932621,0.9807007186120764,0.09142777082864022,0.02966211056216755,0.1702563432950069,0.801071452688099,-0.1383413317156535,0.015692237101579368,0.21167979904100115,-1.310788071565734,0.07369700233321597,-0.7006654998667393,-0.09512541485248986,-0.1449340161520994,-0.29964424385659416,1.2067643732426512,-1.2951714611667944,-0.22839972945832032,-0.9441745463336116,0.6591669910488749,0.249412761109833,-0.10402338322366979,0.4834290827648589,0.8257757103082031,1.7818944169501671,1.7388018111458436,-1.324779043027322,-0.043081888028413395,-0.3369699309570606,-0.7926686356837115,1.1260307468696529,-0.8199517720192873,0.41425045967003304,2.1288787803734897,1.4900559224902243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.808333333333334,1.0,0.0,0.0,1.0,2.450685248343806,0.0077584487533064106,0.0201116066174477,0.9807288768930655,0.09319494950428692,0.02442531603278306,0.1699675714711072,0.8074543004184463,-0.14285826277472802,0.005910344125125769,0.19484333621133798,-1.3074930553192434,0.04278893118594664,-0.6937802373868894,-0.08047698165731745,-0.1301495883734622,-0.3105149634899582,1.205874705416969,-1.2977420890496212,-0.23485600414956204,-0.9347533421887119,0.652704337361172,0.25295076037138464,-0.08581673467627245,0.49519066219014096,0.8242673249683907,1.7352711557449072,1.7951300672045947,-1.2822260274980468,-0.1726671812151226,-0.2838696071094704,-0.7569182916541656,1.1317667346130755,-0.7359419902623121,0.4331453869984975,2.236913618778475,1.326200312808764,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.816666666666666,1.0,0.0,0.0,1.0,2.45743865397216,0.008915171548180011,0.019814030833303308,0.9807551681058917,0.0948814846418716,0.01921935685893642,0.16955064266407321,0.8116043171309469,-0.14713516598547527,-0.00413247385544948,0.17786868689295454,-1.2956218435753275,0.011259126459530387,-0.6869277111172661,-0.06620422892340808,-0.11501518169868948,-0.3210146776482283,1.2038865868890658,-1.2999026212852856,-0.24101503431922308,-0.9253117674233937,0.6469012912111697,0.2566318508931413,-0.06674148957736187,0.5055324213116716,0.8182724211077819,1.6924994699600444,1.8218414151775928,-1.23597503211195,-0.30698904163337204,-0.23778454250154457,-0.7215475186686021,1.1311052747213757,-0.662025821480674,0.4482455662436102,2.3362360593015925,1.1511399578473247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.825,1.0,0.0,0.0,1.0,2.464226078792854,0.01005170343817976,0.01949692076342006,0.9807802386317919,0.09648177859859232,0.014078967836408938,0.16900642760742499,0.8133095474764228,-0.15100559826745086,-0.014310296903769712,0.16086317722125437,-1.275658303737338,-0.020755357902619988,-0.6801423637017597,-0.05226865715798338,-0.09978556478716898,-0.3311145473584907,1.200758221389746,-1.3017051647579803,-0.24688179612737207,-0.9159015876100223,0.6416705736698274,0.26042151980877815,-0.0468794670212459,0.514376328154263,0.8084688615496827,1.6549491857891148,1.8173499343853692,-1.186513908484077,-0.44670002051222735,-0.19708220779171892,-0.6869921830725872,1.1244184269466406,-0.5989213811076843,0.4588309142916214,2.424683860818295,0.968581341548207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.833333333333333,1.0,0.0,0.0,1.0,2.471027227464007,0.011163626039955379,0.019159487396110016,0.9808052644135846,0.09799115915091458,0.009036734510070327,0.16833628086783436,0.8123393922565832,-0.15428569715173707,-0.024476836972307382,0.14394882423435196,-1.2481476214914278,-0.05311167800548515,-0.6734532300914381,-0.038621742493589496,-0.08472601612559999,-0.3407899094562962,1.1964415865471953,-1.3031873247484809,-0.25246490403709954,-0.9065714603076164,0.6369192681927083,0.26427903279800163,-0.026330091897056953,0.5216754436708084,0.7954366925070544,1.6236422447307657,1.7807085645652563,-1.1343731494389864,-0.5926403529797764,-0.15991166979393956,-0.6536897507658962,1.1121013195140095,-0.5473231299540271,0.4641337821180658,2.500226754560254,0.7821828029894529,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.841666666666667,1.0,0.0,0.0,1.0,2.4778194136311256,0.012247257505159707,0.018801434276106872,0.9808318385845057,0.0994059850689715,0.004122987014857897,0.16754210076771422,0.8084599869182922,-0.15678213973991825,-0.03446841818501788,0.12726503461388416,-1.2136524156885296,-0.08565314503384891,-0.6668850854933088,-0.025207953079137285,-0.07010708871108137,-0.35002076651580716,1.1908808821734165,-1.304370359254546,-0.2577766253068037,-0.8973665656181221,0.6325485215039269,0.26815708284407924,-0.005209021111908339,0.5274127082040873,0.779632525097953,1.5992460820760497,1.7115681863434982,-1.0801202912875019,-0.7458089613379082,-0.1242269073858937,-0.6220664924316421,1.09458559657174,-0.507943501876098,0.46335642236898456,2.561001745838916,0.5954572477401388,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.85,1.0,0.0,0.0,1.0,2.4845775238580328,0.013299695187295308,0.018423074152343805,0.9808618669727407,0.10072368958552691,-0.0006342434777533804,0.16662633048358888,0.801445376399045,-0.15830465466926008,-0.04411143108961202,0.11095716963614621,-1.1727358364978757,-0.11822864621487947,-0.6604593546731389,-0.011967641125655333,-0.056199879686541686,-0.3587919143110879,1.1840114371915635,-1.3052577732049124,-0.26283267891096024,-0.8883283670314207,0.62845354316144,0.2720016398374847,0.016353270533591653,0.5315997311331441,0.7614194364129578,1.5821182029613945,1.610063738212386,-1.0243157604427167,-0.907302608100724,-0.08784966278406081,-0.5925134416768363,1.072317939476708,-0.4814678079483392,0.45569245213167076,2.605315745729009,0.411773174352863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.858333333333333,1.0,0.0,0.0,1.0,2.491274110137446,0.014318810653161184,0.01802537093493121,0.9808974811699271,0.10194276184338953,-0.005209190550556129,0.16559187503083084,0.7910907363136231,-0.1586790469270096,-0.05323129283895256,0.09516549577000283,-1.125935338740977,-0.15071000447032376,-0.6541947615530929,0.001160683636885955,-0.04327269307420827,-0.3670926958565191,1.1757591720384044,-1.305834520300947,-0.26765184933475095,-0.879494599960177,0.6245240580381213,0.27575195704627375,0.03821290798357514,0.5342755944433016,0.7410915909172222,1.5724058975046036,1.476598122816091,-0.9674737135659706,-1.0782439680706268,-0.04854847069653445,-0.5653630676354371,1.0457394084514782,-0.46852063234180674,0.440348358099768,2.6316557062296604,0.23431801025889376,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.866666666666666,1.0,0.0,0.0,1.0,2.4978796357240083,0.015303198881859804,0.017609915391095132,0.980940966754093,0.10306266128468437,-0.009578179238244593,0.16444198391867676,0.7772272359923191,-0.15776044115516602,-0.061661498009645946,0.08001495283186011,-1.0737294903994008,-0.18300430672705145,-0.6481078281578518,0.014239123832754726,-0.03158991097294017,-0.3749164762038541,1.1660407043903864,-1.306066914383188,-0.2722553967048842,-0.8708993768905627,0.6206448659557432,0.2793407791391475,0.06021419897075266,0.5355050313041256,0.7188938362230046,1.57019129970118,1.31154820290096,-0.9100304551613492,-1.259700674687605,-0.004127294024773853,-0.540865920273722,1.0152721068356518,-0.4696516787205085,0.4165671788924996,2.638711059630904,0.06601576738881398,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.875,1.0,0.0,0.0,1.0,2.5043628847704986,0.016252082527534673,0.017178833547783028,0.9809947122260368,0.10408367236280522,-0.013719319893441573,0.16318009680664727,0.7597386244712451,-0.15544614279739244,-0.06925291150224791,0.0656066419409716,-1.0165079983153862,-0.2150666792038888,-0.6422131976160428,0.027330538631905623,-0.021413556359192273,-0.38225987010920826,1.154764160793611,-1.3059033085346932,-0.276666281339313,-0.8625733981795828,0.6166965300594461,0.28269474336114875,0.08219142564409021,0.5353758572331152,0.6950435530011756,1.575661532813534,1.114945016491911,-0.8523176525082499,-1.4525979027650715,0.04748274861626989,-0.5191706928792739,0.98130869757586,-0.4853164097785112,0.38365017250319045,2.625406186076418,-0.09057319139393227,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.883333333333333,1.0,0.0,0.0,1.0,2.5106915564241707,0.017165180420831413,0.016734635694181696,0.9810611814562211,0.10500671513836085,-0.017612085836367093,0.16180964881048143,0.738581975993596,-0.15168785316818625,-0.07588266928020705,0.05201221894343705,-0.9545473808608613,-0.24691395008059272,-0.6365237689411656,0.04050014937964696,-0.01300749403140832,-0.38912177041232493,1.141830739344302,-1.3052755352395835,-0.2809082415862054,-0.8545442319309651,0.6125562591261013,0.28573494868086735,0.10397096873869296,0.5339954781142268,0.6697541084784953,1.5892729252296214,0.8861966133748427,-0.7945402816930436,-1.657623406783273,0.10813322605480291,-0.500309024420974,0.9442067893924988,-0.5158428263068626,0.34097537609386497,2.590955857669552,-0.23338092876459937,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.891666666666667,1.0,0.0,0.0,1.0,2.5168330888937547,0.018042553145700583,0.016280018543675636,0.9811429103416024,0.10583313190912784,-0.021236799101028096,0.1603338268760865,0.7138159984632217,-0.14650401926152787,-0.08146271846214893,0.03927122578817982,-0.8879930362506551,-0.2786403676077107,-0.6310506291414012,0.05381842071906598,-0.006643612802944894,-0.39550220813742565,1.1271371040138898,-1.3041010881004464,-0.28500476507966255,-0.8468366183563745,0.6080991496209984,0.2883776662960465,0.12537402327191607,0.5314861750870385,0.6432605377284006,1.6118809959876217,0.6239154268889552,-0.7367558976720978,-1.8751178431402593,0.17936558394694213,-0.48418382951468386,0.9042870302743755,-0.5613705616471387,0.28801420955587687,2.5349604825378713,-0.361007659749788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9,1.0,0.0,0.0,1.0,2.522755789762061,0.018884436903659034,0.015817630630014397,0.9812425271582683,0.10656446632286506,-0.024574046123244476,0.1587552634420673,0.6856392603629293,-0.13999371973296643,-0.08594900000573909,0.027389438237709562,-0.8168447233513271,-0.3104360299321976,-0.6258027599790256,0.06736483264610732,-0.002608903583259066,-0.40140103537352656,1.1105787752919642,-1.3022861088404678,-0.2889779720781168,-0.8394727814263921,0.603200083098649,0.29053518550679863,0.14622031011432415,0.5279786837850636,0.6158480244316489,1.644824261810703,0.325871619858014,-0.6788503697471537,-2.1049400573944954,0.26229757066753123,-0.4705571887854454,0.8618284716250479,-0.6217495787986227,0.22435026722017692,2.45755289153828,-0.4729646587673808,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.908333333333333,1.0,0.0,0.0,1.0,2.5284303609438012,0.019691067579323596,0.01534979758854269,0.9813627958400138,0.10720223492135099,-0.027604025376487665,0.15707565550394023,0.6544363484186456,-0.1323533216116764,-0.08935326793271271,0.01633378170495081,-0.740937126849644,-0.342606667556142,-0.6207864954008737,0.08123215841591103,-0.0012124191386446608,-0.4068163809665449,1.0920547697239815,-1.2997294619226543,-0.2928473848927533,-0.832472810495957,0.5977366566410214,0.2921168374163828,0.1663332381308874,0.5236034307742489,0.5878822753764923,1.6899775019838355,-0.010979245037927325,-0.6205067634467043,-2.34630179885734,0.35745489396481034,-0.4590313816445557,0.8170481962760268,-0.6963975720392734,0.14970762418048844,2.3595888164649876,-0.5699922415831016,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.916666666666667,1.0,0.0,0.0,1.0,2.5338318689517587,0.020462478717512632,0.014878178055131856,0.9815066821149765,0.10774765939345811,-0.03030578769515258,0.15529531252134945,0.6233097629251322,-0.1251166777863218,-0.09188293003932882,0.0024255161045612372,-0.6731683553431889,-0.37546437992845166,-0.616004722056084,0.09553112434583791,-0.002791891000557855,-0.41174281476430497,1.0714737453110086,-1.2963285272743876,-0.2966284951055261,-0.8258553114884584,0.5915934568979945,0.29303031257647344,0.1855467903887406,0.5184788130920119,0.5695988997024282,1.7351237949100484,-0.3309344364076548,-0.5511348651197079,-2.591860064792826,0.48213776991227864,-0.44451915296324973,0.7607980691142768,-0.7402622165860162,0.07586128492595101,2.2563645358388977,-0.6394527018445073,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.925,1.0,0.0,0.0,1.0,2.5389878667489536,0.02119215969755211,0.014401030331776442,0.9816769048004023,0.10818884555512719,-0.03276950538819781,0.15340074248718436,0.5971563045281525,-0.12028313945009306,-0.09418262067853825,-0.018606562897870327,-0.6322265906722155,-0.40900316054811914,-0.6112931804058332,0.1101508883310785,-0.006727993078772241,-0.41600196205187334,1.0488571019774344,-1.2916938324241163,-0.3002560374421408,-0.8197928426773857,0.5853989530312544,0.29338119216514863,0.20393931372820237,0.5129458857435071,0.5736498417684,1.7583733887261994,-0.5437892443032242,-0.45801974491429975,-2.8260601756893333,0.6563676141845276,-0.4213344530229901,0.6784309710122693,-0.6841694799351772,0.020031878477775322,2.172529335617947,-0.6655462006045587,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.933333333333334,1.0,0.0,0.0,1.0,2.5439615792204386,0.021875202129699553,0.013913595751849252,0.9818736657123974,0.10851585773944691,-0.03513256090633293,0.15137409409734912,0.5769044419494331,-0.11754201019114599,-0.09678895839899618,-0.04388251945335833,-0.6133539564860506,-0.4428591059734927,-0.606443891359944,0.12483734749127456,-0.011855045072278258,-0.4193764771795433,1.024372742382853,-1.2853890670379788,-0.3036507359892426,-0.8145481286382539,0.5801906322324082,0.2933641772177697,0.22175561264903973,0.5073863764152693,0.593696222913902,1.7615270610148648,-0.6587181485399688,-0.3481323925776092,-3.040009540224662,0.8664335411767565,-0.39292074019240286,0.5708905736971048,-0.5336885215460652,-0.021224131987640504,2.1116587324274043,-0.6623898896117963,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.941666666666666,1.0,0.0,0.0,1.0,2.5487941406273924,0.02251482727813547,0.013412468399095333,0.9820955196356792,0.10873357947415137,-0.03744273662762656,0.14920938469198736,0.5606879146795735,-0.1157898695587309,-0.09965833585735222,-0.06962386405538876,-0.6026310374884931,-0.47669701388247837,-0.6013982433572682,0.13950967268132625,-0.01770662888777172,-0.4218041685948335,0.9981902763070234,-1.2772532734045037,-0.3068047164453475,-0.810277999782434,0.57650414433882,0.2930274566320213,0.23913362593532578,0.5019060542499771,0.618776765100526,1.760032101215212,-0.7359119782690076,-0.23271925993620823,-3.234759488529917,1.090559468295238,-0.3638635091047904,0.44738181238475283,-0.33147669035407334,-0.058763812944873095,2.0647022315147816,-0.6529041475098429,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.95,1.0,0.0,0.0,1.0,2.553513641713696,0.02311287493877678,0.012896440025314199,0.9823412314138801,0.10884448093047717,-0.03971892113444814,0.14690470155588312,0.5473622806685848,-0.11478594839924991,-0.10262437106020318,-0.09561289663034717,-0.595181121951869,-0.5104002471049244,-0.5961309452749353,0.15417121584486143,-0.02412024471009505,-0.42325513151181343,0.9704600842406877,-1.2672130758997249,-0.30971512780765575,-0.807091765098508,0.574666020726507,0.29238478033535514,0.2561673165076194,0.4965046406234386,0.6463392586022265,1.7609540227220744,-0.8011096926360799,-0.1143502830757459,-3.41203071946772,1.3210045536899928,-0.33439938889992527,0.31196980912212124,-0.09549621940011299,-0.09529180420864258,2.0276954340792033,-0.6457938459046608,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.958333333333333,1.0,0.0,0.0,1.0,2.558141783257733,0.023669479040332536,0.012364835430510255,0.9826098133004785,0.10884879074840352,-0.04196881049858948,0.14445938703877467,0.5363727036769252,-0.11448734628549245,-0.1056532276537114,-0.1219604436747388,-0.5890501198839756,-0.5439751799279564,-0.5906259223805644,0.16885890639336082,-0.03105845709837305,-0.4237100066460959,0.9413230976492281,-1.2552365308430038,-0.3123780395936796,-0.805078502963732,0.5749125406821515,0.2914392598952106,0.27292854983664583,0.49114282348489946,0.6756431316072553,1.767084582949648,-0.8648195536572555,0.005993013448148954,-3.572609556719246,1.553897676130398,-0.3044345181041175,0.16656923633170617,0.16618547890261182,-0.13168164605598887,1.9987627243977801,-0.644461412878824,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.966666666666667,1.0,0.0,0.0,1.0,2.5626975808661623,0.02418384398439494,0.011816899583931425,0.98290039255136,0.10874552551114375,-0.04419541545144111,0.1418731625672644,0.5275110307902867,-0.11489398623133404,-0.10877791878042709,-0.14875987071699137,-0.5833946079945176,-0.5774432596837414,-0.5848702264148143,0.1836226255606889,-0.038533903937715976,-0.4231552479543443,0.9109165916287003,-1.2413147812975516,-0.3147890364427244,-0.8043156111596462,0.5774357787082172,0.290190086234422,0.28948002858091576,0.4857636170754582,0.7064236236272659,1.7795042572229598,-0.9311808269011363,0.12770221704042184,-3.7167635794773513,1.7869142536698135,-0.27394891608723326,0.012469457178330146,0.44930272164346974,-0.16825000623411968,1.9772691427181377,-0.6507151885421536,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.975,1.0,0.0,0.0,1.0,2.5671993932267494,0.024654740924072136,0.011251605682035625,0.9832121198014488,0.10853306278360615,-0.04639959600575672,0.13914589195848115,0.5207597648240703,-0.11602081156084512,-0.11206092876262402,-0.1760722672557058,-0.5778081045279904,-0.6108118522315709,-0.57885219532011,0.19851731068041015,-0.04657813754672532,-0.4215816363620889,0.8793770379912722,-1.2254546266151736,-0.31694385486180016,-0.8048706786774265,0.5824009193762093,0.2886350931246419,0.3058830355486148,0.48029757034253023,0.7385637865310923,1.798638844068909,-1.0016712559325065,0.2503014951326188,-3.844518076724517,2.0183411190041145,-0.24297783556828323,-0.14912323311574882,0.7509643699898216,-0.2050871819707034,1.9633168353859742,-0.6660455067471005,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.983333333333333,1.0,0.0,0.0,1.0,2.571666014799521,0.025080739059053187,0.010667601203890825,0.9835441196655362,0.10820939848482758,-0.048581067440337404,0.136277550012135,0.5162001620490589,-0.11788845849367646,-0.11557805907352361,-0.20394111176057245,-0.5720565642722807,-0.64406994154657,-0.5725608299726295,0.21359993962850404,-0.055228424869924415,-0.41898355636880064,0.8468412903499584,-1.207675762647483,-0.3188386670355291,-0.806800998378242,0.5899518515413809,0.28677196653491027,0.32220197583734866,0.47466285862967317,0.7719947869282806,1.8246429082803617,-1.0766038434620964,0.3733838826676361,-3.955819489150769,2.246681604715701,-0.2115832024342723,-0.31689831468430407,1.0686557286543374,-0.24217592790720555,1.9574290664138527,-0.6920007662220296,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.991666666666666,1.0,0.0,0.0,1.0,2.5761171992803535,0.02546030078414962,0.010063201722894054,0.983895466107361,0.10777225481614626,-0.05073879435483805,0.13326825433194395,0.5139543036111812,-0.12051474310678138,-0.11941047725839354,-0.23240095199138275,-0.5659720554399842,-0.6771895279898879,-0.565985615537972,0.22892802581841618,-0.06452153493776026,-0.4153585716509616,0.8134467131720927,-1.1880099332032452,-0.32047024156903803,-0.8101523172554982,0.6002118481871149,0.2845988276595218,0.338506853322179,0.46876422423882974,0.8066560528015554,1.8574980320430896,-1.155691262951514,0.4965810679979632,-4.050645110662536,2.470504299102525,-0.17984839766784222,-0.4893887415470388,1.3998217590721151,-0.27945269129794337,1.9603388732791915,-0.7302403064473073,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0,1.0,0.0,1.0,1.0,2.580573789149014,0.0257918196052728,0.009436408723144071,0.9842651699899431,0.10721913073042243,-0.0528711364794459,0.13011831568803042,0.49853048654639753,-0.11934654703534597,-0.11834403463786507,-0.25989112540138726,-0.5463702677539648,-0.7060344150308443,-0.5591165624259369,0.24455824016255553,-0.07448994591911631,-0.41070720523550125,0.7793305385055828,-1.1665006909957742,-0.32183614032999314,-0.814957477404026,0.6132822141925828,0.28211442167994455,0.35487429039200186,0.4624921868555514,0.8333126234033927,1.8414642633768281,-1.20505635400686,0.6058211134175595,-4.182489765976174,2.709177373643148,-0.018201842042920857,-0.6148300340226331,2.502373765150794,-0.33897609753616775,1.755033667304201,-0.5102441006174729,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.008333333333333,1.0,0.0,1.0,1.0,2.584780533669488,0.026061760364535662,0.008851323482935873,0.9846524028232496,0.10654469943810821,-0.05487085860301825,0.12687419561369195,0.5061156907017286,-0.12495125822218353,-0.1223181169157807,-0.2928192900574078,-0.5402993188055605,-0.7367912378384687,-0.5520970718145821,0.25961909687469664,-0.08460580750454126,-0.4052615530940023,0.7437385504058232,-1.1428569769758594,-0.3207736056030867,-0.8203994844892087,0.6419180776062948,0.27894922603391903,0.3677574144439157,0.4602601558952052,0.8751625639086114,1.893185345848409,-1.2835053447789688,0.7337803847709001,-4.233710679080485,2.9242125925047446,0.14508567873624645,-0.6516134169014087,3.529130878665543,-0.3749793144181479,1.413904718929484,0.009455433567537863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.016666666666667,1.0,0.0,1.0,1.0,2.589396540740678,0.026288708374791348,0.00818792160748465,0.9850562851575477,0.10572453804613045,-0.05695953044339977,0.12345869357257355,0.5474222313390581,-0.1398754355766464,-0.13583578237180283,-0.32982204159258205,-0.5551374982011159,-0.772565753230612,-0.5445305196941267,0.276111329260029,-0.09588170166543246,-0.39847753215598625,0.7087686938542413,-1.1177638144540285,-0.31941804568438903,-0.8258177010190495,0.6721010621703418,0.2758647664396421,0.3784393690408266,0.46264977741501034,0.9348400974411697,2.0493050026956774,-1.4126068984220486,0.8857383235095695,-4.165104979382255,3.0894959830225455,0.17525741231298575,-0.6299252230561136,3.66087890724889,-0.3731872459559926,1.1411847385704121,0.5556813302921204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.025,1.0,0.0,1.0,1.0,2.594356961949856,0.026466327894228786,0.007461914732570257,0.9854736058764498,0.10477522318888055,-0.05908617525076122,0.1198863988166177,0.5818285799981698,-0.15245799043127428,-0.14763500925405282,-0.3635723497330921,-0.55979692331769,-0.8067071217011342,-0.536516403523896,0.29377418025295793,-0.1081492558115754,-0.39049924770217614,0.6743201340827856,-1.091365377258817,-0.3178526487312036,-0.8308982382068106,0.702932726060443,0.27272943860131915,0.3867771600867559,0.46952151140007387,0.9854772775555354,2.1760019299532076,-1.5216102299777496,1.0236170946680856,-4.109058328547619,3.2405313017455484,0.1983492066739989,-0.5810809671040107,3.7103078774179976,-0.38508393522244333,0.8556557269782483,1.0818377574623794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.033333333333333,1.0,0.0,1.0,0.0,2.5996038247771414,0.026590828056208247,0.0066827171200958616,0.9859033811337488,0.10369549681405829,-0.061215232643867655,0.11616566748486748,0.6103413450550892,-0.1629548550577043,-0.15821911995875382,-0.39665430757414016,-0.5567256066822046,-0.8398271411960929,-0.5281058984015344,0.31237802809258247,-0.12124187216506162,-0.3814172472448515,0.6402843883784477,-1.063754959424936,-0.3161122255731557,-0.8355023838041163,0.7339395267939751,0.26944670085260136,0.3927002978237974,0.48068040670605,1.0306739137259502,2.277476249915057,-1.6117186574651823,1.1514858180671683,-4.064849304214076,3.3815589665430723,0.21754510618893996,-0.518469032030624,3.710856245870804,-0.40788186495720025,0.5655256114486729,1.5810333286233402,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.041666666666667,1.0,0.0,1.0,0.0,2.6050898827027904,0.02665970053160579,0.005857632176176205,0.9863447393756299,0.10248406087931247,-0.06331802823570314,0.11230271444755766,0.6340890338618859,-0.17166254776216583,-0.16774839228444238,-0.42919796777019753,-0.5470964229118543,-0.872093514049772,-0.5193385049617968,0.3317321177515422,-0.1350112334359951,-0.3713078174010567,0.6065726456792176,-1.0350060611497658,-0.31422689696138795,-0.8395393887406544,0.7647803301582897,0.26593140751869915,0.39620258694423377,0.49587206687712954,1.071496838021666,2.357876850495333,-1.685356550614758,1.2706427586424807,-4.0304171114399505,3.51445924271391,0.23336855128687994,-0.44648465811834237,3.6749276603516767,-0.4404637558175595,0.27761003304083487,2.0458891820637906,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.05,1.0,0.0,1.0,0.0,2.61077648925253,0.02667113338909746,0.0049936273958045285,0.9867968227245395,0.10114028438625124,-0.06536858593353148,0.1083033771784138,0.654019091001011,-0.17882890313109756,-0.17623678300895884,-0.46115692147291043,-0.531367771308427,-0.9034723959723218,-0.51024761776784,0.351675975600838,-0.14933114800864092,-0.3602398679341435,0.5731107698544485,-1.0051806387130375,-0.3122227497183744,-0.8429437947727554,0.7951883211331697,0.26210563825564204,0.3973271317078113,0.5147785597404465,1.1085723686553828,2.4206004257729807,-1.745291638034055,1.3818422684488807,-4.004109872235529,3.6402414400262573,0.2463183537516067,-0.3675954216417976,3.60991991397158,-0.4820139682911073,-0.0030445548269308897,2.469547117671852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.058333333333334,1.0,0.0,1.0,0.0,2.616632403835536,0.026623791204250118,0.004097877554125829,0.9872588157369627,0.09966408290649748,-0.06734195167816684,0.10417371488226326,0.670972890878334,-0.18466761002983578,-0.18366237441759808,-0.4924689670447834,-0.5097034417468035,-0.933870956751245,-0.5008622988175404,0.3720754581810919,-0.16409942740322936,-0.34827711292690866,0.5398374811419588,-0.9743353704826615,-0.31012159106552784,-0.845665979101351,0.824945662057816,0.257897841380514,0.3961518443637849,0.5370311855049937,1.1423667087503597,2.4686433463009405,-1.794369246223801,1.4856512087595897,-3.984394490227545,3.7591957840447487,0.25690119540990874,-0.2833919675311547,3.5209005156946516,-0.5317664654675125,-0.2730636072739545,2.8470284164102178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.066666666666666,1.0,0.0,1.0,0.0,2.6226330784346104,0.02651673882114906,0.003177843719749535,0.9877299772906695,0.09805583959471469,-0.0692134919884803,0.09992015216980535,0.6857132610284408,-0.18936190782872336,-0.19000765986991602,-0.5230705646939228,-0.48214745097557876,-0.9631938367651176,-0.49120817262200067,0.39282003137252036,-0.17923730211237093,-0.335479014454817,0.5067041950173228,-0.942527375645625,-0.30794106312820924,-0.847666994231608,0.8538699963947473,0.2532428638311835,0.39277607158657873,0.5622290333472835,1.1732531232653254,2.5046597648426827,-1.8352365997221105,1.5825479445563606,-3.9697476866927084,3.8709766199882467,0.2655914512476454,-0.19495941267940742,3.411605797573143,-0.5889309939530302,-0.5305877875874276,3.175606090303935,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.075,1.0,0.0,1.0,0.0,2.628759993110149,0.02634943265228281,0.0022411914327003252,0.9882096596884224,0.09631638315145541,-0.0709586172906174,0.09554945037756779,0.698908473549266,-0.1930587899211199,-0.195267553988142,-0.552896651269136,-0.44870387005910184,-0.9913636251805786,-0.48130808009645165,0.4138197875951366,-0.19468670406526453,-0.3219013138509693,0.47367501969708037,-0.9098190934828574,-0.3056950668780671,-0.8489153026460078,0.8818057586840351,0.2480823248146302,0.38730871457066113,0.589957953676726,1.2015290024679315,2.5308875661122543,-1.8701171433976511,1.6729548345246892,-3.9587011707439235,3.97473904252436,0.272797049546204,-0.10305993374647437,3.284834664703684,-0.6526700624368176,-0.775106881817621,3.4547379592400684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.083333333333333,1.0,0.0,1.0,0.0,2.6349996935554403,0.026121741384674928,0.0012956851386645783,0.9886973119040198,0.09444700367475085,-0.07255271856208939,0.09106861127764389,0.7111442888971952,-0.19586804222291126,-0.19945081745043303,-0.5818703936014429,-0.40936835347709566,-1.0183189885221096,-0.47118268924753515,0.4350014908077246,-0.21040592116899845,-0.3075964338794055,0.4407258421715907,-0.8762817249368857,-0.3033944456357725,-0.8493846597940492,0.9086172408064753,0.24236502945723654,0.37985762355628505,0.6198079993346179,1.2274097064362688,2.549153903782854,-1.9007259736624011,1.7572397203604884,-3.9498291126980756,4.069226013798222,0.2788404818074408,-0.008220727691963248,3.142691135638087,-0.7220665912526009,-1.007097408323343,3.6855565766308707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.091666666666667,1.0,0.0,1.0,0.0,2.6413433431556568,0.02583403044841563,0.00034908046441854847,0.9891924604100626,0.09244954519189641,-0.073971143846389,0.08648484109914499,0.7228571436478248,-0.1978519763543919,-0.20256063192207643,-0.6099087734493044,-0.36415701892163477,-1.0440211956396803,-0.46085125165584717,0.4563056859915175,-0.22636547029297122,-0.2926139851782945,0.4078445344854458,-0.8419986599195537,-0.30104772551460973,-0.8490523147742072,0.9341839442780032,0.23604788162708684,0.3705237577652721,0.6513838966205738,1.2510407742475504,2.5607292794654546,-1.9281725021747453,1.8357339947444085,-3.941936320141599,4.152997766374858,0.28394601735108105,0.08915359965960157,2.9865989250705693,-0.7961404048814735,-1.2279517008395235,3.870655708755859,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1,1.0,0.0,1.0,0.0,2.6477846276330137,0.025487148455772223,-0.0005908588122017319,0.9896946904140353,0.09032640173336443,-0.07518937316526136,0.08180537316945113,0.7343299439131751,-0.19902621220690342,-0.204585090746498,-0.6369129335626187,-0.3131109995626813,-1.0684488630609283,-0.45033200967674264,0.47768031213214884,-0.24254212953857754,-0.277000867300332,0.37502690350256407,-0.8070650954973048,-0.2986620120132545,-0.8478987664663892,0.9583938895576515,0.22909602270921198,0.3593917618756263,0.6843189278138823,1.2724907283457987,2.5663537516119175,-1.9530257421860575,1.9087271382829085,-3.934107110975499,4.224573078158382,0.2882337053044537,0.18871429264329942,2.8173928218626476,-0.8738423350313346,-1.4397039216158147,4.013596668119417,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.108333333333333,1.0,0.0,1.0,0.0,2.654319242286807,0.025082557663636363,-0.0015163766168736369,0.9902035976791819,0.08808068854968368,-0.07618303283848295,0.07703747760381835,0.7457460523370151,-0.19937214708040946,-0.20549747117307693,-0.6627613846385744,-0.2562916665394754,-1.0915853369071493,-0.43964307285008386,0.4990782485183828,-0.2589158993294055,-0.2608018662069127,0.34227608263585413,-0.771589108616914,-0.29624383042620217,-0.8459070765634855,0.9811404913090473,0.22148384270989793,0.3465286924050085,0.7182771744225641,1.291752644541888,2.5664052967968645,-1.9754721427606554,1.9764697791835313,-3.9255729610037093,4.282425810400974,0.29174052681200546,0.29014653982315064,2.6355055225556057,-0.9540009034844704,-1.644585036519971,4.118219556043486,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.116666666666666,1.0,0.0,1.0,0.0,2.6609437322921163,0.024622363858682182,-0.00241964423817687,0.9907187451222006,0.0857162781251783,-0.0769280379833649,0.07218839726769928,0.7571579264887986,-0.1988408095002957,-0.20524190904605633,-0.687324039168395,-0.19379196246859942,-1.1134242224110493,-0.42880279893437784,0.5204537337454299,-0.2754666652512551,-0.24405970431393983,0.3096006874858356,-0.7356913319906219,-0.29379966989972106,-0.84306299080267,1.002318981600245,0.21319600765113747,0.33198201126696014,0.752955920414607,1.3087735750998997,2.5608826855473987,-1.9953799503859604,2.03920603719174,-3.915785391352219,4.325104591273079,0.2944423306639743,0.39309920619163163,2.440986401090952,-1.0353209554939014,-1.8449784986772744,4.188503200588836,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.125,1.0,0.0,1.0,0.0,2.6676544673922336,0.024109351812375366,-0.003292666815234682,0.9912396118293423,0.08323786379333366,-0.07740070996777482,0.06726529616509935,0.7685092732992268,-0.19736269894051045,-0.20373301347253292,-0.7104600029889886,-0.12573186253513619,-1.1339660783157872,-0.4178301799317522,0.5417596266108394,-0.2921722318358382,-0.2268150989203837,0.2770129927799838,-0.699504032095696,-0.29133645824846927,-0.8393554231269583,1.0218235979938965,0.20422849345166624,0.31577905076038726,0.7880855610990447,1.3234608638707368,2.549514659837433,-2.012449644263987,2.0971788060114376,-3.904377597910627,4.3512684785854105,0.2962714779337938,0.4971546605119692,2.233602231075582,-1.116372157052807,-2.0432373637796832,4.228276884357716,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.133333333333333,1.0,0.0,1.0,0.0,2.6744468829501233,0.023547011250040304,-0.004127178158931143,0.9917655384134847,0.08065100395331885,-0.0775778847102835,0.06227522927081163,0.7796685471313513,-0.19485971946708958,-0.20085825348664857,-0.732023311969731,-0.05225706643252319,-1.1532113582880896,-0.40674511786986556,0.5629456447427205,-0.3090074926556549,-0.2091067242137492,0.24452772752065846,-0.663170190680865,-0.28886181193415783,-0.8347770797941372,1.0395456854515046,0.1945898050335907,0.2979280552039654,0.8234272018205689,1.3356972810870793,2.5318693299382833,-2.026318360825332,2.1506413577973573,-3.891078250854892,4.359674196685979,0.2971474178440425,0.6018266083154633,2.012943867656811,-1.1955636328788977,-2.241500352959475,4.240971075892923,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.141666666666667,1.0,0.0,1.0,0.0,2.681315050000861,0.02293954443134273,-0.004914523792193003,0.9922956692907037,0.07796212839993455,-0.0774370300275224,0.05722514851776414,0.7904469444104207,-0.19125539564080374,-0.1964801466016588,-0.7518711081654115,0.026460379719715252,-1.1711566158944453,-0.3955685585803009,0.5839574487764775,-0.3259442045162604,-0.19097107629042775,0.21216168859906895,-0.626842795484263,-0.2863840012844019,-0.8293249796550339,1.0553726624548434,0.18430243290368462,0.278420711544396,0.8587684123639268,1.3453592130157577,2.507426001316606,-2.0366389474072624,2.199871078573308,-3.8756632402763724,4.349173195891929,0.2970056740120075,0.7065573733186614,1.7784959360187091,-1.2711413126388056,-2.441601829116753,4.229511448107632,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.15,1.0,0.0,1.0,0.0,2.688251251320311,0.022291832706928937,-0.005645550177133544,0.9928288960573772,0.07517850843686316,-0.07695636760543555,0.05212190046193814,0.8006066878515918,-0.18648329153266024,-0.19043891354815295,-0.769871174259793,0.11022273382277667,-1.187791960912323,-0.38432246431960293,0.6047360780979972,-0.3429514751124426,-0.1724422062375274,0.17993334018271892,-0.5906839707493329,-0.28391171736729104,-0.8230011235721595,1.0691872843851498,0.1734041164896106,0.2572346913853529,0.8939190592890295,1.3523327761878934,2.4756249832416666,-2.0431495623817844,2.245179543296729,-3.8579442972949862,4.318730159971842,0.2958226319940116,0.8107172603213475,1.52967828771005,-1.3412111779244928,-2.6450408345349588,4.196297490442711,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.158333333333333,1.0,0.0,1.0,0.0,2.695245721433353,0.021609380203690493,-0.006310497177174809,0.9933638008592157,0.07230819449820416,-0.07611499033788355,0.04697225135017179,0.8098735921458335,-0.18049483218148993,-0.18255678456211405,-0.7859090782843783,0.19880887287732282,-1.203095596413706,-0.3730296789771693,0.6252178651638386,-0.35999669722262345,-0.15355141723548227,0.14786261697748584,-0.5548639594847323,-0.2814536240845017,-0.8158130253163448,1.0808673005833442,0.16194891327160973,0.23433669763548004,0.9287067038713053,1.3565278104368705,2.4359143224425095,-2.045723854377223,2.286917825959153,-3.8377587391222403,4.26744720736413,0.29364037725696956,0.9136214431568535,1.2658801844405465,-1.4037750832521974,-2.8529437672132487,4.143179961447461,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.166666666666667,1.0,0.0,1.0,0.0,2.702286462262081,0.02089822560632439,-0.006898897510617241,0.9938986021890842,0.06935991847223785,-0.07489297067988997,0.041782929755653446,0.8181522306809824,-0.173176832823294,-0.17036416034218432,-0.8001514989932984,0.3027546190367876,-1.2174780037553012,-0.3617136674789884,0.6453346501387057,-0.37704687268539633,-0.1343269091382082,0.11597069453068158,-0.5195598506265974,-0.2790177110796749,-0.8077740995195453,1.0902852874591589,0.15000786510207398,0.2096856285984654,0.9629720586464872,1.3581932132824837,2.386419285410528,-2.060039911100501,2.3252306827611293,-3.8192599299443315,4.180915044701833,0.2936596365858346,1.0216065221346105,0.9558287632709384,-1.4620438068371318,-3.0748825898174115,4.04988516916111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.175,1.0,0.0,1.0,0.0,2.7093569735598995,0.02016107249491153,-0.007361570788389704,0.9944379589150825,0.0663378280322334,-0.07318197749376858,0.03656277630333734,0.8249127874851594,-0.16433857391819273,-0.15141260475058205,-0.8124718128881852,0.4323536221980353,-1.2318721536892272,-0.35039312542246126,0.6649915199206807,-0.39433069574096513,-0.11479757252279678,0.08420828481174698,-0.4851820420730351,-0.2765592968080711,-0.7987862499474346,1.0967977799711932,0.13758151649099087,0.18308865447185652,0.9962047900239904,1.35752265219521,2.325441338813925,-2.1029387987986317,2.360958557294007,-3.806846690992383,4.043120972931747,0.2985462762310809,1.139228910102188,0.5691936237250772,-1.5188307207984288,-3.321941077540254,3.8989471777944207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.183333333333334,1.0,0.0,1.0,0.0,2.716431814989209,0.01940342166787687,-0.007652123422943219,0.9949850989472393,0.06324949681209113,-0.07087626600652704,0.03131627281606335,0.8288083009682665,-0.15394126463375385,-0.1281631243122446,-0.8221833596590844,0.5746101312432136,-1.2463948542091559,-0.3390882899424016,0.6840920057856045,-0.4120958526653735,-0.09497759984997474,0.052523249680808536,-0.45217450107773494,-0.27404193980915686,-0.7887869510178421,1.0997718478545768,0.1246940197554335,0.1543199439727945,1.0279545116097275,1.3540781738695384,2.2538885116086327,-2.1579869642948935,2.3959379326187547,-3.79675329904333,3.868351412070713,0.30414746458444664,1.2551686789383254,0.1414029796903682,-1.5653511486787077,-3.5865458392728122,3.7197843746063763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.191666666666666,1.0,0.0,1.0,0.0,2.7234802722869857,0.01863626648810182,-0.007767614741233499,0.9955339964977907,0.06010985806693661,-0.06797490827276671,0.026043782862042914,0.8290000723574276,-0.14221181862492743,-0.10361446749450016,-0.8290588311912725,0.7132900805464877,-1.2600336103272551,-0.32782515585796895,0.7025563284474913,-0.43029714514588,-0.07486527364581753,0.020929063161024816,-0.42070951853852323,-0.27149017239833034,-0.7778667719651292,1.099154496299366,0.11149233067967908,0.12331289048397631,1.05820119626743,1.3477049137441277,2.1722787790794085,-2.201176038100008,2.431342158400162,-3.7845567608668063,3.680551385958546,0.3066611709056477,1.3588610547423707,-0.28416784363635816,-1.590935017743732,-3.8542828697216898,3.5423001557563527,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2,1.0,0.0,1.0,0.0,2.7304726503890513,0.01786991727864228,-0.007712628760734359,0.9960757454297912,0.05693331856998046,-0.06450728136288077,0.020748909715738947,0.8255190584569534,-0.12949625463258968,-0.07836221467293972,-0.8333540292798958,0.8436743383065624,-1.2716592430590312,-0.31662654137999946,0.7202966521035946,-0.4487821199670403,-0.054455230543305366,-0.010552696333638235,-0.39083197797842584,-0.26893092029406274,-0.766139266772136,1.0950357171273042,0.0981784361263713,0.09008189614409967,1.086992847539,1.3387313901170494,2.080500054499539,-2.224865435672744,2.4673351445350145,-3.769441238461864,3.4906291324331185,0.3064472858650591,1.4493583059277948,-0.6968283347253079,-1.5912204036829658,-4.117060303186248,3.3697593056467268,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.208333333333333,1.0,0.0,1.0,0.0,2.7373823878396304,0.017113125185953485,-0.007492721846660751,0.9966005492679104,0.053732874260628456,-0.060512495483718884,0.015438954401539235,0.8185975403755044,-0.11614098275930791,-0.052620696145886305,-0.8353300617433461,0.9642745896833723,-1.2804562597473912,-0.3055129660226848,0.7372313293558169,-0.46737823574042575,-0.03374302123690063,-0.04189495748000626,-0.3625323663313046,-0.2663827176339127,-0.753710800199666,1.0875406907206109,0.08497199061829631,0.05469521876420551,1.1143638513615421,1.327429688350098,1.9798222684627276,-2.2287966397459713,2.5038153319189784,-3.7506284964810903,3.3030253781017027,0.30454893703368513,1.5278250655246528,-1.0939649431927023,-1.5654327552694312,-4.369390101123295,3.1998627310173466,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.216666666666667,1.0,0.0,1.0,0.0,2.74418600052826,0.016373023136147885,-0.007113646328173503,0.9970985599359884,0.0505200221877008,-0.05603300346246529,0.010123816215007578,0.8085115476747207,-0.10246869370266948,-0.02657657092544287,-0.8352620064730997,1.0745593402418843,-1.285910786543662,-0.29450271324083116,0.7532936899113067,-0.48592873062947317,-0.012724975011322392,-0.07306317127498974,-0.3357815550100641,-0.26385510467683465,-0.7406755156800584,1.0768029680740925,0.07208789020521411,0.017258727792044768,1.1403238930559558,1.3140953622960883,1.8721345964149871,-2.215221150725665,2.5407123880873503,-3.7271201404085654,3.1193544451881063,0.30198687710210503,1.5958697906826291,-1.4749374499417378,-1.5149093226798058,-4.607141021095702,3.0297041416087733,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.225,1.0,0.0,1.0,0.0,2.750863391495371,0.015655267215260667,-0.006581227943018557,0.9975603026756927,0.04730466332698256,-0.05111287033378983,0.004815167638583768,0.795542884656878,-0.08876985952899868,-0.00043744075898766166,-0.8334317588814837,1.1742754793829073,-1.2877384627779798,-0.2836113766510833,0.7684335726294,-0.5042985882525202,0.008602185231221873,-0.10401362648681568,-0.3105431255781695,-0.2613496030155443,-0.7271129703549555,1.0629583998882486,0.059723501906966216,-0.022090464920722853,1.164858920388355,1.2990638611672178,1.759396318267843,-2.186855594459194,2.578010052060844,-3.6977613784616303,2.9399553540422887,0.2995980234023554,1.6552014834344408,-1.8395525892429543,-1.4422936732479366,-4.8270196598385064,2.8568575500275273,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.233333333333333,1.0,0.0,1.0,0.0,2.757397262498864,0.014964167250049938,-0.005901621313074483,0.9979769609339707,0.04409524165880187,-0.04579705238177454,-0.00047444848993196607,0.779934715317168,-0.07530091632867442,0.025561615645636027,-0.8301066280969256,1.2632658900590277,-1.2858568286869938,-0.2728516488880442,0.7826169618824375,-0.5223763238704597,0.030241859189691675,-0.13469252758268357,-0.2867822991093593,-0.2588618042867954,-0.7130888242894844,1.0461437582533766,0.0480496623177485,-0.06319159987193035,1.1879381855564146,1.2826934925969236,1.6434531726267765,-2.1463711778088723,2.615738109029474,-3.661313116356647,2.764356821635238,0.29797574816080363,1.7074434233383862,-2.187679875754367,-1.3510451502346468,-5.0265151810075075,2.6796950990247437,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.241666666666666,1.0,0.0,1.0,0.0,2.7637726904357893,0.014302845474376059,-0.005081484720798651,0.9983405796489295,0.040898836496551176,-0.04013119478319902,-0.005732312393590798,0.7619054436672,-0.06228387680887254,0.05116547824005833,-0.8255412500169733,1.341390706061734,-1.2803374355822654,-0.26223315177446793,0.7958244588398463,-0.5400714412160014,0.052197820381713105,-0.16503551175942646,-0.26447051188424886,-0.25638334054619755,-0.6986555799659824,1.0264970686256758,0.03720608273638877,-0.10586571793751463,1.2095205053721008,1.2653580109808282,1.5259590350179786,-2.096079500058985,2.6539448583541896,-3.616458473017467,2.591583350505307,0.2974884370265851,1.7541052816865021,-2.519103291047591,-1.2449739632204222,-5.203718743808285,2.4973024020432844,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.25,1.0,0.0,1.0,0.0,2.7699767457400593,0.013673372688478992,-0.00412815050174465,0.9986442190551442,0.0377212490737165,-0.03416159288039169,-0.010946081017637837,0.7416565653786781,-0.04991011164780154,0.07610246134439737,-0.8199771294393323,1.4085031083783075,-1.2713703740195088,-0.2517623487050304,0.8080496124660704,-0.5573109822047762,0.07447427349559484,-0.19496683546630802,-0.2435892432676042,-0.25390366366968564,-0.683853736261376,1.0041587034025834,0.0273000962640748,-0.14992024560206843,1.229559892257136,1.2474402380673733,1.4083780701679505,-2.037874422835082,2.692675162695953,-3.5617587050699955,2.4202063498062336,0.29831247868542743,1.7965375400854722,-2.8334458658334682,-1.1278819891263427,-5.35722925231705,2.30939091599478,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.258333333333333,1.0,0.0,1.0,0.0,2.7759981888461405,0.013076867882001566,-0.0030497867405874686,0.9988820737697193,0.03456705756159306,-0.027935209009244497,-0.016104202385928065,0.7193823187935787,-0.03834526427755902,0.10008798216415823,-0.8136461842905586,1.4644438344132829,-1.2592310369538462,-0.2414424811400117,0.8192974266759788,-0.5740360149299194,0.09707573975997899,-0.2243981568439264,-0.2241337393874783,-0.2514114659014404,-0.6687132876312245,0.9792729708617847,0.01840804958428306,-0.1951528721427988,1.2480103539720138,1.2293309863332091,1.292009510664327,-1.9732437582434459,2.7319496465362363,-3.4956066278389515,2.2483398026818913,0.3004790599518581,1.8358914376435664,-3.1301172897364915,-1.0032917232979055,-5.486079335846244,2.116199565251211,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.266666666666667,1.0,0.0,1.0,0.0,2.7818272401047763,0.012513555628521642,-0.0018555435933498938,0.9990495651488402,0.03143963612051963,-0.021499693037606567,-0.021196199268086222,0.6952778395024267,-0.027734182231088547,0.12282909508496523,-0.8067750049390682,1.5090452240215468,-1.2442509607159522,-0.23127349893281024,0.8295831043104759,-0.5901983781755002,0.1200067676045321,-0.25322694593029055,-0.206116913222906,-0.24889567933715467,-0.6532555456339832,0.9519900819069752,0.010578567542443042,-0.24135490119950584,1.2648298850113229,1.2114302320543475,1.1780146353927212,-1.9033084758621244,2.771743725697244,-3.416190661878952,2.0736178030410652,0.3039236602395834,1.8730808152156864,-3.40827270418683,-0.8742672534774796,-5.589683442478771,1.9184011460591588,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.275,1.0,0.0,1.0,0.0,2.787455404777532,0.011982785126931053,-0.0005556761630871778,0.9991434110755585,0.028341144665134113,-0.014903374031288216,-0.026212841882136254,0.6695448958816675,-0.018204990704498616,0.14402999470475178,-0.7995880195862947,1.54214115000815,-1.226794674778961,-0.22125197727243925,0.8389310039325242,-0.6057578228609548,0.14327146852159972,-0.28133466787524225,-0.1895734426701272,-0.24634607156411403,-0.6374952740442964,0.9224684257920042,0.0038369286929917333,-0.2883142628507783,1.279983706406333,1.1941480448922288,1.0674392439118985,-1.8288731790684087,2.8119672168073695,-3.321480426411917,1.8931808870452538,0.3085302627033043,1.908745189267309,-3.6667775561216187,-0.7433207112392776,-5.667805437884788,1.7170137594968526,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.283333333333333,1.0,0.0,1.0,0.0,2.7928753361438154,0.01148302170445113,0.000838363840256539,0.9991616742441253,0.02527250217533333,-0.008195202045407688,-0.031146236397033206,0.6423956944776518,-0.00987177714685139,0.16339829904084882,-0.7923085913620564,1.5635803640009214,-1.2072431719456558,-0.21137103151793976,0.8473737583756742,-0.6206795978266404,0.16687288788465493,-0.30858495303715583,-0.17456389843881845,-0.2437535082920996,-0.6214431258128614,0.8908771226382816,-0.0018101109782115838,-0.3358183251642523,1.293446781002937,1.1779033775921854,0.9612297298305861,-1.7504777960824591,2.8524454582873644,-3.209240243873308,1.7036922629139701,0.31416558564126396,1.9432150318000851,-3.904173992490425,-0.6123889573880729,-5.720537456554241,1.513312887247804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.291666666666667,1.0,0.0,1.0,0.0,2.7980807307430697,0.01101182495818417,0.002313874155598884,0.9991037876595945,0.02223335831901388,-0.001424629577457394,-0.035989855905804405,0.6140560641237655,-0.002835640594044668,0.18065189430919734,-0.7851577893917445,1.5732409822559106,-1.1859829935634683,-0.2016202543125695,0.8549514994297006,-0.6349324527956625,0.19081222615972246,-0.3348220052731307,-0.16117857162156105,-0.24110997847009297,-0.6051083568476283,0.8573988592504971,-0.0063695539301428135,-0.383656553793349,1.3052055878604631,1.1631194406517227,0.8602425630515231,-1.6684416853394857,2.8929020029782473,-3.077074058287137,1.5014025324558307,0.32070184482584474,1.9764810482668094,-4.118644187905119,-0.48286103413899945,-5.748278074519191,1.3087398683191598,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3,1.0,0.0,1.0,0.0,2.8030662648094276,0.010565827875988802,0.0038568908886426868,0.998970554829199,0.019222076870710657,0.00535856722101326,-0.040738534020526206,0.5847695770091972,0.002815952657759427,0.19552625626095718,-0.7783510961870451,1.5710438896793213,-1.1633987536302959,-0.19198570750707772,0.8617111344265329,-0.6484869592489652,0.21508792126762571,-0.3598695206752748,-0.14954052289788794,-0.2384084775450022,-0.5885017750084146,0.8222330528398629,-0.00985779488052824,-0.43162295973957215,1.3152591121415897,1.1502148925979345,0.765247304706842,-1.582891856801416,2.932941615069553,-2.922503672789564,1.2822792243263192,0.3280289300973549,2.0081692333424317,-4.307966304626434,-0.3556371955267494,-5.751697496256692,1.1048055188593198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.308333333333334,1.0,0.0,1.0,0.0,2.8078275952903797,0.010140729261112804,0.005452224318895866,0.9987641221803789,0.016235741389833212,0.012104517454707704,-0.045388431073585145,0.554803930858816,0.00701145912331784,0.20778230916537271,-0.7720935628470635,1.5569630584968799,-1.1398665291345955,-0.18245000610260392,0.8677056211748146,-0.6613139837423527,0.23969458641088168,-0.38353039981962345,-0.1398072512161224,-0.23564282963513705,-0.5716388696252545,0.7855994208400565,-0.012296840522255303,-0.47951817873096053,1.3236190131747851,1.1395903977401878,0.676923214710905,-1.4937685159640024,2.9720311227198373,-2.74308048169433,1.042212303939662,0.3360580724402845,2.0375227357683734,-4.469459537217393,-0.23120377944212042,-5.73168049752315,0.9029919930966335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.316666666666666,1.0,0.0,1.0,0.0,2.8123614588459125,0.009731308693252408,0.007083544395218379,0.9984879224963306,0.013270190340641901,0.01876351623277486,-0.049936972563793286,0.5244603173365445,0.009699082225177895,0.21721490489585135,-0.7665739035006198,1.5310313550664048,-1.115745968666008,-0.17299253421140792,0.872993188005048,-0.6733831011816985,0.26462177331295633,-0.4055875287035136,-0.1321703178322269,-0.23280750967099745,-0.5545430627456084,0.7477420605529064,-0.01371119120456358,-0.5271509680316246,1.3303089786932003,1.1316102779469828,0.5958497500813809,-1.4008045519959844,3.0094753072346974,-2.536527141382532,0.7772953217058376,0.34471916090601185,2.0633903092667594,-4.599915982556031,-0.10971318237396853,-5.6892437578408614,0.7046603070886093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.325,1.0,0.0,1.0,0.0,2.8166659053039926,0.00933146999532811,0.008733516557739969,0.9981465901817561,0.01032008647660486,0.025286294561648076,-0.05438275228237607,0.4940856734260854,0.010851960103190554,0.22366182162445897,-0.7619577971253502,1.4933414421669278,-1.0913700883219493,-0.16358983480348754,0.8776364503428377,-0.6846607262756191,0.28985250819812663,-0.425805852175999,-0.12685232918769176,-0.22989751028670352,-0.5372490311374751,0.7089341544641227,-0.014125393561821445,-0.5743389080283082,1.335363351626262,1.1265791305334634,0.5224921022404394,-1.303481066959018,3.0443861096576375,-2.300898500617674,0.48416188395154214,0.353953159042783,2.0842198162445036,-4.695519288057324,0.008936636536740726,-5.625431805289232,0.5109739758113063,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.333333333333333,1.0,1.0,1.0,0.0,2.8207406967453696,0.008934316340086566,0.010383984587375673,0.9977458512512923,0.007379024515901565,0.03162427687543109,-0.058725391057468976,0.3588427225227236,-0.009072949003671317,0.2429032678832844,-0.7794690687509085,1.3812737108607769,-1.1029586098355397,-0.15421621536918353,0.8817013897090553,-0.6951077856310155,0.3153615418072503,-0.4439358370471415,-0.1241009530997012,-0.22690829035361773,-0.5198060658082,0.669483405751951,-0.013562247262284569,-0.6209081647864452,1.3388252116233887,1.2152097679833695,0.34482136767993277,-1.3668641766916823,3.0471539564337258,-1.1867961191459264,-0.6920680021685383,0.3965090765088858,1.9402976113275883,-4.685999441491798,0.15840687898387137,-5.811508970395656,0.45903041217815854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.341666666666667,1.0,1.0,1.0,0.0,2.8228275816710524,0.008408600463678135,0.012389098958904405,0.9972938643438954,0.00422007904712695,0.0372205801018621,-0.06325952745936576,0.2329614331996953,-0.026858683725083474,0.24478835516452618,-0.7775036196040521,1.291756889081464,-1.1046675788147664,-0.14333633867043138,0.8833834731375032,-0.7074417958871472,0.34063840747202206,-0.44558578749509775,-0.13838679589050074,-0.2232890256782221,-0.5049107376153487,0.6308341637725927,-0.011485278912090256,-0.6711973908682358,1.343013858495898,1.2723237617771976,0.31281424824654014,-1.7615465578396128,3.0082325886797046,-0.1092637662984608,-1.8928980540222469,0.4157872712816768,1.771159998629377,-4.636010260273287,0.2857853113439332,-5.977049490084085,0.38190546751931453,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.35,1.0,1.0,1.0,0.0,2.824825636483333,0.007948031752717124,0.014160358261425005,0.9967915292567201,0.0012566787169890513,0.04280808935150021,-0.067620527953421,0.22930383978978622,-0.020395578465621185,0.22358163978031104,-0.7431592506923033,1.2749609701051887,-1.0630221649062668,-0.13301081933956357,0.8869149605131643,-0.7244668949283424,0.3654987516185787,-0.4457568998187825,-0.15564925400007198,-0.21997850249892312,-0.4902867324977104,0.5922165680807295,-0.008799158739885682,-0.7205256562878466,1.3451903027487107,1.2213013150383398,0.5090459879587517,-2.2241074858370724,2.9553218929462157,0.02080496910303542,-2.084679302604957,0.3895076037782441,1.7644603860413588,-4.6170732882516585,0.3669787713692379,-5.809925749025511,0.12638843616112894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.358333333333333,1.0,1.0,1.0,0.0,2.8268718742041714,0.007526089430506864,0.01577610517828901,0.9962496330297156,-0.001613488969118893,0.04824113075005292,-0.07181127339526266,0.23545616503300903,-0.014845228016142513,0.20892496292444104,-0.7216065301447462,1.2266961599095592,-1.0227889327185167,-0.12298131675312572,0.8918675729368157,-0.7445102539844317,0.389893772354459,-0.44523903801004716,-0.1731314509339167,-0.21679723228191802,-0.47550306451465935,0.5538829423017317,-0.0053689660559362905,-0.7680294866853277,1.3451203324319168,1.1910556111179293,0.6630117459888951,-2.529978843313785,2.891034374357049,0.09593288210327566,-2.056465372868831,0.3745442121863407,1.7834291379480571,-4.552597413333029,0.45481406371559047,-5.574673060519098,-0.13141187649963193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.366666666666666,1.0,1.0,1.0,0.0,2.82899130970893,0.007128122489472633,0.01725243244567261,0.9956788984275796,-0.004411416470886956,0.053410470050425575,-0.07583793659530973,0.24408688523882457,-0.010164768747516054,0.19525284754041497,-0.7020691628517071,1.1554415380507326,-0.9840013254596943,-0.11315989248759808,0.8979651562796459,-0.7666332089835721,0.41368265785786285,-0.4441580184503946,-0.18992367688121917,-0.2137360989624841,-0.4605629135319094,0.5163399445251791,-0.0012189243446258406,-0.8134368739631649,1.3430001048070501,1.168941149447525,0.7910931402756716,-2.743746087164054,2.80959949813266,0.16605464393420588,-1.9531817162000453,0.3592657495171142,1.793748296356501,-4.421984232771693,0.5387093380885857,-5.315470890271071,-0.3628065801972191,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.375,1.0,1.0,1.0,0.0,2.8311927728239406,0.006744570994312466,0.018584526795474912,0.9950902225242215,-0.007147070024490441,0.05823596681910635,-0.07970533770254976,0.2544192114775998,-0.0060628789555711715,0.18087462860421374,-0.6831639831606776,1.0663621460829027,-0.9465151982773512,-0.10349896426233364,0.9050524586080769,-0.790239355437166,0.43672043065667,-0.44247146061114373,-0.20568447953725078,-0.21080946978996612,-0.44560725957538433,0.4801832050888702,0.003609522912206804,-0.8566206681898455,1.3390735560952964,1.1517733967415398,0.9035432057725967,-2.89341928211327,2.7105719011317633,0.2457803362100286,-1.8226190413087446,0.34200102011006706,1.783494902429098,-4.215891033688059,0.6176167420122527,-5.0437279682941565,-0.565194969537326,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.383333333333333,0.0,1.0,1.0,0.0,2.833485870794399,0.006367099012319539,0.01976200716845274,0.994494690774434,-0.009828384402479561,0.06265087738434677,-0.0834181074990293,0.26678654086869225,-0.0023596846474963143,0.1653683339305531,-0.6646159292929813,0.9618952203506624,-0.9103771242271527,-0.09396366920857242,0.9130242097091892,-0.81485686368546,0.4588588562100589,-0.4400616795135608,-0.22030066090303158,-0.20803608196064965,-0.43083799849142446,0.4460750939637114,0.009074688022245037,-0.8974990067680675,1.3335801886480947,1.1383742506298578,1.0050251568966484,-2.9900488546044657,2.5935029975970214,0.34186762110501645,-1.6848379651545515,0.32236776639287534,1.746299739806656,-3.925947456381781,0.6916277353540209,-4.763464715286195,-0.7392323635701903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.391666666666667,0.0,1.0,1.0,0.0,2.8358839178858495,0.005987648535673189,0.02077288788988696,0.9939034370382153,-0.01246277023950842,0.06659541412214785,-0.0869809645004485,0.28162298249787143,0.0010879731756714695,0.14862317657213214,-0.6463145604131308,0.8433777037397654,-0.8756470516195289,-0.08452606008516934,0.9218028778896877,-0.840073503013907,0.47994548061662035,-0.4367736669260601,-0.23376511228982663,-0.2054366736834182,-0.41650226391194006,0.4147507474825072,0.015136651834773819,-0.9360117467779487,1.32675301670246,1.1279987563229834,1.0984502188886291,-3.03976029733662,2.458001131287463,0.45748668002271176,-1.5492677871235583,0.3001392717882573,1.676915632443331,-3.54322926768044,0.7609649112428186,-4.477054743612396,-0.8853921589233105,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4,0.0,1.0,1.0,0.0,2.8384033168136122,0.0055982793711337785,0.021604487697359048,0.9933274404447162,-0.015057454540364812,0.07001408238960331,-0.09039854816895679,0.29923063467998406,0.004398722353543272,0.13056484922737321,-0.628191146626468,0.711624530445523,-0.8423362963063333,-0.0751636899365227,0.931331713357333,-0.865519535307737,0.4998255417315166,-0.43243690151318226,-0.2461217906884242,-0.2030337607641787,-0.40288940461736894,0.3870212728357041,0.02175743654295868,-0.9721165858282741,1.3188236526660395,1.1200298520374827,1.186135036150977,-3.0473082591919765,2.304003456029602,0.5936663314251844,-1.4201446035903504,0.2750983078387692,1.5705853040168405,-3.0589874725643242,0.8258633814961582,-4.186683634306423,-1.0034477599841995,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.408333333333333,0.0,1.0,1.0,0.0,2.8410623067411214,0.0051911127249982935,0.02224341800786469,0.9927773206986107,-0.017619666722335572,0.07285397779691755,-0.09367516668821353,0.3197606075346109,0.007658409732017826,0.11105725944806008,-0.6102183771824998,0.567032484622353,-0.8104054032418324,-0.06585889588454463,0.9415717951588707,-0.89086197400044,0.5183455382171137,-0.4268792280689737,-0.25743418901633247,-0.20085170188610538,-0.39032584217832605,0.36376762293976844,0.028901041526376455,-1.0057898073497225,1.31002888736939,1.1139554552791282,1.2701250915813334,-3.016838571965288,2.1319174345059366,0.7500887581849025,-1.2984967204932873,0.24702273096248006,1.423602474683059,-2.4659415348529414,0.8865863087984228,-3.8946971719469037,-1.0922680522437078,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.416666666666667,0.0,1.0,1.0,0.0,2.843879830697642,0.004758166478032359,0.02267510977304231,0.9922631630836308,-0.02015695818864566,0.07506299285659683,-0.09681456182426867,0.34108863289569075,0.010540835266576606,0.09379372940054431,-0.5949187066491118,0.43141632995144086,-0.7785964933572737,-0.05659776568187056,0.9525004648836886,-0.9158001781738251,0.5353574989732822,-0.41993542221010055,-0.26776340269664567,-0.19891671524813737,-0.3791626967059846,0.34592224725482174,0.03653387502293239,-1.0370282053607225,1.3006191851286444,1.1121196148983736,1.343736805627529,-2.9809250831627443,1.958920720869537,0.9048683102454691,-1.1982710071584657,0.22297016338878373,1.2706983176793152,-1.8752386465566029,0.9431391936637693,-3.5782719068755675,-1.2021265093941746,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.425,0.0,1.0,1.0,0.0,2.8468486764513017,0.004293737651310766,0.02295353246829154,0.9917808978649726,-0.022679220140958488,0.07677090067405011,-0.09981248642044209,0.35997402609894524,0.012799053018316617,0.08431298125427095,-0.5846329928881548,0.33663580656262615,-0.7455989637655871,-0.04732356896957174,0.9639674085859962,-0.940544058719819,0.5509942168982727,-0.41179808956488256,-0.27740537246897357,-0.19713553249629232,-0.3691475368836708,0.3325136454971584,0.04462002808743928,-1.0654276724643152,1.2899934455461537,1.1167100635833063,1.3950091683610633,-2.983075659892076,1.810638465375889,1.027298865734071,-1.1411250267424433,0.2116920354438434,1.1734950148363654,-1.4703862779229726,0.9939224994666817,-3.213586708613372,-1.4001297565604753,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.433333333333334,0.0,1.0,1.0,0.0,2.8499509745715588,0.0037999818419356215,0.023163000182896246,0.9913180853216592,-0.02518648223472647,0.07819098446559904,-0.10266579173502882,0.3767827037017423,0.015155570196052688,0.08140636869855687,-0.5762340056250819,0.27638463333049335,-0.7126301364246748,-0.03798593128881546,0.9757506176897063,-0.965518105838693,0.565534806729547,-0.40281377444786604,-0.28678215314235306,-0.19538851465740664,-0.35960444645871187,0.32141580928943886,0.05309925001404375,-1.090587983837612,1.2772836891859698,1.1238375832330492,1.4253266689896416,-3.0136004228405944,1.684357039198967,1.1231560025646492,-1.1219400074084618,0.20764499214468934,1.1363116376603921,-1.2464356115780517,1.0360778925556766,-2.826000925441572,-1.659633362243742,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.441666666666666,0.0,1.0,1.0,0.0,2.8531869918366346,0.003283690974925316,0.02333429326251983,0.9908709245780924,-0.027667784660296447,0.07939785565583357,-0.10538161625303889,0.39332891990080576,0.018136508901343523,0.08102079307278989,-0.5668062977794244,0.22828498757331644,-0.6810094213807194,-0.028592942582354255,0.9877228530691569,-0.990770732433829,0.5790668342182554,-0.39307882285547174,-0.29610437259244793,-0.19367478262721416,-0.35020900958933093,0.3117397186375242,0.06188799296336722,-1.1125276878883414,1.262332889508758,1.1302281491634882,1.4425903405119223,-3.0428226544059145,1.5651768592130821,1.2112378500127552,-1.1204046470828544,0.20285092344758837,1.1268703123704171,-1.096375088443251,1.0687623821785621,-2.443847263633536,-1.9237804710879125,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.45,0.0,1.0,1.0,0.0,2.856560348685349,0.002748680625111368,0.023479370029433996,0.9904389606017844,-0.03011722129835745,0.08041701877200347,-0.10796629751717043,0.4101706534137526,0.02154615266232804,0.08165592030857736,-0.556624537034897,0.1840632609523207,-0.650584284380981,-0.01914879546942399,0.9997937900315716,-1.0162318167454583,0.5916210877164317,-0.38262647694765345,-0.3054555639270673,-0.19200766593328017,-0.3408232745858716,0.303142891148718,0.07091195638368646,-1.1313187715648376,1.2452206813345046,1.1364667408847575,1.4500634695629389,-3.0612601114197724,1.448467804454554,1.2967272279762687,-1.1255771228108236,0.1965810770034726,1.1292985436613112,-0.9739284969636208,1.0933154790624933,-2.0719549779080237,-2.173140412252832,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.458333333333333,0.0,1.0,1.0,0.0,2.8600760799272122,0.0021961756737028737,0.02360297504320503,0.9900231231261785,-0.032532700166111324,0.08125484118285288,-0.11042413631859208,0.4275869538632841,0.025183865915410095,0.08261770798527898,-0.5459758720003977,0.13984720727063352,-0.6209228561253187,-0.009651830234274966,1.0118905775618725,-1.0417917342908252,0.603207964292498,-0.3714667023892006,-0.31486399130596165,-0.19039843134382295,-0.33138736719497575,0.29550757702146385,0.08010991761440878,-1.1470602708534752,1.2261138826378775,1.1429392211891949,1.4495100663863347,-3.0652537400015323,1.3319359023795352,1.3819725769028013,-1.1322006041980015,0.18905013665356463,1.1359163775401382,-0.8569128564828665,1.1110699548738097,-1.713372790135299,-2.399124942568993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.466666666666667,0.0,1.0,1.0,0.0,2.86373988601042,0.0016254380034287448,0.02370530463647063,0.9896254186839245,-0.034913747862559026,0.08190511579528456,-0.1127568752325357,0.4456704246246459,0.02892284075301009,0.08356971684120475,-0.5350338076320054,0.0938703969434167,-0.5916570962409101,-9.980844960407702e-05,1.0239522911380106,-1.0673193790788171,0.6138200194227573,-0.3595936006659401,-0.324325573997034,-0.18885683032238743,-0.3218913349602026,0.2888610102073369,0.08942978896491662,-1.1598749847337593,1.2052352656250214,1.1497404770446493,1.44191427272371,-3.053871350351689,1.2145595464753,1.467768997979516,-1.1374562953078127,0.1805461883374715,1.143066174061661,-0.7349891854622104,1.1229255601835186,-1.3702456952649955,-2.5982781893821905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.475,0.0,1.0,1.0,0.0,2.8675569675305135,0.0010351289584950756,0.02378585627820928,0.9892479342858436,-0.03726107208920955,0.08235983344623841,-0.11496518974428857,0.4642680556618836,0.03274407525061662,0.08456797838283706,-0.5240587703406773,0.04679698852731998,-0.5628416677452628,0.00951051104980252,1.0359224821072677,-1.09268959013002,0.6234506234004197,-0.34700388575620866,-0.33382159622775853,-0.1873893282048651,-0.31233626429394806,0.28325775726376035,0.09882534361746742,-1.1698976991078918,1.1828092461481743,1.1570249808650785,1.4273770573640743,-3.029128435288637,1.0975758188839468,1.5527489756788226,-1.1402452454603007,0.17140934585673395,1.1516632470676402,-0.6115128844156403,1.1292763044180734,-1.04321528537759,-2.7733809521557617,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.483333333333333,0.0,1.0,1.0,0.0,2.8715307011272357,0.00042492957959492283,0.023846598816856322,0.9888917813336614,-0.03957579940704689,0.08261845129697103,-0.11705123842749235,0.48320059975404833,0.03664888833222578,0.08563897620411652,-0.5130221931452432,-0.000922016622966676,-0.5345812956327641,0.019183941231480567,1.0477419087607451,-1.1178048530002944,0.6321129497374898,-0.33371445107129305,-0.34332966142137233,-0.18600000789144186,-0.3026969475090753,0.27866912880040956,0.10825106070521784,-1.177261906156719,1.1590122497557587,1.1646353114853576,1.405894026810075,-2.992579743935009,0.9818532133792535,1.635703133906835,-1.1393877850307743,0.16162677318689866,1.162752647447295,-0.48973435826199285,1.1302102426681413,-0.7327878219396577,-2.9267166293630087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.491666666666666,0.0,1.0,1.0,0.0,2.8756635519036036,-0.00020562281337774312,0.023888277382245363,0.9885583063572413,-0.0418581166718411,0.0826765900691842,-0.11901661419884421,0.5023840858645658,0.04060225689794961,0.08664004094286172,-0.5017498809968488,-0.04990098877873689,-0.5067699910413508,0.028921099574558483,1.059354049220769,-1.1425659191956035,0.6398148436234072,-0.3197421668577614,-0.3528113926449381,-0.1846955486517501,-0.2929570535031598,0.2750955179593938,0.11766218099526977,-1.1821108294735527,1.1340306356587908,1.172219227016236,1.3777160708182823,-2.9443443119710233,0.8670939849364312,1.7164134181617086,-1.133156160096096,0.1510547583840488,1.175543209166745,-0.3672143208737444,1.1259586678118523,-0.4398305714641637,-3.0577653407887473,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5,0.0,1.0,1.0,0.0,2.8799570711429667,-0.000857040352068862,0.023911232223341877,0.9882488438730774,-0.044108258363959416,0.08252847237605336,-0.12086246470651352,0.5229172890850957,0.04481631605357374,0.0884674825064442,-0.4882046551545477,-0.11405049997803181,-0.4806637365553855,0.03872092834841783,1.0707038432743832,-1.1668772581998115,0.646564516153097,-0.3051075607685979,-0.36221559742297393,-0.18348242858504105,-0.2831045606896295,0.2725488901191805,0.12701703850208204,-1.1845924156811218,1.1080494940759462,1.1771574913986889,1.3385917364439504,-2.853358758891953,0.7386570925172631,1.796199871691706,-1.084618912877089,0.1353862079068785,1.1854201208301673,-0.20456395304122021,1.1141926713438075,-0.1638083309183891,-3.1460636616942894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.508333333333333,0.0,1.0,1.0,0.0,2.884434724454983,-0.0015296807365499444,0.02392820284684405,0.9879734040233001,-0.0463247526325945,0.08205258380171408,-0.1225966709485061,0.546253690532964,0.04933809890734295,0.09171592342591153,-0.4709870231657758,-0.2101295290807525,-0.457456442301792,0.048540391097869964,1.0816639114948348,-1.1901218985104693,0.6521257951653616,-0.2898055023295663,-0.3708883745262229,-0.18243911185330214,-0.2732000514893237,0.27168611874204013,0.1362320588509999,-1.1848409683221925,1.0815962412972193,1.1773271175889386,1.2854636214162163,-2.685454022482534,0.5805326503101549,1.8766445488726513,-0.9504683663709823,0.11055925249773113,1.183763751629533,0.05214351169796627,1.0937833844760931,0.09398788573883543,-3.163408766054303,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.516666666666667,0.0,1.0,1.0,0.0,2.8891231800026973,-0.002228479864314477,0.023948202043970263,0.9877433378320594,-0.04851429326411161,0.08110322548076936,-0.12422450939388663,0.571443672692535,0.05358146476743912,0.0946962647802066,-0.453086889469396,-0.3278230988266011,-0.43551955912364654,0.05834304697490014,1.0921282369646534,-1.211634825241187,0.6562400603249329,-0.2738301516207204,-0.3780567368624903,-0.18163977437674553,-0.2633751648291373,0.2734179486474799,0.1452467615766836,-1.183025950918808,1.0553260146417078,1.1758096253970143,1.2251210961039494,-2.4712592923550414,0.40741818134149677,1.9552363501031433,-0.7580274353406424,0.08160165432044064,1.169338173612674,0.38301215191282045,1.06987840714577,0.32874358737651654,-3.1200801771802578,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.525,0.0,1.0,1.0,0.0,2.894023562271572,-0.002961152991972128,0.023963567703253964,0.9875606280280464,-0.05068883042273022,0.07964736829627554,-0.12574158088232767,0.5965609157038548,0.05719462335755396,0.09596738923486198,-0.4366547568445808,-0.44907911796957917,-0.4131658944920917,0.0681372181878202,1.1020825964299006,-1.2313095533830534,0.6589160981877199,-0.25721822982784726,-0.3835221651152336,-0.1810790842812948,-0.25371108192911246,0.2780696546072538,0.15406336563676273,-1.179361908532584,1.0295949050108817,1.1748954033334242,1.1630796372845387,-2.253712438919977,0.24029765333194897,2.0271475781015473,-0.5511105238660652,0.053555130731197664,1.1511035318514418,0.7309555296219461,1.0459352732640703,0.5381990187362451,-3.042767650738507,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.533333333333333,0.0,1.0,1.0,0.0,2.899126358999583,-0.0037317781987943107,0.023967245479236222,0.987423447033713,-0.05285351297980828,0.07769066905554987,-0.12714402209913647,0.6207589247825818,0.0602372172273358,0.09534582368883862,-0.42103687580965343,-0.5684991745034605,-0.3898505950470952,0.07792463703045721,1.1115128975860624,-1.2491966992231867,0.6602450212137987,-0.24004435865236126,-0.38724191226025806,-0.1807471888645589,-0.2441901059649466,0.2856005408078457,0.16267901613108476,-1.1740559672732038,1.0046132204627327,1.1734820214570705,1.0989510143049852,-2.0435440011947525,0.08452371945611992,2.089526059530771,-0.3404968692228716,0.026568845311973344,1.1371495395752524,1.0683367256939036,1.0214980647269556,0.722867105306424,-2.9412102759639502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.541666666666667,0.0,1.0,1.0,0.0,2.9044191588396373,-0.004543533503917566,0.023951674597906283,0.9873293726732523,-0.05500896644622705,0.07524404582922886,-0.128425297486521,0.6437783637237074,0.06272653078567589,0.09278450034671291,-0.4057114796085536,-0.6849345617156273,-0.36496164620270144,0.08769525187877138,1.120398446668317,-1.2653686200696326,0.6603248268453219,-0.2223927955023344,-0.3891971129356148,-0.1806362701927619,-0.23475858960285825,0.2958752667021522,0.171088333382212,-1.1673141234441435,0.9805747337448159,1.1705644556665036,1.031808907273204,-1.842369790398859,-0.05915938077253324,2.1411284183494734,-0.1276701849456885,0.0006416962884675526,1.131456453502231,1.3851084002251635,0.9965134804161502,0.8834188678954114,-2.8175872826770387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.55,0.0,1.0,1.0,0.0,2.909888656449728,-0.00539887488738516,0.023910395824856573,0.9872753413819445,-0.05715433625278828,0.07232229873482292,-0.12957726364013783,0.6651820557988936,0.0648804082362283,0.08885588696679284,-0.3908920722138298,-0.7944341149446841,-0.33920811284473673,0.09743404462489894,1.1287097127072825,-1.279902862396501,0.6592590315342565,-0.20435888501320337,-0.38936974867601953,-0.18073649392641777,-0.2253324984065761,0.3086856808115984,0.1792875741380206,-1.159332319474947,0.9576534324181154,1.1663085367476398,0.9596514457545613,-1.6536576388228896,-0.18702875521524165,2.1782278658849044,0.08574434254327912,-0.024166513140223556,1.141688703319148,1.6581932107686614,0.970539784553951,1.0237633037670202,-2.683425475368888,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.558333333333334,0.0,1.0,1.0,0.0,2.9155184125306493,-0.006294372436667682,0.02384616880390486,0.9872545917062222,-0.059288024876383016,0.06896872780250181,-0.13060097950098035,0.6846419024623894,0.06692315075147064,0.08414149113930053,-0.37644615568520223,-0.8937235170560518,-0.3134062287885777,0.10713372749123204,1.136392637430893,-1.2929295807166807,0.6572076809250679,-0.186088997737586,-0.3877680405598935,-0.18103904541176563,-0.21573044454753912,0.3235118202149632,0.18726399645811118,-1.1502514017146932,0.935850975822001,1.160614764729048,0.8806986011395601,-1.479525591041586,-0.2967272151521638,2.198225448707622,0.2979423127194081,-0.048207080246291945,1.1733930219661877,1.8697790691318772,0.9428584318123201,1.1477202430069022,-2.54907487140283,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.566666666666666,0.0,1.0,1.0,0.0,2.9212927402647355,-0.007226302482062984,0.023761694165726002,0.987260754486683,-0.06140495540724616,0.06522458040165938,-0.13149672320366768,0.70223526233564,0.06889510200319743,0.07871423448421505,-0.3618967858581947,-0.9829614114962107,-0.28734030335155614,0.11677762403704973,1.1433880227262752,-1.304561622247194,0.6543135779483871,-0.16772179420140967,-0.3844040434640294,-0.18153994526385597,-0.20577594804047297,0.3398486652971297,0.1950018813348926,-1.1402036487581653,0.9151688512280682,1.1527429660848494,0.7945460201666465,-1.3184013344935064,-0.38991808371773296,2.2020535306625684,0.5080642462427332,-0.07171683191779299,1.2251992095019293,2.022608348563252,0.9134252628371359,1.2564539946566367,-2.4151180874978406,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.575,0.0,1.0,1.0,0.0,2.9271970773343594,-0.008190524672565725,0.02365979118450945,0.9872876585920699,-0.06349943252460657,0.061131468887149105,-0.13226429893428004,0.7180567361870118,0.07084630102429051,0.0726589477914525,-0.3471643303458904,-1.0620426093436761,-0.2608731333534887,0.12634611025931286,1.1496350711003371,-1.3149029362915725,0.650709046196439,-0.14938810555987653,-0.3793003031225146,-0.18223432594372885,-0.19531045772250696,0.3572219593576841,0.2024877508387301,-1.1293105018037493,0.895599007697037,1.142382444947456,0.7011245494930618,-1.169350572413097,-0.4678605485750009,2.1907919330902352,0.7145686158512621,-0.09456452518626868,1.2946312270769755,2.120877250603179,0.8825199330036554,1.3511788430481886,-2.282699146585667,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.583333333333333,0.0,1.0,1.0,0.0,2.9332179137618244,-0.009182553285857428,0.023543145333357784,0.9873294462651311,-0.06556536762975887,0.05673154479801353,-0.1329032690727132,0.7321931065711892,0.07282116405286307,0.06603949486668054,-0.33219865632745227,-1.1308686026106436,-0.2339060485245794,0.13581733145284067,1.1550734318844929,-1.324050798454079,0.6465159021388037,-0.13120859531657242,-0.37249456653317503,-0.18311602068362712,-0.18419876092252338,0.37519661947384936,0.20971054688495352,-1.1176840013740288,0.8771238654516404,1.1292823674457808,0.6005725261976247,-1.031633877211866,-0.5318538682036844,2.1657834609253737,0.9154544481152915,-0.11658221638412958,1.3786956687083758,2.1696145973362713,0.850431764302359,1.4329191660197393,-2.1528792394220186,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.591666666666667,0.0,1.0,1.0,0.0,2.939342619600937,-0.010197623522664144,0.023414067621006875,0.9873807190400816,-0.06759637502237519,0.05206730962196505,-0.13341304666509704,0.7447159743340432,0.07485626906774104,0.058899899469255494,-0.3169580583349141,-1.1893978978294542,-0.20635755557288554,0.14516748305007587,1.1596446132036309,-1.3320968342451036,0.6418448150597109,-0.11329171454445364,-0.36404272898725976,-0.18417736288346434,-0.17233219657736737,0.39338220264662194,0.21666161357710276,-1.1054285157034203,0.8597176870400034,1.1132247088739555,0.49316826782618506,-0.9046023840975836,-0.5832600304028124,2.12860242520072,1.1084132220152199,-0.1375737731686405,1.4741407992444295,2.174290044194486,0.8174477526057355,1.5025051207672746,-2.026550299600618,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6,0.0,1.0,1.0,0.0,2.9455592596354903,-0.01123076517177468,0.02327431145574428,0.9874366704708579,-0.0695858654965261,0.04718135365671699,-0.133792933294881,0.755678353635996,0.07697903809897286,0.051270431991963517,-0.3014060227029938,-1.2376518964076157,-0.17815580223375546,0.15437107660073993,1.1632929030149293,-1.3391275048557054,0.6367949016320902,-0.09573188822989376,-0.35402101283292137,-0.18540891690310446,-0.1596297476017829,0.4114347868770908,0.22333467609504912,-1.0926422493612409,0.8433480271249635,1.0940220767444904,0.37927423096135726,-0.7876519309922436,-0.6234706292773606,2.0810224564893205,1.2909016420727148,-0.15730957788609223,1.5776781438320153,2.1404215034176235,0.7838473279307617,1.5606055562530097,-1.9044547337676243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.608333333333333,0.0,1.0,1.0,0.0,2.9518563860481284,-0.012276863226454549,0.02312496687401099,0.9874931947009181,-0.07152711800349798,0.042116110225521704,-0.13404213915394592,0.7651104938850882,0.07920752374542216,0.04317570276837119,-0.2855064107059266,-1.2757095857611849,-0.14923665628550037,0.1634011843291507,1.1659658503863202,-1.3452243664283077,0.6314536379050882,-0.0786080069362983,-0.3425277016193812,-0.18679918918156588,-0.14603756084683378,0.429055894370249,0.22972573570928212,-1.0794184230992034,0.827976774810543,1.071514496870496,0.2592863973853454,-0.680196535139248,-0.653873191056582,2.024978513074392,1.4601947417406858,-0.1755262484864134,1.686133569926207,2.0732900765246454,0.7498907851731201,1.6077683805912102,-1.7872376144395807,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.616666666666666,0.0,1.0,1.0,0.0,2.9582228099127006,-0.013330698149117219,0.022966436073958374,0.9875469689002291,-0.07341332559283505,0.03691362610923363,-0.13415980042044442,0.7730230670617678,0.08154923641232406,0.034640827206315804,-0.26922740103875925,-1.3036973469879634,-0.11954778551773396,0.17222965154858152,1.1676143429713517,-1.3504641137746929,0.6258970151144805,-0.06198224634532056,-0.32968443380390994,-0.18833435437787802,-0.1315275214363461,0.4459896214858349,0.23583285584793445,-1.0658461096847207,0.8135607335509705,1.0455804595216218,0.13359215411462788,-0.5816355113826344,-0.675807009284537,1.9625561327067031,1.6133944506341547,-0.19192100753636032,1.7965407086581016,1.9777780773583786,0.7158183016077507,1.6444574511116095,-1.6754835605493779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.625,0.0,1.0,1.0,0.0,2.964647454022372,-0.014387023164112785,0.022798442459672937,0.9875954984821199,-0.07523768683297002,0.03161539465646522,-0.1341450285274184,0.7794096303444179,0.0840001178507739,0.025696509479288338,-0.25254489002133057,-1.3217836566322716,-0.08905278441114811,0.18082752532117774,1.1681923862882306,-1.3549182916180182,0.620190187750346,-0.045898738057853244,-0.31563779410881193,-0.18999787264050522,-0.11609521570253209,0.46201886232622197,0.24165604073607796,-1.05201079891401,0.8000520488013867,1.0161469172397886,0.0025381246122302414,-0.4913251829988008,-0.6905317817296486,1.895977103406325,1.7474452058377798,-0.20614847321704155,1.9061811509475324,1.8583142214609727,0.681850035331445,1.671081211365375,-1.5697399652417743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.633333333333333,0.0,1.0,1.0,0.0,2.9711191655706406,-0.01544061734590289,0.02262010270492575,0.9876371399627488,-0.07699347102521056,0.02626216526085359,-0.13399695467266076,0.7842418187876792,0.08654418654915182,0.016385244552646477,-0.23543806122526884,-1.3301862083911602,-0.05773169075971345,0.189165433502578,1.1676566450482222,-1.358652866824673,0.614388152085653,-0.03038262795521515,-0.30056034703994694,-0.1917701622648287,-0.09975783558722057,0.4769615251768511,0.24719702310345854,-1.0379947561619645,0.7873984007969409,0.9831859055424302,-0.13360062593791078,-0.40855286161221915,-0.6992247870195478,1.8275466368132816,1.8592183113414895,-0.21782611462396295,2.0125807292033904,1.7189015825684695,0.6481790520217928,1.6880154993717333,-1.4705374890134082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.641666666666667,0.0,1.0,1.0,0.0,2.977626492140295,-0.016486328422160555,0.022430054122442814,0.9876711003081803,-0.07867407514427593,0.020893707800400153,-0.1337147728960055,0.7874738811109628,0.08914961201231399,0.0067614636434677605,-0.21790404772316213,-1.3291668638329976,-0.025585748130041212,0.19721395708021824,1.1659657091892655,-1.361727505978222,0.6085364413000202,-0.015439627444298554,-0.28465082225312044,-0.19362830788423793,-0.08255220354914225,0.49066722203569646,0.2524590249364412,-1.0238772072578144,0.7755430906511632,0.9467418886251572,-0.2746507905976614,-0.33250589359058225,-0.7029438044803382,1.7596351600357405,1.9455284379237114,-0.2265197700742877,2.113495968967966,1.5631742473981713,0.6149922756896775,1.695615780689339,-1.3783884106817457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.65,0.0,1.0,1.0,0.0,2.9841575385674,-0.01751920386305721,0.022226546333988243,0.9876973950818743,-0.0802731977005804,0.015548673432193634,-0.133297817813988,0.7890408610868904,0.09176772049427857,-0.0031051027028218825,-0.19995777899949096,-1.3190382353171046,0.00736185994897955,0.20494446497966395,1.1630791318715945,-1.3641946317178493,0.6026724220109807,-0.0010553752879528084,-0.26813487307455175,-0.19554549176606684,-0.0645329027710878,0.5030144293001539,0.25744689436495316,-1.0097344931504755,0.7644252606189118,0.9069331760773097,-0.42055951389507573,-0.2622469064325106,-0.7026266329068331,1.6946188891828635,2.003228101851217,-0.23174725134909757,2.2068941729402436,1.3944664404545337,0.5824722469180099,1.694229892613539,-1.293788106593996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.658333333333333,0.0,1.0,1.0,0.0,2.990699700311449,-0.01853453129940505,0.022007636554348585,0.9877168016463341,-0.08178489371571976,0.01026430215161007,-0.1327456025895438,0.7888550374438197,0.09433253911745598,-0.013126460770649405,-0.18163045774933406,-1.3001704855395468,0.041068280366858,0.21232951001484007,1.1589563839576809,-1.366098287752097,0.5968259974182396,0.012804020708749168,-0.25126368722226683,-0.19749076207338956,-0.04577063400013819,0.5139083293766054,0.262166895718408,-0.9956400423809221,0.7539799555412633,0.8639473781365781,-0.5714140454480976,-0.19669141651212918,-0.6990984335482886,1.634797332565168,2.0293372385903012,-0.23298372570422,2.2909286456049287,1.2158840825562889,0.5507977414421539,1.6842087647953852,-1.2172200485526052,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.666666666666667,0.0,1.0,1.0,0.0,2.9972394493109076,-0.0195279517779184,0.021771342711172734,0.9877307776217302,-0.08320373351387605,0.005076226213732259,-0.1320578721456296,0.7868101301648704,0.0967594388286583,-0.023198379599401717,-0.1629797063457873,-1.2729822123715888,0.07547178144435697,0.21934358794860692,1.1535555644474595,-1.3674728219930514,0.5910207814518426,0.026191246921466658,-0.2343125857647134,-0.19942855386113717,-0.026350758677672316,0.5232791640094254,0.2666268567223224,-0.9816643470705524,0.7441382598097017,0.8180529222882932,-0.7274533145344764,-0.13459638381796868,-0.69305397309541,1.5823390463625293,2.0211091219114192,-0.22965511383327586,2.36392207412499,1.0303542781405706,0.520159863600973,1.6659099848282333,-1.1491525440795014,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.675,0.0,1.0,1.0,0.0,3.0037621129322485,-0.020495546930473972,0.02151581625750508,0.9877413668475938,-0.08452492176176307,1.8264925208303484e-05,-0.1312346352366279,0.7827831281093519,0.09894824528511567,-0.033200384476495315,-0.14408490627750736,-1.2379350583816537,0.11049753488104629,0.22596372538631163,1.146832162048773,-1.3683415608157299,0.5852750978666494,0.039176338148124656,-0.21757853519040984,-0.20131834730394416,-0.006371932764721701,0.5310809006789482,0.2708362267784242,-0.9678748759671182,0.7348274131399383,0.7695817691952866,-0.8890598307069242,-0.07456527923214828,-0.6850709725754212,1.5392071193513233,1.9761363589848358,-0.2211504674648318,2.4243576651498664,0.840652375730091,0.490755943034179,1.6397019941761815,-1.0900390954421368,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.683333333333334,0.0,1.0,1.0,0.0,3.010251692018754,-0.021433914664686034,0.021239498671285866,0.9877510939999826,-0.08574440247072027,-0.004877727541170526,-0.1302761740338495,0.7766406478932543,0.10078817799382983,-0.04299895302569934,-0.12504426995840695,-1.1955177431865427,0.14606545406433,0.23216995076852837,1.1387379006023441,-1.3687155766469206,0.5796029319089189,0.05184469891065538,-0.2013769797816328,-0.20311439498555103,0.014055202408158787,0.5372900369382603,0.2748061224395587,-0.9543359805009494,0.7259709415523328,0.7189097625634844,-1.0567385336275636,-0.015071849078971411,-0.6756192618586909,1.5071060790619675,1.8924121522760446,-0.20683373962754104,2.4708769230297185,0.6494036620027255,0.46278390314241746,1.6059623092998487,-1.0403139697586838,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.691666666666666,0.0,1.0,1.0,0.0,3.0166907550352327,-0.02234022020659542,0.020941243782870815,0.9877628559852967,-0.08685892857610113,-0.00958193142074211,-0.12918302308245413,0.7682491567049563,0.10216588653471975,-0.05245302977570611,-0.10596795120218921,-1.146222219005105,0.182100754818839,0.2379455547623697,1.1292198531549802,-1.3685927583003794,0.5740147768356713,0.06429477279915745,-0.18603833265247577,-0.2047655762977365,0.03480934928577361,0.5419042950456603,0.27854929183079785,-0.9411088374787874,0.7174888469772935,0.6664266038738947,-1.2310734487268515,0.04548972247123029,-0.6650760305784398,1.4874572555733936,1.7683400340919238,-0.18606200647481252,2.5022870613730004,0.45905431062084334,0.43642900836466825,1.565070020369923,-1.0003812017126323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7,0.0,1.0,1.0,0.0,3.0230604526422526,-0.023212210811006183,0.020620384998547594,0.9877798187795754,-0.08786607908177234,-0.014066514289084401,-0.1279559101192187,0.7574896282358108,0.10297645062205893,-0.06142220634795822,-0.08696791997521458,-1.0905119490453676,0.2185469065709615,0.24327706083309328,1.11822000979023,-1.3679574146057334,0.5685183313992782,0.07663565317021194,-0.17190464588010074,-0.2062154284267979,0.055759986764375456,0.5449409421152743,0.2820799392456365,-0.9282514801614506,0.7092979215237889,0.6124973955380764,-1.4126619624371095,0.10872597541322637,-0.653746003261253,1.4814139907999837,1.6026748460794649,-0.15820938405119833,2.517579331243374,0.2718096115305868,0.41184405146760694,1.5173920488532877,-0.9705944625920315,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.708333333333333,0.0,1.0,1.0,0.0,3.029340699775879,-0.02404818453432583,0.020276727461304756,0.9878053283831202,-0.08876420959556665,-0.018305437223350655,-0.12659565269374773,0.7442768442334327,0.10313685225481112,-0.0697775144521631,-0.06814525998032739,-1.0287836069922118,0.2553803684446067,0.2481538446880043,1.1056754871143617,-1.366780658710159,0.5631190101146504,0.08898500597915718,-0.15932708521781802,-0.20740239936525648,0.07676900480649651,0.5464344552378367,0.28541335935525797,-0.9158189699978992,0.7013122726007597,0.5574183760089474,-1.6020275665663464,0.176135957709751,-0.6418856834783737,1.4899215906567642,1.394390978201111,-0.12269592296515974,2.515960578319768,0.08953772836433282,0.3891243996779059,1.4632635799384341,-0.9512255558605576,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.716666666666667,0.0,1.0,1.0,0.0,3.0355105716355477,-0.024846907006230743,0.01991044913958413,0.9878428434322925,-0.08955232709372304,-0.022274091173843085,-0.12510300657533793,0.7285833312193317,0.1026011043130456,-0.07741445621421313,-0.04957588167702845,-0.9613244206202707,0.29262632894197643,0.25256736709990907,1.0915195503474575,-1.3650218153105709,0.5578202366746386,0.10146767968115801,-0.14866479624341555,-0.20826036047621724,0.09769266306970492,0.5464332375880132,0.28856534590693494,-0.9038637538291434,0.6934441622594463,0.5013701234509876,-1.7995140850447289,0.24897517206842856,-0.6297304927498137,1.5138162259502843,1.142494266672991,-0.07902043428303862,2.4969014041893165,-0.0863627021800073,0.3682800200708469,1.4029638400361688,-0.9424195332156438,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.725,0.0,1.0,1.0,0.0,3.0415489565513663,-0.025607474558089732,0.019521900913924597,0.9878958947649229,-0.09022988593450679,-0.025948750882741158,-0.12347846418947585,0.7104676803963843,0.10137602546571724,-0.0842676652209421,-0.03129572493116786,-0.8882678015828447,0.33037458392507646,0.25651001341218743,1.0756835856969496,-1.3626310725090185,0.5526235019021535,0.11421527641166192,-0.1402855141066015,-0.20871940660330712,0.11838402820965178,0.54499507686817,0.2915513596897721,-0.8924362393306298,0.685605280380499,0.4443715368676593,-2.0051661514083907,0.3280942918789753,-0.6175233866912788,1.553943736874078,0.845817900308799,-0.026796238461691546,2.460204911874494,-0.25513290014879786,0.3492068739598775,1.3366885449691068,-0.944134622974877,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.733333333333333,0.0,1.0,1.0,0.0,3.047435501970013,-0.02632912628871041,0.019111302391602532,0.9879680741020586,-0.09079650775034112,-0.029305844490489206,-0.12172200382106807,0.6901064286051729,0.09953654534751319,-0.09032646583101483,-0.013286295646560309,-0.8095496837783942,0.36879454868103895,0.2599735593810367,1.058100114490651,-1.359553577112588,0.547528180229784,0.12736674196239264,-0.1345678312382689,-0.20870696445057876,0.13869607826761315,0.5421810225855332,0.2943854604729329,-0.8815856114129916,0.677708585209865,0.3862375419979125,-2.2186026369315526,0.41375497990099763,-0.6055433082579764,1.6112662871029846,0.502864032037732,0.034210703516532326,2.40609882552777,-0.41686296757823094,0.3316598910322177,1.2645197180192813,-0.9560662244884544,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.741666666666666,0.0,1.0,1.0,0.0,3.053151875502251,-0.027011010694096123,0.018678335996070525,0.9880630502521236,-0.09125163131565696,-0.032321045829627366,-0.11983279394756985,0.6678272580789805,0.09723920292619942,-0.09565043933007139,0.004538981944650022,-0.7248674315506752,0.4081479488035873,0.2629473057788193,1.0387068750814237,-1.3557351561773352,0.5425311134311872,0.141069714530045,-0.13190444690597264,-0.20814922821136492,0.1584856753017813,0.5380473607418661,0.29707902454030904,-0.8713609106969751,0.6696708433056914,0.3265434757561325,-2.438893615653206,0.5054252039933527,-0.5941313736940512,1.6869146388464136,0.1117659198562243,0.10404120475497325,2.33534895096628,-0.5727356864463196,0.31522951103736707,1.1863925745602222,-0.9775579096654652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.75,0.0,1.0,1.0,0.0,3.0586833313664914,-0.027651914357445042,0.018221647043607746,0.9881846068723666,-0.09159409985729236,-0.03496820326924633,-0.11780886372449895,0.6457924786263494,0.09531311869443379,-0.10019118398827603,0.024874680893447715,-0.6489667204242814,0.4484933412963805,0.26541595064363893,1.0174518875630976,-1.3511298237126987,0.5376259906682165,0.1554819859431662,-0.13270506590733183,-0.2069729443713292,0.17761856078371782,0.5326354278114279,0.299639285656889,-0.8618124018369879,0.6614159533821072,0.25737238815403796,-2.6608969078294997,0.6255432703222663,-0.5921622350581757,1.7634899679024547,-0.2600346400574671,0.17387559896168192,2.2604307597254354,-0.7025383579827627,0.29701145403259965,1.0952446698768648,-0.9671196516667546,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.758333333333333,0.0,1.0,1.0,0.0,3.064049408680943,-0.028246341159872186,0.017742236712213796,0.9883335710854272,-0.09181557330526947,-0.037347002453885565,-0.11563673366177525,0.6271791089840565,0.09459966328264105,-0.10409833745238406,0.05056621695831161,-0.6034095703768965,0.4893891489625628,0.2672368455813866,0.9943585932842653,-1.3453094350052974,0.5326617428468843,0.1704612139950859,-0.1362383575735971,-0.20525130156200355,0.1961595212972052,0.52633838810882,0.30202921544085237,-0.853106832865694,0.6535521824445788,0.16963866513565184,-2.873386583105997,0.8027792259997568,-0.6100980267771217,1.811044306780062,-0.5055028417339574,0.23152774502284534,2.2005010340586364,-0.777215670597089,0.27469286374036783,0.980267550201126,-0.8626702087251226,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.766666666666667,0.0,1.0,1.0,0.0,3.0692900428654553,-0.028791472785458037,0.017241868885555463,0.9885069904538104,-0.09191204149509588,-0.0396119129750392,-0.11330049780439537,0.6123025882686157,0.09463678974860834,-0.10787457581231363,0.07917070599400879,-0.5827668157882583,0.5303486820749872,0.26824326172923313,0.9695621111779976,-1.3377501699460361,0.5274576902219311,0.1856660577228339,-0.14113011326956446,-0.20311414862094845,0.21429357801802842,0.5196818333014764,0.3042175000525618,-0.8454746093336358,0.6470381165700219,0.06902288646733701,-3.0690799276232217,1.021793894872669,-0.6415198754657325,1.82999209426709,-0.6353221897250244,0.2804810683237491,2.156437140368023,-0.8090849851025195,0.2514112247337208,0.842679537252935,-0.6727491779157502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.775,0.0,1.0,1.0,0.0,3.074428567061083,-0.029290630831938697,0.01671962905367634,0.9887023026095929,-0.09188920114185989,-0.041815801680608944,-0.11079517253891655,0.5997801163398016,0.09482873554587484,-0.11174902572696885,0.10795263308805936,-0.570953723361881,0.5711747169970361,0.2683872270225089,0.9432072611572117,-1.3282795367574196,0.5219697449224554,0.20096108223287074,-0.14682706073568083,-0.20057661708994107,0.23210014030333892,0.5128536383571114,0.3062194025197477,-0.8390621739114784,0.642339696145983,-0.036133817869591356,-3.248039396957272,1.2548785750888491,-0.6765130438925349,1.8387830231368507,-0.7195331579547676,0.32892689507659556,2.1199375133510663,-0.826588889895743,0.22970594243590603,0.6897937632587325,-0.43847262863474734,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.783333333333333,0.0,1.0,1.0,0.0,3.0794804855284545,-0.029745407063697837,0.016174926525029484,0.9889176943067637,-0.09174923959621868,-0.043978091594219414,-0.10811937097656807,0.5889529297215378,0.09520661897842993,-0.11569235234402434,0.13695528299528534,-0.5623764245465424,0.6118027635061937,0.2676410314314066,0.9154281212287098,-1.3168355270278886,0.5161824728237222,0.2163124414417814,-0.15312233256881058,-0.1976320337030052,0.24962586990721286,0.505905351803214,0.3080459324264936,-0.833978046612657,0.6397302394261094,-0.14431763206185666,-3.411177308248954,1.4926404839824992,-0.7129553500361019,1.8460712488145499,-0.7872316324036144,0.37844373020667177,2.088345706785022,-0.8412244603609953,0.20901099636087217,0.524898792760693,-0.17610230045629338,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.791666666666667,0.0,1.0,1.0,0.0,3.084458576813178,-0.030155742930484928,0.01560703428078614,0.9891517222727709,-0.0914918941014917,-0.04610564258384733,-0.105272851963829,0.5796094741014998,0.09585966474890023,-0.1197225374274879,0.16636026173802368,-0.5548915471480174,0.6522293844485285,0.2659819331548113,0.8863543060197291,-1.3034021953577113,0.510087155755187,0.2317289363797799,-0.15994758794240774,-0.19426922158649654,0.2669059020830893,0.49883323068442814,0.30970291912576225,-0.8303138606988002,0.6394046578050447,-0.2550376113949737,-3.5588370298210625,1.730996408426697,-0.7503333212430441,1.8554755199925694,-0.849940327433743,0.4293500337562661,2.06087737663638,-0.8579158677342447,0.18887531772141752,0.34965767232492784,0.10742170121688766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8,0.0,1.0,1.0,0.0,3.0893752317651693,-0.030520776923135536,0.015014972223533945,0.9894030504784367,-0.09111574531254536,-0.04820036152223314,-0.10225580574896537,0.5717534906300165,0.09684332013207007,-0.12388480031138983,0.19626602242104244,-0.5476394526772885,0.6924432381460449,0.2633904045748237,0.856114170731692,-1.2879855868874437,0.5036769174696715,0.24723703344165757,-0.1672880046927063,-0.19047619980706743,0.28397382618448586,0.4916067540076433,0.3111938543885172,-0.8281504187405748,0.6415206011130575,-0.36789830499552534,-3.6911136553907586,1.9678670268388077,-0.7884899378900578,1.8684844307351485,-0.9119869470430991,0.48168352754680843,2.03763829583841,-0.8793083102328436,0.1691255926783286,0.16530924854563978,0.40845738028425504,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.808333333333334,0.0,1.0,1.0,0.0,3.094243474924864,-0.03083935377700357,0.014397520029572685,0.9896703177775652,-0.09061888076196244,-0.05026208291655637,-0.09906868112848166,0.5654816933442319,0.09818309993216165,-0.12823467595683827,0.226711633664928,-0.5402500675314719,0.7324125036492805,0.2598502947382192,0.8248357450965498,-1.2706044115770645,0.49694565679035274,0.26287034355869904,-0.17514737039312606,-0.18624116279404973,0.3008665403470628,0.4841780921805474,0.3125216790037344,-0.8275587065563729,0.6462122808097823,-0.4824785467773418,-3.8080617864738375,2.201950484888946,-0.8273399351570687,1.8856726889694115,-0.974719977329005,0.5354041881309424,2.0191605542523874,-0.9073038426259761,0.14975255976164448,-0.02693248507685153,0.7243998017790299,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.816666666666666,0.0,1.0,1.0,0.0,3.099077346131813,-0.031110262254632336,0.013753255950250082,0.9899520769313984,-0.08999919376286981,-0.052289675387381794,-0.09571217450917541,0.5609203034588887,0.09988294452442499,-0.13282980767665342,0.2577046900475224,-0.5325415044266563,0.7720868258123179,0.255349095461868,0.7926464742904614,-1.2512864121392946,0.489887918550387,0.27866491159114776,-0.18353333764818971,-0.18155279667155172,0.3176265020886923,0.4764850232972104,0.3136897303845446,-0.8285992934918557,0.653593931142708,-0.5983294180160642,-3.909808321624164,2.4322554143394237,-0.8667976488798645,1.907180506197772,-1.038200308705255,0.5904491582653026,2.006158978684959,-0.9435747335874645,0.13083848083687455,-0.22575933264313175,1.052827632624651,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.825,0.0,1.0,1.0,0.0,3.1038919294284955,-0.03133233930915141,0.013080600782712485,0.9902467678681046,-0.08925452094367875,-0.054281466962339146,-0.09218726355876428,0.5581884526172682,0.10192806226963817,-0.13772500733562665,0.28923484752827694,-0.5244039962211964,0.8114011074871773,0.2498781377712848,0.7596722730694804,-1.230066821338074,0.48249902930902167,0.2946566853286619,-0.19245070887154697,-0.17640034348962802,0.33430252332514543,0.46845184662075634,0.31470232035101564,-0.8313213621004251,0.6637594080201932,-0.7149801477014295,-3.996620595947551,2.657939542437684,-0.9067553135731132,1.93288767664901,-1.101874861493568,0.6467573523834524,1.9993881273328062,-0.9897042332601347,0.11252814985292292,-0.4297552786265335,1.39119755122729,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.833333333333333,0.0,1.0,1.0,0.0,3.1087031531154543,-0.03150451920967124,0.012377867007239593,0.9905527067003932,-0.08838271903809368,-0.056235406303664325,-0.08849525016614933,0.5508818687474775,0.10280882673080857,-0.13828708485349456,0.3215463747620133,-0.5074303652377637,0.8436869776305206,0.2434327596668442,0.7260361310246689,-1.2069874197653332,0.4747753299908351,0.3108797062019646,-0.20189791867308252,-0.17077350746516085,0.3509496375442391,0.4599899527428748,0.31556519954876,-0.8357618814689646,0.6767805569964962,-0.8237223735968757,-4.096182680198044,2.8965494458572927,-0.9430432596281191,1.9289906183453143,-1.1366739503945866,0.728875802639089,1.6374551115028935,-0.5981047477696222,0.004667312484543107,-0.5354236299770054,2.483908937264334,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.841666666666667,0.0,1.0,1.0,1.0,3.113409573232957,-0.03161735891747352,0.011709936016063563,0.9908676581622535,-0.08737043245230318,-0.058085381164329056,-0.08469817020820193,0.5638721764155359,0.10850372158251327,-0.1474505312002453,0.35748264595810236,-0.5153910544318681,0.875417177147891,0.2361494315446702,0.6914025617328463,-1.1817909972404526,0.466781641648553,0.3268065289677505,-0.21139527471145675,-0.1642524134456432,0.36159344185019365,0.4584834341579293,0.3147801088924247,-0.8402450892667085,0.7051578903079321,-0.9460622246622102,-4.110760368854587,3.1176512906891896,-0.989418970272633,1.9823325484217347,-1.1652248715036995,0.7910723864803892,1.1172155370743786,0.14916987084771183,-0.10133365281601137,-0.5485895920157557,3.527391224085459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.85,0.0,1.0,1.0,1.0,3.118471175849796,-0.03168140411449639,0.010900017122491132,0.9911802700106384,-0.08621800488288328,-0.06010562264386327,-0.08071828852676319,0.5987636472313606,0.11884274813072297,-0.1679758392510502,0.3944492391941483,-0.5504375062574697,0.909784717028877,0.22766505592247402,0.6575234582104258,-1.1550265649205134,0.45828501381962455,0.3439185820089935,-0.22131833319814417,-0.1575889676904877,0.3695698964954787,0.4624761172570033,0.3138763053351598,-0.8449050413358938,0.7355704107312538,-1.0807988784718559,-4.030250982479382,3.3045686910666072,-1.0434493441419201,2.1033121470615734,-1.1977347551377688,0.8103899580079554,0.7964120948373365,0.7836866698212541,-0.11270894329156289,-0.54889244706261,3.7129109805017046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.858333333333333,0.0,1.0,1.0,1.0,3.123818898280461,-0.03169096327356785,0.009980829741121435,0.9914863826531913,-0.08493804149132579,-0.062243159534471744,-0.07659028144895878,0.6263188065922165,0.126973546990672,-0.18505721127575261,0.42831073867255154,-0.5738742874785426,0.9388355102512046,0.2181361169034726,0.6242317120248566,-1.1267148523893424,0.4493908192461877,0.3618617314187767,-0.23135752063041956,-0.1507459141455106,0.37486697676414926,0.4715448786549502,0.312901626504232,-0.849393296717752,0.7670397399829605,-1.1996798037909306,-3.9693145116991,3.4886966737464675,-1.0872000705441254,2.188269750092046,-1.202766046285045,0.8349994681148587,0.4739693294026093,1.3714911877588487,-0.11951355866232305,-0.5175060263033759,3.805331656929074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.866666666666666,0.0,1.0,1.0,1.0,3.1293908064020015,-0.03164444414239706,0.008972094391692985,0.991784155398548,-0.08353227698396087,-0.06445562059443286,-0.07233270889648169,0.6474457210936646,0.13310418694017823,-0.19974392301943816,0.46079219850193787,-0.587600143014386,0.9650791749490489,0.2076703925259585,0.5913682163487741,-1.0968816203580722,0.44016501264388913,0.3803897445105276,-0.2413644339695616,-0.14367230988857338,0.37746938531885554,0.4853343037196508,0.31188441269078776,-0.8535301417742834,0.7989926050134051,-1.3068515524595625,-3.926290891001327,3.6696018181901646,-1.1239202925169889,2.247663838971279,-1.1950060959809201,0.8659888962895035,0.15241079805770386,1.914344570687565,-0.12298854879602805,-0.4680539440292586,3.8372446078113964,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.875,0.0,1.0,1.0,1.0,3.1351346610344186,-0.03154140049018342,0.007889017628077174,0.992072510294182,-0.08200226054373562,-0.06670512958559563,-0.06795726062346279,0.6632681967225412,0.13753420873365796,-0.2123897832671987,0.4920924132387123,-0.5923595450074132,0.9895950469629557,0.19635525769581322,0.5587935305081678,-1.065554822086173,0.43065881437090453,0.39932279540163135,-0.2512742888967682,-0.1363127658740189,0.37740715673177766,0.503450621499743,0.3108518173576315,-0.8571941957849063,0.8309938167798171,-1.404269827960259,-3.898916598360642,3.8470204983134826,-1.1550455744489008,2.2881831791752463,-1.1826485362924122,0.9034067504452642,-0.16294306141148795,2.406403460018056,-0.12346585911873764,-0.4059753831388857,3.821920722157288,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.883333333333333,0.0,1.0,0.0,1.0,3.1410080065098698,-0.03138186253689877,0.006745491062568167,0.9923509182720084,-0.08034976231894381,-0.06895482354867785,-0.06347285253912506,0.6749635307116445,0.1405414077558284,-0.2231207797636895,0.5222744676022273,-0.5882939456505974,1.0128270054783082,0.18426589539328753,0.5263862730427634,-1.0327646120528475,0.4209142530697408,0.41852613083011503,-0.26107524290776846,-0.12861553071448564,0.3747536676286641,0.5254410280532851,0.30982664837214213,-0.8602963981599315,0.8626912837160265,-1.4931972138878224,-3.8849013359679176,4.02040020570494,-1.18153033066848,2.3147305693997446,-1.1711914351599184,0.9465367945960849,-0.46747013673052784,2.841248164815924,-0.12152960670178015,-0.33446639235627185,3.767996804856788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.891666666666667,0.0,1.0,0.0,1.0,3.1469784551727424,-0.031166217020321376,0.005554961940504144,0.992619329794024,-0.07857678448169028,-0.07116773313781799,-0.05888725515642505,0.6837333016663862,0.1423681059936484,-0.23202383786959413,0.5513683641531857,-0.5753594461876275,1.034960567153528,0.1714686374643495,0.49404517490870253,-0.9985481519910907,0.41096664219309653,0.4379016382249604,-0.27079414614943353,-0.12053715263075081,0.36961598778626886,0.5508047575800084,0.30882632391260184,-0.8627686356575108,0.8937937635274302,-1.574599057525522,-3.881718087916628,4.188563484750059,-1.2040895752057768,2.331366997230915,-1.1646516696115283,0.9942232256312542,-0.7578554624095135,3.2144063099452413,-0.11781636200383083,-0.2556291620064388,3.682010223225174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9,0.0,1.0,0.0,1.0,3.1530235969203186,-0.03089521760340302,0.004330576961215225,0.9928781357300246,-0.07668559936539539,-0.0733065439003252,-0.05420772141186335,0.6907440947467941,0.1432100491489688,-0.2391988688674314,0.5793829196172532,-0.5534856746275124,1.0560754767972484,0.15802257776786216,0.4616909715774863,-0.9629552206403466,0.40084609348297784,0.4573822474506303,-0.2804861040679606,-0.11204514362063141,0.3621227432551722,0.5790144665523724,0.30786304233874495,-0.8645568841933722,0.9240581207697794,-1.64927814798831,-3.886687955229572,4.3497046657531095,-1.2232701088216213,2.3414881377214924,-1.1658453457735396,1.0450551826657501,-1.0322118172531003,3.5240094653253817,-0.11290373297918266,-0.17085954199159703,3.56915130621158,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.908333333333333,0.0,1.0,0.0,1.0,3.159130416725497,-0.030570047048070224,0.0030851157972586274,0.9931281241616878,-0.07467883797891654,-0.07533368682588458,-0.0494412356889998,0.6970424087758914,0.14320543799746654,-0.2447591851425801,0.6063068381937631,-0.5226392815014583,1.0762081180785015,0.143980668331211,0.429267042321543,-0.9260530742285389,0.3905788070460695,0.47692644052031863,-0.29022490191232586,-0.1031195662529883,0.3524124574987172,0.6095382486687647,0.30694459502961546,-0.8656162946907041,0.9532796186309566,-1.717922074169674,-3.897201831119125,4.501562441559191,-1.2394745113844619,2.3477516862641847,-1.1764444967385834,1.0974789698979859,-1.2900278991053238,3.770726952844712,-0.10725591419238234,-0.08105669950712713,3.433467722666399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.916666666666667,0.0,1.0,0.0,1.0,3.1652938285316297,-0.030192374547379507,0.0018309260938171366,0.9933704254279538,-0.07255958038809991,-0.0772115814892739,-0.04459458333637489,0.7034893185374368,0.14243012961906726,-0.2488166345313624,0.632104660340332,-0.4828432039809477,1.095374196943491,0.1293905431983676,0.3967376077255009,-0.8879291799476934,0.3801881849599035,0.4965114422217,-0.300093512346937,-0.09375382745566498,0.34062227827008346,0.641859915766451,0.3060754437688719,-0.8659078291851576,0.9812825828142194,-1.7811176391486794,-3.9109116038080627,4.641620209770976,-1.2529681007510562,2.3520163778103753,-1.1970696150602245,1.1498680460980673,-1.5319541074401355,3.9572962052283756,-0.1012028951614008,0.013217138534318273,3.277952436549134,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.925,0.0,1.0,0.0,1.0,3.1715150238648433,-0.02976443727108554,0.000579883675185004,0.9936064413646899,-0.07033148951995181,-0.07890286957548152,-0.03967440526701869,0.710749714311491,0.14090199821023852,-0.25146788949591636,0.6567132821542879,-0.43417455056433757,1.1135689530881014,0.11429537434539969,0.3640851822580753,-0.8486927373990226,0.36969600536688524,0.5161267134838249,-0.3101760621633296,-0.08395509881802052,0.3268798890413816,0.675493185422571,0.3052578801102588,-0.8653960090484655,1.0079121592401088,-1.8393566744826353,-3.9257711555517796,4.767226906885775,-1.2638844469468713,2.3553937491141577,-1.2274527664668333,1.2005485060086973,-1.7594018666609113,4.08777545355671,-0.09495004693340636,0.11162104183334742,3.104679723684629,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.933333333333334,0.0,1.0,0.0,1.0,3.1777998478213183,-0.029289110481345894,-0.0006565744886310116,0.9938377637035324,-0.06799891749386176,-0.08037063942540314,-0.03468727396061342,0.7192544465544805,0.138589034468313,-0.25277249581490857,0.6800492596851265,-0.3767613951012826,1.1307766615367278,0.09873459862365701,0.33130808846630455,-0.8084753981662638,0.3591234441774556,0.535768004706936,-0.32055105845471754,-0.07374468568885335,0.31129891382573494,0.7099895066590628,0.3044929429866485,-0.8640474784879352,1.03302724487563,-1.8930674894642336,-3.9401349219026596,4.8757557615865625,-1.2722570098384578,2.3582584771571047,-1.266615392383229,1.247839483948104,-1.97433952856359,4.167048788904291,-0.08860754762513245,0.2138975033658297,2.9148710546120116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.941666666666666,0.0,1.0,0.0,1.0,3.184156522951119,-0.0287699206521263,-0.001867347706649005,0.9940660887496584,-0.06556697308345706,-0.0815786312686696,-0.029639672046310538,0.729217531616674,0.1354219866584148,-0.25274204416064183,0.7020106343305433,-0.3107720562699962,1.1469672797236101,0.0827442495209958,0.29841626689303097,-0.7674301413725799,0.3484917218695776,0.5554310214364433,-0.3312863187030501,-0.06315777408555212,0.29397423023198843,0.7449439985709758,0.3037810876498399,-0.861831050659035,1.0564933434836423,-1.9426294780265063,-3.9527228662900105,4.964672321696202,-1.2780385039127473,2.3603671546237504,-1.313078893521491,1.2900722533806555,-2.1789871178795464,4.200269659818832,-0.08222563137313621,0.31978510897114676,2.7090379433557255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.95,0.0,1.0,0.0,1.0,3.1905943268815298,-0.028211094017132003,-0.003041535102365018,0.994293121405579,-0.0630415975144368,-0.08249137556664994,-0.024538106397416375,0.7406842768160042,0.13130967475970823,-0.25133706314882653,0.7224826249554654,-0.23640634566543559,1.162087984591032,0.06635744065654857,0.2654293740281377,-0.7257308594713271,0.3378228024455765,0.5751074572839985,-0.3424357066800757,-0.05224348146584243,0.27498246186107583,0.7799940009893767,0.3031225157970962,-0.8587177266717494,1.078177877264892,-1.9883879863213991,-3.962486960309546,5.031515653656367,-1.281123554633793,2.361024393866047,-1.365054527897207,1.325593305577136,-2.3754904841338034,4.192352926572118,-0.0758397567513247,0.4289743449334349,2.487162457346175,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.958333333333333,0.0,1.0,0.0,1.0,3.197122140084782,-0.027617538081138253,-0.004168252132225813,0.9945204789038555,-0.060429568983264625,-0.08307433175143307,-0.019389162887862813,0.7535408846265667,0.12615311467800322,-0.24845999557890147,0.7413488813388498,-0.15389331518444604,1.1760678268789657,0.049604449748972476,0.23237481755453854,-0.6835715471449738,0.32713966262568106,0.5947814280008774,-0.35403722750133687,-0.04106455232593319,0.2543827221630917,0.8148165473471778,0.3025170917039845,-0.8546814782434777,1.0979460511060786,-2.0306835898349087,-3.9685782433982846,5.073928461017217,-1.2813849761338536,2.3591714449621803,-1.4206015050140708,1.3528006235442525,-2.5658270247934305,4.147795510919554,-0.06951414867719552,0.541047693484602,2.248794959109386,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.966666666666667,0.0,1.0,0.0,1.0,3.2037472952306354,-0.0269948071182981,-0.0052364214436111944,0.99474959066615,-0.057738481908606504,-0.08329400640808267,-0.014199580030307092,0.7675431523190319,0.11985825619268056,-0.24395492233367927,0.758498501690467,-0.06348846612642035,1.18881581885471,0.03251271415930009,0.19928640330483297,-0.6411653851210402,0.31646638617667894,0.6144269813667015,-0.36611239843031024,-0.029696804406771554,0.23221867811451866,0.8491239261713692,0.3019639466524763,-0.8497002651136727,1.1156577932500484,-2.069865767303038,-3.970289184565267,5.089676617863537,-1.278698107266657,2.3534982073381183,-1.4777640023513006,1.3701788968530735,-2.7516912830116804,4.0705150904513365,-0.06337889829737375,0.6554553735794522,1.993166607166943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.975,0.0,1.0,0.0,1.0,3.2104746202082985,-0.02634903896368662,-0.0062345397805774775,0.9949815959605888,-0.05497668669382915,-0.08311806836841763,-0.008976320558024711,0.7823342282064603,0.1123476977772868,-0.23760803289063698,0.7738346898610043,0.034526600875910626,1.2002227718898504,0.015106686960588502,0.16620333114511743,-0.5987436035139149,0.3058280275045701,0.6340063981231794,-0.3786666275405252,-0.018228237378381962,0.2085212007795637,0.8826584655213667,0.3014607767323616,-0.8437572220171535,1.131165494558861,-2.1063093922485767,-3.9670363423676216,5.076698456496927,-1.2729679748744815,2.3425280041068652,-1.5346861901103737,1.376345837389494,-2.9344530015049277,3.963796730393916,-0.05766303687973706,0.7714990266103827,1.7192719271569556,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.983333333333333,0.0,1.0,0.0,1.0,3.2173056010103362,-0.025686864243792098,-0.007150426441107458,0.9952172402123068,-0.052153194992887564,-0.08251546083413706,-0.0037266284725162974,0.7974544141837859,0.10357110395382729,-0.22914966197600617,0.7872823661000161,0.13984519847113427,1.210166352006118,-0.0025924423781761865,0.13316913093203928,-0.5565537441794247,0.29525025326210425,0.6534691147684826,-0.39169050159881647,-0.006757707116946654,0.18331112808943653,0.9151872050112678,0.301002896037814,-0.8368419480034996,1.144312325369331,-2.1404313984954273,-3.958392048702387,5.033204043371211,-1.2641551752264224,2.3246864089863606,-1.5897212809684802,1.3701076555071336,-3.115161563792608,3.8302998118005305,-0.052719306122123166,0.8883236047648735,1.4259276162719248,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.991666666666666,0.0,1.0,0.0,1.0,3.224237609552214,-0.025015291971503817,-0.00797096008200373,0.9954567710157489,-0.04927755735599726,-0.08145650248662341,0.0015419412495345029,0.8123457231384174,0.09351447889633768,-0.21825870374176812,0.7987941763138887,0.2521394624092564,1.2185195433939429,-0.020567169681001952,0.10023013033341098,-0.514856869457728,0.28475877458412974,0.6727511716062854,-0.4051619822233332,0.0046068902134035975,0.15660184138302025,0.9464967957180422,0.3005821216303262,-0.8289518286044056,1.1549309548300597,-2.1727089687539496,-3.9441621578323356,4.957827916254874,-1.252299686516678,2.298363650983286,-1.6415455521150124,1.3505182300850174,-3.2945764255949994,3.672090196407738,-0.04903855349833508,1.004919222424654,1.1118126855229615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0,0.0,1.0,0.0,1.0,3.2312631714614946,-0.024341577732387907,-0.008681815254773694,0.9956998350948,-0.04635972297000609,-0.07991295994930578,0.006821532873815213,0.8263984572638902,0.08207210061363773,-0.20287977605524843,0.8085840594942459,0.378882954219104,1.2257530924654527,-0.03880425852407535,0.06743309496816702,-0.47392327890851016,0.2743785918201596,0.691775175618204,-0.41904959413406667,0.01575093005113697,0.12840152099618654,0.9763887082847301,0.30018558681284174,-0.8200932942964221,1.1628425367947137,-2.204605404338968,-3.928134566831362,4.839931344219906,-1.2378327112862952,2.260504482217651,-1.700037952275948,1.3176594000307804,-3.478726189677091,3.4743713576028257,-0.04953525229037137,1.124559823278597,0.753844248349993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.008333333333333,0.0,1.0,0.0,1.0,3.23836551280336,-0.023672755743431678,-0.009239188256438638,0.9959504681835778,-0.04340915861958096,-0.07779298158820526,0.012106274768377787,0.8385777068134161,0.0691902964768034,-0.18136996978318004,0.8166233041547355,0.525305124511932,1.2324345311712488,-0.05731059308665142,0.03476122088622162,-0.4341913470540629,0.2641282293960248,0.7104262463099129,-0.433495948094599,0.026567880213916605,0.09862307155506873,1.0044029850114227,0.29975653409215336,-0.8102091648830957,1.167495025635893,-2.237916792724786,-3.913687748265551,4.671403629480594,-1.2211678278466853,2.2086524177684996,-1.773552847685862,1.2713924453059586,-3.672838923612683,3.2279388343941906,-0.0564460229903585,1.247926327119846,0.3351784885770348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.016666666666667,0.0,1.0,0.0,1.0,3.245517770915124,-0.023017345670723763,-0.009607532294956072,0.9962096391453948,-0.04043742206056335,-0.07502472820146318,0.01739137514710037,0.8475413004988306,0.0551824143699284,-0.15604339651672997,0.8224189164979667,0.6783447758808906,1.2377271087891049,-0.07610287173615511,0.0022049658304078242,-0.39606655175050026,0.2540257946893815,0.728586049247679,-0.44860880826216437,0.036940804139569614,0.06718753893597516,1.0301876888579666,0.29924481976300243,-0.799294522177758,1.1684288449376643,-2.2725297467434418,-3.8968635379872842,4.469186612828144,-1.2021649217161696,2.1438146511598744,-1.8460188330204963,1.210210744931013,-3.8689489511251445,2.9610281287390317,-0.06675153912275023,1.3651953467505584,-0.1106349442049348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.025,0.0,1.0,0.0,1.0,3.252689765133025,-0.022384184875200903,-0.009786978167634415,0.9964702367725756,-0.037457101291227625,-0.07162509066708661,0.02266890329339444,0.8525489274417363,0.040516828935417325,-0.1292975714334764,0.8258304632730652,0.824582940236102,1.2403307956257974,-0.09518608886570878,-0.030186504746899774,-0.3597049035069272,0.244092147367422,0.7461564904959108,-0.4642629286449406,0.04673805929610016,0.03414058903631633,1.0537534538237399,0.2986440084401075,-0.7874559091039197,1.165651109899144,-2.3075197205726408,-3.874260537851606,4.255044573050615,-1.18093319197856,2.0670112686531494,-1.8993447870087776,1.1335391619965873,-4.0562176123039535,2.698762722638137,-0.0777347249566529,1.4689681505558028,-0.5494800424017487,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.033333333333333,0.0,1.0,0.0,1.0,3.259850909921948,-0.021780343209851404,-0.009782788559636633,0.9967230484333042,-0.03447902309846019,-0.06763416569022508,0.027928145655509124,0.8534847425115852,0.025571197367150904,-0.10154157806636009,0.8270939635105201,0.9604490593804227,1.2395900182660453,-0.11456153374569912,-0.062366043133785604,-0.3251491421996567,0.2343435748230722,0.7630362370585648,-0.48026455471231067,0.0558331235061794,-0.0004160879357574022,1.0751670675686023,0.2979492410137249,-0.7748117196684946,1.1592708442309685,-2.342553894346186,-3.846384166712013,4.039075694034105,-1.1579777279217291,1.9784779828524535,-1.9292901562567655,1.0427784474896524,-4.229201829987163,2.4439998592033296,-0.08955996469637517,1.5591254875336191,-0.9739949702902173,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.041666666666667,0.0,1.0,0.0,1.0,3.2669718742399008,-0.02121132145281309,-0.009600276550913885,0.996958446089366,-0.03151236809936598,-0.06309882490341315,0.03315668445645975,0.8504118885268617,0.010659524599754194,-0.07293282789216837,0.8264474120497938,1.0848999305902787,1.23524525753342,-0.13422865377147855,-0.09429290752543333,-0.29238697527302543,0.2247925185687265,0.7791311235434517,-0.4964177645825534,0.06411770008759436,-0.03634610813013638,1.094486784810462,0.2971513423618346,-0.7614704843116927,1.149417860394307,-2.3775162063355824,-3.81384654871199,3.826244165059,-1.1337374900149289,1.879516166673283,-1.9371386972893934,0.940516515492689,-4.384499277806902,2.195268381936626,-0.10266897224152416,1.6370365874503756,-1.3827012985378362,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.05,0.0,1.0,0.0,1.0,3.2740248487941757,-0.02068131725359974,-0.009244540719495585,0.9971670211670876,-0.028564949796603026,-0.05806804032807151,0.03834159925058831,0.8434495868088159,-0.003942271050635604,-0.043667572226186835,0.8241183009236754,1.197594426568776,1.2273042531276637,-0.15418680385129216,-0.12593015227898544,-0.26137840611534,0.21544794998949005,0.7943615065031195,-0.5125501996671339,0.07150839876439088,-0.07349107589920575,1.1117548739342127,0.29623809147636615,-0.7475277765443217,1.1362258225886712,-2.41245186118475,-3.7769283860330964,3.6191753782100506,-1.10863254556696,1.772020727874295,-1.9260353835098964,0.8298254508640585,-4.5198419683298505,1.950810357712811,-0.11731805784941152,1.7043142898881203,-1.7752645639454157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.058333333333334,0.0,1.0,0.0,1.0,3.280983919221705,-0.020193391473318476,-0.008720773187551063,0.9973399021883077,-0.025643282782834953,-0.052591650910289174,0.043470217470763156,0.8327728175989005,-0.017988542330383918,-0.014006671619088834,0.8203393970542414,1.298368586520225,1.2159276180751202,-0.17443618479122439,-0.15724171395931827,-0.23206738563619125,0.20631530947594384,0.8086648023413566,-0.5285183543077183,0.077948124268662,-0.11167680760230055,1.1270002907723422,0.29519604139767774,-0.7330652461468907,1.1198301176618835,-2.4474828911431805,-3.7355451251226337,3.419350288154649,-1.0830931051902633,1.6580543492074051,-1.899340573752084,0.7137699349981702,-4.633584143635844,1.7093150695400494,-0.13356014672401328,1.7626486089300575,-2.1514129804095328,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.066666666666666,0.0,1.0,0.0,1.0,3.287825359270855,-0.019749551787904766,-0.008034611249945409,0.9974689652354582,-0.022752594342316232,-0.04672007969066856,0.04853057797620814,0.8186058654852602,-0.03126005158290504,0.015735083838464406,0.8153512252513557,1.3870902869224448,1.201364454681444,-0.19497818537034517,-0.188189237697696,-0.20438923464609587,0.197396398236319,0.8219957456565763,-0.5442058758963353,0.08340456434769372,-0.15071747829313648,1.1402434584265468,0.29401208903096593,-0.7181502997288207,1.1003689395818457,-2.48274800825603,-3.689220953098426,3.22742385274636,-1.057562056300152,1.539651002230873,-1.8600698053108933,0.5951309884330639,-4.7245318882817555,1.4700558184212564,-0.15128749711878497,1.8137386691403945,-2.510709806260918,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.075,0.0,1.0,0.0,1.0,3.2945278343595987,-0.019350782912964513,-0.007192439719646497,0.997546999384815,-0.01989679199914787,-0.040504319058039084,0.05351169804642427,0.8012135430247025,-0.04356150684560183,0.04520468379775597,0.8094046683133767,1.4636201894514833,1.1839125000993784,-0.21581531826215822,-0.21872872984429204,-0.1782769880904186,0.18868927520427464,0.8343256523785378,-0.5595195177295665,0.08786697407587973,-0.1904190057403298,1.1515012210793631,0.29267458311236466,-0.7028362683278842,1.0779849542242015,-2.5183617762593893,-3.6370739897461926,3.043292864197841,-1.0324943860790532,1.4187295367558361,-1.810721840824927,0.4762532051704549,-4.79189147455258,1.2328888952754102,-0.170286823220116,1.8592268965947345,-2.852517859261292,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.083333333333333,0.0,1.0,0.0,1.0,3.3010724801519866,-0.018997041709210922,-0.006201636221787626,0.9975678462569116,-0.017078405089602573,-0.03399597229278789,0.05840371621419928,0.7808881041536057,-0.0547190414428318,0.07402593409564608,0.8027616940272195,1.527806974579639,1.1638953273846915,-0.236950881641335,-0.2488071375267992,-0.1536676869094652,0.18018815846833477,0.8456412379358402,-0.5743845732434174,0.0913421177672013,-0.23058233620234614,1.160791606681137,0.29117397531063066,-0.6871631847855751,1.0528269752608241,-2.554387781534492,-3.577816566060951,2.8660869174758625,-1.0083569173422768,1.297056172728932,-1.7532665058850405,0.3589810337368912,-4.835278345443143,0.9982238112143582,-0.19028989257373508,1.9006199914621136,-3.1760017003917707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.091666666666667,0.0,1.0,0.0,1.0,3.307442831296384,-0.01868723279065678,-0.005070763043014117,0.9975265186851124,-0.014298519302674843,-0.027247272098967965,0.06319796703700813,0.757933313700188,-0.06457751567110409,0.10181245026190089,0.7956934743692232,1.5794966524301033,1.141652038676138,-0.25838844795439975,-0.2783590059453079,-0.1305088727991542,0.17188332658190336,0.8559432552573534,-0.5887406261609839,0.09384999130482792,-0.2710069781643822,1.1681382845996024,0.2895030849028024,-0.6711592684701823,1.0250515925510053,-2.5908233763895407,-3.509771645898237,2.6941407872038816,-0.9856280198668804,1.1762326005472268,-1.6892094685563475,0.24465802198935932,-4.854754876410269,0.7669783013857101,-0.21101410367900142,1.9392022810235043,-3.4801290206836333,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1,0.0,1.0,0.0,1.0,3.3136245950324055,-0.018419179463393106,-0.003809711573205263,0.997419297499873,-0.011556722621175868,-0.02031103632312057,0.0678870308159047,0.7326479018672105,-0.07299793126264936,0.12817788419307713,0.788475692986321,1.6185499455662848,1.117535980599245,-0.28013127124782733,-0.30730333162510315,-0.10876534045606717,0.16376102480388677,0.8652451146116273,-0.6025380643860232,0.09541975146702396,-0.3114949174758506,1.1735745783708988,0.2876570735826473,-0.6548431467685167,0.9948248249160969,-2.6275952876427233,-3.4308987209620225,2.5249594383440144,-0.9647959869789086,1.0577010671828835,-1.619699331614446,0.1341675219264002,-4.8508737884770925,0.5405129535043995,-0.23219096498033998,1.9759493623978641,-3.763661750367142,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.108333333333333,0.0,1.0,0.0,1.0,3.3196052849184285,-0.01818960387425162,-0.0024298072739630245,0.9972438021770573,-0.008851079599666384,-0.013240534765967711,0.07246478914012322,0.7053106660385997,-0.07985541198969476,0.15274302439167206,0.7813811531169421,1.6448654848099433,1.0919193005831176,-0.30218170274844514,-0.3355406512946749,-0.08842621549342064,0.15580339346558822,0.8735716063770681,-0.6157356150212246,0.09608611667026792,-0.3518548746390004,1.1771468338246758,0.2856332354864634,-0.6382267790968845,0.9623238967115529,-2.6645658750781687,-3.3388192279562814,2.3551706812726025,-0.9463546684663532,0.9427623517255967,-1.5456575957849084,0.027997541213201915,-4.824708247769793,0.3205399273232823,-0.25358214656550526,2.011448876395152,-4.025135450654423,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.116666666666666,0.0,1.0,0.0,1.0,3.325373748339711,-0.017994128779694137,-0.000943884347663696,0.9969990292675758,-0.006178148729178952,-0.006089248708396325,0.0769265051141238,0.6761692994301449,-0.08503826812537907,0.17513989772796462,0.7746700419149457,1.6584070863477094,1.0652002071741302,-0.32454070249913014,-0.36295031875770783,-0.06951249576819046,0.14798844699611421,0.8809578204737206,-0.6282990243157717,0.09588637715391066,-0.3919067216053472,1.1789169104929536,0.2834307044732222,-0.6213189988285975,0.9277392340718565,-2.701549349845919,-3.2308326785267005,2.1804600663000935,-0.9307951328653224,0.8326030294871867,-1.4679156623381573,-0.07368338808972585,-4.777853245445901,0.10900435109796991,-0.274984015468801,2.045833761720506,-4.262827880495015,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.125,0.0,1.0,0.0,1.0,3.330919637528397,-0.01782731129970093,0.0006336612169615812,0.9966853519509433,-0.003533054601814659,0.0010894865858703162,0.08126893487610856,0.6454349059589468,-0.08844865545692879,0.1950136345664044,0.7685785490364516,1.659232521345063,1.0378096763848554,-0.3472075252458771,-0.38938786260345326,-0.05208521438841908,0.14029014125116618,0.8874483235351879,-0.6402008760601939,0.09485806020210583,-0.43148576206309874,1.178963573009642,0.2810501685619834,-0.6041295497348761,0.8912767653699694,-2.7383356678267856,-3.103921153368018,1.9954962439225152,-0.9185925263254618,0.7283270842087841,-1.3873411414864667,-0.17094888366687988,-4.712386234597056,-0.09205809747094396,-0.2962226882476493,2.0787324798979934,-4.474717862607904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.133333333333333,0.0,1.0,0.0,1.0,3.3362328893687336,-0.01768271605712212,0.0022868354624833343,0.9963044750426567,-0.0009096215811828762,0.008242952168835475,0.08549046360136414,0.6132842805586871,-0.09000524179586171,0.21202371987293944,0.7633072116906536,1.6475190908952704,1.0102138846655049,-0.37017963029624323,-0.41468233798050813,-0.036254225036148544,0.13267857155735652,0.8930966052105337,-0.6514213766738794,0.09303722909279599,-0.47044649218196477,1.1773826088684378,0.27849365966909473,-0.5866734574969643,0.8531606030283915,-2.7747163833489363,-2.954754533415336,1.7938885615646052,-0.9101880711116755,0.6309839882462009,-1.3049285816610001,-0.26404329341894406,-4.630777427868725,-0.2806791180247181,-0.3171430671033493,2.1092412121693527,-4.658434427309639,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.141666666666667,0.0,1.0,0.0,1.0,3.34130329728146,-0.017553030269147743,0.003998032476363366,0.9958593430282521,0.001699433770102487,0.015319599547522576,0.0895912424771937,0.5798724189987754,-0.0896480485821955,0.22584744983736013,0.7590115887237704,1.623577652903615,0.9829076800476195,-0.3934527983016927,-0.43863377149370886,-0.02218707169567566,0.12512034006597159,0.8979647233392912,-0.6619496857545439,0.09045733864512343,-0.5086653858609108,1.17428558770923,0.27576445077692757,-0.5689755295320535,0.8136361915814754,-2.810500422547301,-2.7797356305126186,1.5682802368637234,-0.905967559418783,0.5415804363063859,-1.221816256922199,-0.3533231978074089,-4.535741013944146,-0.4551179311125786,-0.33759748703341863,2.1359251494001663,-4.81119344745641,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.15,0.0,1.0,0.0,1.0,3.3461202814614337,-0.017430215080399918,0.005748067606259965,0.9953540052765366,0.004302271620092281,0.02226961747976696,0.09357328041291915,0.5453579967749234,-0.08734516133293183,0.2361897971509957,0.7557995403011971,1.5878419156435246,0.9563932703429833,-0.4170213040053649,-0.46101126515571844,-0.010116221088419822,0.11757911223371013,0.9021229458156401,-0.6717849809559161,0.08714850912933918,-0.5460421757477005,1.1697973100165615,0.2728670348852044,-0.5510747050069615,0.7729740455707846,-2.8454983047348783,-2.5751617064427856,1.3107646085612432,-0.906239775688874,0.46105674460720225,-1.1391737560500892,-0.43921984171983924,-4.430019376651049,-0.6140042042875304,-0.357442314649834,2.1568583699999877,-4.9297142111125485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.158333333333333,0.0,1.0,0.0,1.0,3.350672988607151,-0.017305674432523743,0.007516312537452717,0.9947934534260083,0.006907706062650772,0.029045378636331425,0.097440415779596,0.5099434528132433,-0.08310027999592495,0.24280439651061497,0.7537402843959158,1.5408172502298367,0.9311388098919289,-0.440877770047274,-0.4815531332677553,-0.0003409948863216052,0.11001634380449035,0.9056490024160779,-0.6809359150220454,0.08313700794979277,-0.5824990421384283,1.1640521843044378,0.269807078866097,-0.5330278900320538,0.7314742880629329,-2.8794449232440136,-2.337604533879871,1.0138628855179446,-0.9112200829101816,0.39020673035916165,-1.0579015674231806,-0.5222299088052288,-4.3161001823915734,-0.7564366425424929,-0.37655198001465107,2.16970942566983,-5.010102873993632,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.166666666666667,1.0,1.0,0.0,1.0,3.354950859599984,-0.01717040729379586,0.009281014099159369,0.9941834596569267,0.009525064934531577,0.03560157320007335,0.10119807159822915,0.34690085510900726,-0.0393624484077049,0.2593764101426331,0.7801321403933078,1.4258984751734396,0.9691069193243279,-0.46501205272609847,-0.49997134072038296,0.006781493670212586,0.10239211085187377,0.9086263913216261,-0.6894166737463024,0.0784446773159187,-0.6179771787875601,1.1571900326408533,0.2665911685516269,-0.5149128812457977,0.6894723310042241,-2.884347074667082,-1.2790151006278805,-0.13439403506360342,-1.0553238718010391,0.23276946308401048,-1.1082306279299647,-0.6598607817796753,-4.510686424537207,-0.7528161995380867,-0.448135232988478,1.9541258112824766,-4.954584461677903,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.175,1.0,1.0,0.0,1.0,3.3567675056882207,-0.016831578518354703,0.011412224510430129,0.9934935415031785,0.012461314184188143,0.041439840150175045,0.10534722754656643,0.19110290338370123,0.0005552204652265955,0.2566717604687494,0.7835668740940702,1.3338258356984676,0.9970251799901501,-0.4889502212917254,-0.5028700516115533,-0.0025808954707149958,0.09242761260780637,0.9095284934674781,-0.6994064254875448,0.07213932825346485,-0.6576771492140484,1.1515052476454697,0.26233815831628904,-0.5004591265106791,0.6488978803683012,-2.8476965829295176,-0.22323822630292645,-1.384120651100128,-1.1758196286417835,0.22881491709930257,-1.5051183536235757,-0.7697537366946298,-4.698788076869951,-0.76044056710181,-0.48890597697709537,1.7068541266369397,-4.851049277339608,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.183333333333334,1.0,1.0,0.0,1.0,3.3584158185371678,-0.01655993792518063,0.013289269910696058,0.9927676850076548,0.01518482117084783,0.047228381673402604,0.1093216577028765,0.18184139493563922,-0.0049521846665353045,0.23266086895842814,0.7451519957582666,1.3090500296857794,0.9555721166509304,-0.5124736624415904,-0.5036919778254317,-0.01628718384812288,0.08279511704117738,0.9124399732732812,-0.7145019796400287,0.0656154483710082,-0.6962903134020593,1.1445160231891565,0.25844273560200864,-0.4864653124685154,0.6086215097152307,-2.7881591555384944,-0.03232774869310173,-1.7100387512525146,-1.1483521667429766,0.4433754272273571,-2.0033652146157688,-0.802649232846556,-4.5118838506308405,-0.9327541696314023,-0.45491491543451335,1.6883102653586923,-4.805472553670172,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.191666666666666,1.0,1.0,0.0,1.0,3.360106530138775,-0.016326779919784748,0.014993341488806442,0.9920154880560806,0.01780929323737159,0.052827668027558124,0.11312532024929685,0.18831419371373215,-0.011060547657685445,0.21598654632603895,0.7205020095746548,1.252715704561953,0.9170182479070969,-0.5354195405507003,-0.503408847423105,-0.03108154132492357,0.07328840982875676,0.9169180839212674,-0.732795845731141,0.05876184103935558,-0.7328752133912291,1.1359593448182796,0.25475624305904715,-0.47232062208803427,0.568806671140465,-2.708510624734757,0.0849625666492182,-1.7677402992188846,-1.138135225339911,0.6141651855887731,-2.3240163507893197,-0.8407999930707388,-4.255703760986265,-1.1049376861812865,-0.4297664434508519,1.7094164328994488,-4.72017297696663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2,1.0,1.0,0.0,1.0,3.3618893709958635,-0.016113275546393847,0.016541640550032603,0.9912472017890027,0.020364091403435085,0.058127630767958446,0.11677100374172414,0.19940011778449876,-0.016525963228057522,0.20055117117371263,0.6983686601112298,1.1730530224817843,0.8816648571620778,-0.5576155061871697,-0.5022759350479448,-0.045749522168437626,0.06382619661884553,0.9226760596997607,-0.7532355854865174,0.051602115153162556,-0.767218709418497,1.126100395086135,0.25127996154449445,-0.4579750385868579,0.5299519600991202,-2.6093443548732687,0.18454183197437413,-1.7222161362849406,-1.1355068993156998,0.7583083101267385,-2.543006442056388,-0.8754793070822375,-3.985371583888606,-1.2405649243900108,-0.4033066608437441,1.725378651516405,-4.568149634632109,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.208333333333333,1.0,1.0,0.0,1.0,3.363780967941193,-0.015906827773386013,0.01792847427036948,0.9904734600025661,0.022864319304257683,0.063047752025623,0.12026857000796877,0.21293512512186413,-0.021445625579152083,0.1844107000678233,0.6770650010390938,1.0754554413033042,0.8489413097533864,-0.5789086131319214,-0.5003331502235321,-0.05978514359633925,0.05436329484016176,0.929556555756713,-0.7751792864320808,0.044170519254651625,-0.7992980731227058,1.1152832627451128,0.24803446537831808,-0.4435643112294275,0.49267084389659654,-2.492165875888057,0.28529802950418737,-1.633682064255297,-1.1375428024149787,0.8866225135482586,-2.693932805226258,-0.906118202354848,-3.715755269723253,-1.3347845083607668,-0.3741976675743941,1.720328107246476,-4.338031379156522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.216666666666667,1.0,1.0,0.0,1.0,3.365792301172891,-0.01569684035628344,0.019142173221061504,0.9897050593783888,0.0253216460698157,0.06752150967556972,0.12362667768424965,0.22870453328593876,-0.025987769110618793,0.16707357197472758,0.6561974619157322,0.9624489952977345,0.818669421286158,-0.5991516041186373,-0.49752096788954164,-0.07297755657269257,0.04486714991192922,0.9374531015922317,-0.7981344655736217,0.03650014511391509,-0.8291479639138846,1.1038539866134556,0.24504333375158788,-0.4293029034660833,0.45765143711317813,-2.3573468843526757,0.39621332465483716,-1.5280290976040931,-1.1430581512725555,1.0037067450624293,-2.78970036661756,-0.9328439205776823,-3.4515976205307086,-1.3878172994242854,-0.34214085627606194,1.6864097867816985,-4.020684673984948,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.225,1.0,1.0,0.0,1.0,3.3679355464963163,-0.01547344406899578,0.0201695470715054,0.9889527655165096,0.027746623450887617,0.07148921357756965,0.12685363542630976,0.24691683278484639,-0.030317976605384954,0.14841803233635115,0.6356102405604283,0.8353409703720841,0.7908192670610601,-0.6181977278711327,-0.49372959481261813,-0.08525229522307413,0.035312325652285835,0.9462850015077535,-0.8216742925423735,0.02862312057835692,-0.856824700131551,1.0921529744213747,0.24233211777371705,-0.41545748144973255,0.4256594326635141,-2.2050259304152653,0.5217138560237256,-1.4174144631922745,-1.1513062408890549,1.1122234689531996,-2.8368266106068774,-0.9557431943376753,-3.1949696533799843,-1.4001448754960055,-0.3068838973514443,1.61783119377084,-3.6067680319778153,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.233333333333333,1.0,1.0,0.0,1.0,3.370225032487697,-0.01522711947612395,0.020996891957470152,0.9882270795099329,0.030149354522104533,0.07489521448584684,0.12995754153082809,0.2677836773361961,-0.03457612497091123,0.1283653136664462,0.6152209461703432,0.694888097600697,0.7653628530218957,-0.6359020362922251,-0.4888257369558129,-0.09660113095923048,0.025678712563778308,0.9559901594081184,-0.8454149090837363,0.020571091874953835,-0.8823974581368843,1.0805182386885221,0.2399286021290638,-0.4023390502365693,0.39753863658021454,-2.0355984970407226,0.6636505881692578,-1.3075013905126185,-1.161700589161056,1.2142738297843803,-2.840072674615113,-0.9748753023550852,-2.9473515876957723,-1.371617114444521,-0.2681378016643515,1.5097342390859947,-3.0873940121047894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.241666666666666,1.0,1.0,0.0,1.0,3.372676657906008,-0.014948523083241079,0.021609841604748273,0.9875380383764423,0.03253983272949168,0.07768614497988063,0.13294602261146343,0.2915091942466887,-0.03878183427733456,0.106607138072671,0.5949172892505201,0.5405404373523639,0.7418294689350716,-0.6521243694884781,-0.48266875167646384,-0.10704398506495111,0.015950649166268236,0.9665228986708265,-0.869008837119292,0.012375198872438832,-0.9059472265931472,1.0692926891806327,0.23786315441264452,-0.39029524413163263,0.3742028657951009,-1.8487149141186277,0.8231643629202334,-1.2000271142094705,-1.1736818187150653,1.3119878600926826,-2.8025080650251355,-0.9906182325291967,-2.710734586385748,-1.298353400870771,-0.22566381203138974,1.3571234431363433,-2.450878838924524,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.25,1.0,1.0,0.0,1.0,3.3753075809935615,-0.014626458538660665,0.021990145384594238,0.9868960986345265,0.03492839231738971,0.07980193495010818,0.13582249110666433,0.3038623920592823,-0.04161438904768523,0.09584108746283732,0.585003321508499,0.459683815317975,0.7302445184546108,-0.6667139515275355,-0.4751063309071423,-0.11660158286272165,0.006117348918527223,0.9778566237429964,-0.8921233768341552,0.004060787999467225,-0.9275763679099801,1.058879015340676,0.2361675385952073,-0.3797203261842969,0.3566906559314725,-1.7507498446868963,0.9074904923185811,-1.1469117357324654,-1.1799960297289216,1.3600470086603877,-2.7737447657835856,-0.9977293047565927,-2.5954969580199494,-1.2496408607948073,-0.20347389809246552,1.2689901536802872,-2.1014651836354137,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/cartesianMotion.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/cartesianMotion.txt new file mode 100644 index 000000000..c29ff54a9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/cartesianMotion.txt @@ -0,0 +1,751 @@ +time,contactflag_LF,contactflag_RF,contactflag_LH,contactflag_RH,base_positionInWorld_x,base_positionInWorld_y,base_positionInWorld_z,base_quaternion_w,base_quaternion_x,base_quaternion_y,base_quaternion_z,base_linearvelocityInBase_x,base_linearvelocityInBase_y,base_linearvelocityInBase_z,base_angularvelocityInBase_x,base_angularvelocityInBase_y,base_angularvelocityInBase_z,footPositionInWorld_LF_x,footPositionInWorld_LF_y,footPositionInWorld_LF_z,footPositionInWorld_RF_x,footPositionInWorld_RF_y,footPositionInWorld_RF_z,footPositionInWorld_LH_x,footPositionInWorld_LH_y,footPositionInWorld_LH_z,footPositionInWorld_RH_x,footPositionInWorld_RH_y,footPositionInWorld_RH_z,footVelocityInWorld_LF_x,footVelocityInWorld_LF_y,footVelocityInWorld_LF_z,footVelocityInWorld_RF_x,footVelocityInWorld_RF_y,footVelocityInWorld_RF_z,footVelocityInWorld_LH_x,footVelocityInWorld_LH_y,footVelocityInWorld_LH_z,footVelocityInWorld_RH_x,footVelocityInWorld_RH_y,footVelocityInWorld_RH_z,contactForcesInWorld_LF_x,contactForcesInWorld_LF_y,contactForcesInWorld_LF_z,contactForcesInWorld_RF_x,contactForcesInWorld_RF_y,contactForcesInWorld_RF_z,contactForcesInWorld_LH_x,contactForcesInWorld_LH_y,contactForcesInWorld_LH_z,contactForcesInWorld_RH_x,contactForcesInWorld_RH_y,contactForcesInWorld_RH_z +0.0,1.0,1.0,1.0,1.0,-0.022534031675274076,-0.01567146984550802,0.553609975497579,0.998609171980068,0.048537586547287195,-0.02058386059184357,0.000359183216710024,-0.019386222957083837,0.31607161115912963,-0.04150852622541065,-0.20323931009014376,0.19268480139355038,0.9920334962140588,-0.1085402830120083,0.14128442116754836,-0.040190662435935,0.08809258872551584,0.13882126753155646,0.008243878355737037,-0.10766027732767143,-0.13422935917459658,-0.01348176862855014,0.08897259440987602,-0.13669251281059014,0.03495277216312523,-0.1085402830120083,0.14128442116754836,-0.040190662435935,0.08809258872551584,0.13882126753155646,0.008243878355737037,-0.10766027732767143,-0.13422935917459658,-0.01348176862855014,0.08897259440987602,-0.13669251281059014,0.03495277216312523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0166667,1.0,1.0,1.0,1.0,-0.022842750805729232,-0.010360933355768728,0.5534193073347287,0.99868461613743,0.046673767223556116,-0.019381506050334618,0.008657607453348981,0.0010671926757830907,0.3284662771114266,-0.06072966798327038,-0.34212274263303993,0.2768085850393799,1.065110949383288,-0.12059255284135882,0.14603020386262303,-0.0668378217060405,0.08975351952977458,0.1433523199508356,0.009627676650351814,-0.11744063752930904,-0.15135314003046627,-0.01836294073971764,0.09290543484184934,-0.15403102394223123,0.05810255761667634,-0.12059255284135882,0.14603020386262303,-0.0668378217060405,0.08975351952977458,0.1433523199508356,0.009627676650351814,-0.11744063752930904,-0.15135314003046627,-0.01836294073971764,0.09290543484184934,-0.15403102394223123,0.05810255761667634,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0333334,1.0,1.0,1.0,1.0,-0.02263090286055411,-0.004581968972306507,0.5526144294654874,0.9987905137973824,0.04244882022480436,-0.016871297131678984,0.01819248589329953,0.03027303146732266,0.3681917852841976,-0.08951853457810766,-0.5188088337102809,0.39896057028657683,1.2515875731576367,-0.14823626454399352,0.16405901286270377,-0.10278251918077849,0.09844640348921138,0.1644829643338283,0.009255342698390267,-0.13809489827092408,-0.1865093683548272,-0.022524501589078167,0.1085877697623008,-0.18608541688366187,0.08951336029008893,-0.14823626454399352,0.16405901286270377,-0.10278251918077849,0.09844640348921138,0.1644829643338283,0.009255342698390267,-0.13809489827092408,-0.1865093683548272,-0.022524501589078167,0.1085877697623008,-0.18608541688366187,0.08951336029008893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0500001,1.0,1.0,1.0,1.0,-0.022202529065692797,0.0021498796040460965,0.5515165313256246,0.9987599124898467,0.037562934521058224,-0.013780897274813263,0.029626846334726564,0.05929355000141759,0.40226104598807466,-0.0945635065480822,-0.6076181550827999,0.4300181589570753,1.414752963251996,-0.17096085508832315,0.17953125323691857,-0.11617776522104654,0.10833280532250669,0.18711513650319883,0.013315848980132714,-0.1503054704794484,-0.2151221458159524,-0.027391560650685338,0.12898818993139977,-0.20753826254963054,0.10210205355049726,-0.17096085508832315,0.17953125323691857,-0.11617776522104654,0.10833280532250669,0.18711513650319883,0.013315848980132714,-0.1503054704794484,-0.2151221458159524,-0.027391560650685338,0.12898818993139977,-0.20753826254963054,0.10210205355049726,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0666668,1.0,1.0,1.0,1.0,-0.021386326478493412,0.009119388715432313,0.5505263488801034,0.9985570708788565,0.03180191834551468,-0.010904851223761114,0.04187479441348114,0.07418840938843294,0.3970125977927123,-0.08493311609398602,-0.6603014198231024,0.4451754348256172,1.500404477202139,-0.1858461038809404,0.18362278093074103,-0.12463920209775864,0.1105351069373,0.2001804885169074,0.014397786089951205,-0.15324470298532245,-0.23279359819169862,-0.02859767626162006,0.14313650783294127,-0.2162358906054848,0.11043931192609145,-0.1858461038809404,0.18362278093074103,-0.12463920209775864,0.1105351069373,0.2001804885169074,0.014397786089951205,-0.15324470298532245,-0.23279359819169862,-0.02859767626162006,0.14313650783294127,-0.2162358906054848,0.11043931192609145,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.0833335,1.0,1.0,1.0,1.0,-0.02080062492976549,0.01569797005950927,0.5495806831698828,0.9981349198796693,0.025987281813303186,-0.0076253470805591654,0.05471011773578177,0.07740430326238212,0.386044725171924,-0.07144862212063383,-0.6460469357998933,0.4419092604045836,1.5504078947636286,-0.19677823473230344,0.18500601240074477,-0.12359723369350901,0.10974042440057921,0.21197630644649093,0.010985072141387641,-0.15167419872858917,-0.2429574587864979,-0.024379051119098646,0.1548444604043168,-0.21598716474071428,0.11020325471579634,-0.19677823473230344,0.18500601240074477,-0.12359723369350901,0.10974042440057921,0.21197630644649093,0.010985072141387641,-0.15167419872858917,-0.2429574587864979,-0.024379051119098646,0.1548444604043168,-0.21598716474071428,0.11020325471579634,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1000002,1.0,1.0,1.0,1.0,-0.020202955751586902,0.022299468747507063,0.548851663579202,0.9974790643354519,0.02046170141026995,-0.004809032749363797,0.06777690013481091,0.08462031555694274,0.3671732073115922,-0.05450576866609433,-0.7374479634054688,0.3474441279987788,1.5408586056717153,-0.19529637753946866,0.17298944752263617,-0.11989298565690952,0.10908457437394115,0.20862919408180772,0.03129120188490924,-0.13904532080536217,-0.24898977533293565,-0.041865442281690424,0.16533563110805766,-0.21335002877372747,0.10931874526013001,-0.19529637753946866,0.17298944752263617,-0.11989298565690952,0.10908457437394115,0.20862919408180772,0.03129120188490924,-0.13904532080536217,-0.24898977533293565,-0.041865442281690424,0.16533563110805766,-0.21335002877372747,0.10931874526013001,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.11666689999999999,1.0,1.0,1.0,1.0,-0.019650883139930953,0.02827059127654448,0.5482919365021814,0.9966699703982546,0.013226854662963321,-0.003232566742893341,0.08039633657275748,0.10639499657551124,0.35055179395008895,-0.03485276631968773,-0.7553757950905631,0.14623753841865061,1.503160636474112,-0.18525658723368876,0.16161507241548473,-0.09394416315514711,0.11079516602106003,0.205402351714913,0.059629632731619586,-0.11952560564058888,-0.24615000130861356,-0.06460847145898875,0.17652614761415658,-0.20236272200913866,0.0889653244277813,-0.18525658723368876,0.16161507241548473,-0.09394416315514711,0.11079516602106003,0.205402351714913,0.059629632731619586,-0.11952560564058888,-0.24615000130861356,-0.06460847145898875,0.17652614761415658,-0.20236272200913866,0.0889653244277813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1333336,1.0,1.0,1.0,1.0,-0.01857097225004465,0.034428693095196666,0.5480227389344662,0.9956530233732545,0.007663203993747954,-0.0037041047112110364,0.09275026663323573,0.1282401988155217,0.3451416282526491,0.0032541092755912974,-0.5799991711260293,-0.04249251160262282,1.4921297869291301,-0.18009887751843803,0.16404762983995197,-0.05014298225689386,0.3012920020275748,0.2200177281968738,0.14795428364272759,-0.1044746062136503,-0.23750027871730786,-0.06773100779549114,0.18812276005565307,-0.18440315582013891,0.05086143053515086,-0.18009887751843803,0.16404762983995197,-0.05014298225689386,0.3012920020275748,0.2200177281968738,0.14795428364272759,-0.1044746062136503,-0.23750027871730786,-0.06773100779549114,0.18812276005565307,-0.18440315582013891,0.05086143053515086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1500003,1.0,0.0,1.0,1.0,-0.017576023570561115,0.04036357866329486,0.5486056528222701,0.9944403694346267,0.0035863940587846747,-0.005006189087509106,0.10512101353772513,0.13083518602307265,0.32846651019279605,0.018912209248326116,-0.3525821315213242,-0.09675624971556679,1.478243858837187,-0.18212782570650043,0.16897930899217073,-0.021101274930844165,0.6450166005193256,0.3231420643840793,0.29062483790311217,-0.09733250789528024,-0.22672998012725226,-0.050088348343449135,0.19118328366674706,-0.16574453627431598,0.023574972956724984,-0.18212782570650043,0.16897930899217073,-0.021101274930844165,0.6450166005193256,0.3231420643840793,0.29062483790311217,-0.09733250789528024,-0.22672998012725226,-0.050088348343449135,0.19118328366674706,-0.16574453627431598,0.023574972956724984,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.166667,1.0,0.0,1.0,1.0,-0.01660171199373589,0.046041826089837756,0.5487663844777749,0.9930864540113548,0.001862209172522635,-0.00598562593639688,0.11721774318890767,0.15445651575117306,0.30543777229348373,-0.006736135568378662,-0.15909756051195414,-0.10573836487292558,1.406788558068466,-0.17855118441820134,0.1654442595130432,-0.0012653331613298386,0.9787146783274939,0.7115359064541066,0.37323812859880373,-0.08884213744544418,-0.20921120572203716,-0.031152442598099073,0.18445809503836982,-0.14415587202770128,0.004109094471561567,-0.17855118441820134,0.1654442595130432,-0.0012653331613298386,0.9787146783274939,0.7115359064541066,0.37323812859880373,-0.08884213744544418,-0.20921120572203716,-0.031152442598099073,0.18445809503836982,-0.14415587202770128,0.004109094471561567,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.1833337,1.0,0.0,1.0,1.0,-0.014937321269347069,0.051464697414863064,0.5484679588443877,0.9916980328909119,0.0010219825993310063,-0.007101633638584037,0.1283882156256018,0.17479537204782897,0.28150754477571316,-0.03205380606649064,0.07258734238476947,-0.09574577697774206,1.3242461073137195,-0.17512284508435455,0.16258970897686786,0.019796999083682622,0.9481662076553501,1.5378822210522627,0.2166804759425436,-0.08256313438279317,-0.18810431696119628,-0.006491582684798609,0.17378172827509455,-0.12067517263157301,-0.01721451577082786,-0.17512284508435455,0.16258970897686786,0.019796999083682622,0.9481662076553501,1.5378822210522627,0.2166804759425436,-0.08256313438279317,-0.18810431696119628,-0.006491582684798609,0.17378172827509455,-0.12067517263157301,-0.01721451577082786,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2000004,1.0,0.0,1.0,1.0,-0.013342710730305341,0.056603783118817474,0.5477835390152442,0.9902437193927556,0.0031014001243194374,-0.007402868559299388,0.13911489876200997,0.17006267035907047,0.26367492049572405,-0.04862465706378115,0.35746066175578983,-0.04935067535990326,1.3073122784130662,-0.18287246352028005,0.1697876769707135,0.04203970954648073,0.5764331692581248,2.230432355251478,0.08928291948847514,-0.08395490057239155,-0.1743111691495682,0.027047020671791114,0.1682932145156271,-0.10153839489061378,-0.040368426096877866,-0.18287246352028005,0.1697876769707135,0.04203970954648073,0.5764331692581248,2.230432355251478,0.08928291948847514,-0.08395490057239155,-0.1743111691495682,0.027047020671791114,0.1682932145156271,-0.10153839489061378,-0.040368426096877866,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2166671,1.0,0.0,1.0,1.0,-0.011888183267107437,0.061488382433698086,0.5469712281325355,0.9886354614000314,0.006868339025951846,-0.007136954439948975,0.15000604742040788,0.1768788866726012,0.24828073970822567,-0.06071015053838543,0.4941946058350948,-0.012967302168928108,1.2396976494081446,-0.180725573231593,0.1640761419889222,0.051685886994253735,0.46940032893990224,2.492683371653045,0.2654196572588321,0.0890621090694549,-0.19864284707102184,0.16702384517693875,0.15765556744186016,-0.085460616331477,-0.050389482543270005,-0.180725573231593,0.1640761419889222,0.051685886994253735,0.46940032893990224,2.492683371653045,0.2654196572588321,0.0890621090694549,-0.19864284707102184,0.16702384517693875,0.15765556744186016,-0.085460616331477,-0.050389482543270005,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.23333379999999998,1.0,0.0,0.0,1.0,-0.010143796078052804,0.06628659068276481,0.5459502846064617,0.9870973446269399,0.011124984462250357,-0.006512737843337605,0.15960153883012235,0.21069615068667352,0.24193880799284503,-0.06855634988922929,0.5047182969915069,-0.016866334307326092,1.0916497467803177,-0.16272842944353197,0.14428334420034541,0.05486900139029506,0.595690244692672,2.8265426638873987,0.4453174715987,0.35338023286588194,-0.1972636024012589,0.27729536975385044,0.13942422218833403,-0.06845894603055842,-0.05286787832065893,-0.16272842944353197,0.14428334420034541,0.05486900139029506,0.595690244692672,2.8265426638873987,0.4453174715987,0.35338023286588194,-0.1972636024012589,0.27729536975385044,0.13942422218833403,-0.06845894603055842,-0.05286787832065893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2500005,1.0,0.0,0.0,1.0,-0.007744305881453466,0.07140700403620762,0.544962369558435,0.9856484128257366,0.015101155566208845,-0.006272069950283281,0.16801732807425124,0.25341669033498987,0.24239253522377135,-0.05354794593734821,0.4520400272713505,-0.06246079089395831,0.9621433648531127,-0.1433986318357256,0.12520362576437802,0.05745065387093146,0.7832616856025841,2.9383074675852314,0.46624398730187644,0.49568560596154043,-0.11004035856823759,0.2264748103893597,0.12607516565025276,-0.056470960303068515,-0.053837074842332154,-0.1433986318357256,0.12520362576437802,0.05745065387093146,0.7832616856025841,2.9383074675852314,0.46624398730187644,0.49568560596154043,-0.11004035856823759,0.2264748103893597,0.12607516565025276,-0.056470960303068515,-0.053837074842332154,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.2666672,1.0,0.0,0.0,1.0,-0.00483878414855967,0.07675961686188049,0.5445371085441136,0.984292593727049,0.018629147276192613,-0.006515045080991603,0.1754383053766564,0.28893596088665807,0.22678413988899992,-0.022204595447720545,0.3311761237681664,-0.13711726572859453,0.7848331135389223,-0.11362231068725923,0.09953924959896614,0.056747038719995896,0.8420245728268251,2.8533690959985063,0.5030046284633228,0.6321575361467033,0.021542442890551284,0.14223330179629126,0.10831845330399673,-0.044298789192423804,-0.0512101140653301,-0.11362231068725923,0.09953924959896614,0.056747038719995896,0.8420245728268251,2.8533690959985063,0.5030046284633228,0.6321575361467033,0.021542442890551284,0.14223330179629126,0.10831845330399673,-0.044298789192423804,-0.0512101140653301,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.28333389999999997,1.0,0.0,0.0,1.0,-0.0013147404800996979,0.08184868854460284,0.5446692193699351,0.9832521891819481,0.020858364855580746,-0.007799632564130007,0.18088456765662075,0.3296189143253478,0.2197965788118038,-0.003679137479845477,0.23000775671213022,-0.23479540344747196,0.611245673784484,-0.08304373332533745,0.07645615755996252,0.0608885846905772,0.8444206520168324,2.5476816714541237,0.4513317603448929,0.772510827244815,0.17391601923276767,0.053919999024238933,0.09157705677399985,-0.03169461891228013,-0.0529029509359879,-0.08304373332533745,0.07645615755996252,0.0608885846905772,0.8444206520168324,2.5476816714541237,0.4513317603448929,0.772510827244815,0.17391601923276767,0.053919999024238933,0.09157705677399985,-0.03169461891228013,-0.0529029509359879,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3000006,1.0,0.0,0.0,1.0,0.0028206413088857213,0.08751047368967639,0.5449458734853769,0.9823430802493951,0.023032473260550773,-0.009880071522325536,0.1854021630088129,0.3768204792970309,0.2023575550444213,-0.0007031738348685998,0.15800021156889663,-0.2908178710094123,0.42659209330357467,-0.0525956532664559,0.05405166243416613,0.061462703968200555,0.9116825707906724,2.127932859467547,0.14996361541438796,0.908775292795862,0.3243618158426407,-0.014446928340030656,0.07046348283891332,-0.018459938378250062,-0.052178735114868584,-0.0525956532664559,0.05405166243416613,0.061462703968200555,0.9116825707906724,2.127932859467547,0.14996361541438796,0.908775292795862,0.3243618158426407,-0.014446928340030656,0.07046348283891332,-0.018459938378250062,-0.052178735114868584,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3166673,1.0,0.0,0.0,1.0,0.007920166772766898,0.09269383059324962,0.5452774259361142,0.9818342858486508,0.02427958310336475,-0.012236170359836417,0.18778235569755153,0.42056628424687137,0.17710721658165968,0.0056859243473204755,0.16132525669440465,-0.3496223809966726,0.31825412925699803,-0.034688286921157975,0.04308647755908755,0.07029625202620984,1.0215211610531172,1.7617172523318065,-0.10580755421237466,1.0467592441203484,0.4453228885383593,-0.0713544390016058,0.05869512352553277,-0.007557315088959274,-0.05917091682255784,-0.034688286921157975,0.04308647755908755,0.07029625202620984,1.0215211610531172,1.7617172523318065,-0.10580755421237466,1.0467592441203484,0.4453228885383593,-0.0713544390016058,0.05869512352553277,-0.007557315088959274,-0.05917091682255784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.333334,1.0,0.0,0.0,1.0,0.013663437012719479,0.09814187819488626,0.5458541356003807,0.9812054069395618,0.02670227018518693,-0.015222661507633918,0.19050251635122886,0.4592165605809988,0.17221143046461734,0.0009651222761844968,0.2581716017659532,-0.40541150340560567,0.3258399006297782,-0.03590449124823496,0.04791495800789268,0.08872721390817184,1.0620037044243114,1.3842583495816985,-0.35818956385131995,1.1155531664106004,0.5154589673037955,-0.0879497194628026,0.06117126793503426,-0.000919621844772468,-0.07519445362192365,-0.03590449124823496,0.04791495800789268,0.08872721390817184,1.0620037044243114,1.3842583495816985,-0.35818956385131995,1.1155531664106004,0.5154589673037955,-0.0879497194628026,0.06117126793503426,-0.000919621844772468,-0.07519445362192365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3500007,1.0,0.0,0.0,1.0,0.019957971752930896,0.10371759540260866,0.5461900500679701,0.9805807430367497,0.02970667499248241,-0.018189153788816966,0.19299760239659358,0.4883044677586952,0.1774500143888708,-0.016503641163946654,0.437013752776264,-0.42511028436141307,0.35183784645162336,-0.04360911544621545,0.057012967375004775,0.11030625632081355,0.8453202902319339,1.178712709197295,-0.4947851359737697,1.1138161030526457,0.5393225638373966,-0.07366644894250396,0.06314871960224785,0.00823192955317054,-0.0946561173406275,-0.04360911544621545,0.057012967375004775,0.11030625632081355,0.8453202902319339,1.178712709197295,-0.4947851359737697,1.1138161030526457,0.5393225638373966,-0.07366644894250396,0.06314871960224785,0.00823192955317054,-0.0946561173406275,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3666674,1.0,0.0,0.0,1.0,0.026485047037707328,0.10978490557522652,0.5463756916376237,0.9797157721116807,0.0351020689782879,-0.02093452839915901,0.1961800095569417,0.5116966858078705,0.17629924449426598,-0.03612860993101526,0.5677291730710774,-0.4320409118693333,0.3626823380986757,-0.0484765800998291,0.061995443206853164,0.12524672056820327,0.4713811292738221,0.8639794429226804,-0.568173175263345,1.0677947312511515,0.529891432340669,-0.07983206548649185,0.06301571262786025,0.01606858666087273,-0.10787697202511115,-0.0484765800998291,0.061995443206853164,0.12524672056820327,0.4713811292738221,0.8639794429226804,-0.568173175263345,1.0677947312511515,0.529891432340669,-0.07983206548649185,0.06301571262786025,0.01606858666087273,-0.10787697202511115,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.3833341,1.0,0.0,0.0,1.0,0.03345189502617413,0.11575165256997157,0.5462802826264268,0.9789149636709196,0.04026413536683933,-0.023597768565305897,0.19886537814074506,0.5380140839837849,0.15399054432117082,-0.06511206011047695,0.5823194824488764,-0.4062410022117268,0.35024945826708853,-0.04885770843506776,0.05940720181616257,0.1233289232768912,0.09344999321446629,0.40152672000812223,-0.8757156195184761,0.9548409636456867,0.4697532351128857,-0.12138258305555447,0.05999974685258033,0.018635956543698564,-0.1057349761365926,-0.04885770843506776,0.05940720181616257,0.1233289232768912,0.09344999321446629,0.40152672000812223,-0.8757156195184761,0.9548409636456867,0.4697532351128857,-0.12138258305555447,0.05999974685258033,0.018635956543698564,-0.1057349761365926,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4000008,1.0,0.0,0.0,1.0,0.04103768296081664,0.1216351223106138,0.5456869502428154,0.9780018189677556,0.045809378141675273,-0.025867940783360865,0.2018533938522287,0.5664729283735084,0.14617070774171678,-0.08788019012414183,0.5663516095920142,-0.39901975117319555,0.37997215835944775,-0.053931981240199774,0.05997980350909061,0.12126014673905099,-0.09174104557908183,0.17613101972413733,-0.6524306711078743,0.7670578766586015,0.3714773235587292,-0.19601197621414468,0.0642503653827063,0.016872846281092767,-0.10307584994350222,-0.053931981240199774,0.05997980350909061,0.12126014673905099,-0.09174104557908183,0.17613101972413733,-0.6524306711078743,0.7670578766586015,0.3714773235587292,-0.19601197621414468,0.0642503653827063,0.016872846281092767,-0.10307584994350222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.41666749999999997,1.0,1.0,0.0,1.0,0.048929128790093084,0.12791013102413545,0.5450574647750271,0.9770349343311686,0.05067502733153953,-0.02848961087775667,0.20499541646941938,0.5795086871072005,0.154707994764322,-0.10830644342586146,0.40150238272270755,-0.3951612479761114,0.39967496823756143,-0.05384175035502566,0.054479744834194474,0.1040784705565634,-0.047957062371970186,0.15202101952017683,-0.09844663801213138,0.5611293052801627,0.23628121535150942,-0.16024892758460893,0.06990530175331924,0.007195727240727692,-0.08666759444109116,-0.05384175035502566,0.054479744834194474,0.1040784705565634,-0.047957062371970186,0.15202101952017683,-0.09844663801213138,0.5611293052801627,0.23628121535150942,-0.16024892758460893,0.06990530175331924,0.007195727240727692,-0.08666759444109116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4333342,1.0,1.0,1.0,1.0,0.05674514113574541,0.13441395687780247,0.5440282747153123,0.9761176285114911,0.053508431550665245,-0.03127565968761344,0.20821396728652738,0.5721150414278761,0.1611025934813044,-0.11644815152933496,0.10087707057330143,-0.41450415917072647,0.3929198510140118,-0.045340801424263937,0.04238506478696303,0.07590751244739911,0.026864455755102132,0.07626483599484614,0.06238809970232681,0.236908359185532,0.05418415200954655,-0.07486309330659285,0.07540408210308333,-0.008042859259118424,-0.0601056319835289,-0.045340801424263937,0.04238506478696303,0.07590751244739911,0.026864455755102132,0.07626483599484614,0.06238809970232681,0.236908359185532,0.05418415200954655,-0.07486309330659285,0.07540408210308333,-0.008042859259118424,-0.0601056319835289,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4500009,1.0,1.0,1.0,1.0,0.0642585121567642,0.14092790270909367,0.5432860344269824,0.9753684598807966,0.053554873416895354,-0.03524157186176683,0.21105988395660408,0.5686432516867526,0.16555103293186585,-0.11109536525286079,-0.22586120950882904,-0.4129926688399964,0.3892843155493918,-0.037155796045611825,0.030301329854771478,0.04144383930002306,0.03124752796617045,0.05670034201800714,0.09336445657588262,0.012306479653255296,-0.05270204474942709,-0.08029176640610014,0.08070980366501092,-0.026303032586189767,-0.028371149130238905,-0.037155796045611825,0.030301329854771478,0.04144383930002306,0.03124752796617045,0.05670034201800714,0.09336445657588262,0.012306479653255296,-0.05270204474942709,-0.08029176640610014,0.08070980366501092,-0.026303032586189767,-0.028371149130238905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.46666759999999996,1.0,1.0,1.0,1.0,0.07184213570339226,0.14758357127007482,0.5425815406928158,0.9747061276028679,0.05106013616691114,-0.03913865497318247,0.21403035531187772,0.5801250092181192,0.1594913887867149,-0.1281919554753846,-0.4544280339835357,-0.2866290877074916,0.3998230934691244,-0.03796770153712481,0.02272913650709165,-0.0019906720200142313,0.02935532631589781,0.045281698433134926,0.09599114766109391,0.012251335587750262,-0.06693184258355936,-0.0889147524640744,0.07957436344073875,-0.04437928065750026,0.009067067217037077,-0.03796770153712481,0.02272913650709165,-0.0019906720200142313,0.02935532631589781,0.045281698433134926,0.09599114766109391,0.012251335587750262,-0.06693184258355936,-0.0889147524640744,0.07957436344073875,-0.04437928065750026,0.009067067217037077,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.4833343,1.0,1.0,1.0,1.0,0.07975834498809378,0.15421739263858603,0.5413865034370142,0.97414250149463,0.04693072853668402,-0.0418641108832629,0.21700527579014028,0.5965555827447881,0.15237567409511404,-0.14569376282073174,-0.5515760516773641,-0.07711490295367938,0.37556799669191265,-0.03944911502793592,0.015730489833683234,-0.04462755567626182,0.021571075050768912,0.0351006194199731,0.07246266025866765,0.005540656607625079,-0.07443961822635818,-0.07316479739543057,0.06656084668631575,-0.055069488640040846,0.04392541853950224,-0.03944911502793592,0.015730489833683234,-0.04462755567626182,0.021571075050768912,0.0351006194199731,0.07246266025866765,0.005540656607625079,-0.07443961822635818,-0.07316479739543057,0.06656084668631575,-0.055069488640040846,0.04392541853950224,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.500001,1.0,1.0,1.0,1.0,0.08791462493221805,0.16102341236915602,0.5401625491032476,0.9737288453678996,0.04211698199052102,-0.04268283617926273,0.21967355558237212,0.6269210123836246,0.12359602614207599,-0.1411207879088393,-0.6167301073917979,0.1544943130468629,0.3962197398887673,0.16098634749907265,0.18590951890544047,-0.04168080533847345,0.014100333509384005,0.03435754261430674,0.04320386844753295,-0.0051071762344944765,-0.08857721930034342,-0.051989023073676394,0.1719774848141069,-0.12732426509091996,0.21157178661071283,0.16098634749907265,0.18590951890544047,-0.04168080533847345,0.014100333509384005,0.03435754261430674,0.04320386844753295,-0.0051071762344944765,-0.08857721930034342,-0.051989023073676394,0.1719774848141069,-0.12732426509091996,0.21157178661071283,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5166677,0.0,1.0,1.0,0.0,0.09708939526643759,0.1672639554760014,0.5391006950332156,0.9732280430935484,0.03606915040741537,-0.04189228944918257,0.22309466288976013,0.658280007503559,0.062437890733586604,-0.11489283483920619,-0.5906606822182107,0.35331352906586644,0.4361409517998959,0.5092725703487331,0.5677355886820549,-0.025401592958037754,0.0071549568377200735,0.04161181267230738,0.010436694481478935,-0.017419401340035275,-0.1009173136788155,-0.025432627301905836,0.32758344059767475,-0.17707693721672732,0.3871136488170476,0.5092725703487331,0.5677355886820549,-0.025401592958037754,0.0071549568377200735,0.04161181267230738,0.010436694481478935,-0.017419401340035275,-0.1009173136788155,-0.025432627301905836,0.32758344059767475,-0.17707693721672732,0.3871136488170476,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5333344,0.0,1.0,1.0,0.0,0.1069366697336268,0.17269472999920957,0.5386057845026654,0.9727137964285479,0.030912293734585213,-0.03940722312769718,0.22653779176771394,0.6527154940449694,0.005431479327944688,-0.06317353808777958,-0.506616442543377,0.6017621605538244,0.40658789020127817,0.7955754863523962,0.9166150302873133,-0.00294085119747984,-0.004273413548797104,0.03826353141477465,-0.036696075964717675,-0.03142714572660109,-0.10148269332786126,0.014355689447385014,0.4060553540325618,-0.10239466956079438,0.42326768730855996,0.7955754863523962,0.9166150302873133,-0.00294085119747984,-0.004273413548797104,0.03826353141477465,-0.036696075964717675,-0.03142714572660109,-0.10148269332786126,0.014355689447385014,0.4060553540325618,-0.10239466956079438,0.42326768730855996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5500011,0.0,1.0,1.0,0.0,0.11659762578712207,0.17712599319678624,0.5389858432783059,0.9723410956677707,0.025306464677829547,-0.03426186603920698,0.2296486469731981,0.6614507033241888,-0.037089304064081036,-0.019544629788504516,-0.44794153547170357,0.8373797501562854,0.30546235869724775,1.2629983155069149,1.0996500062771999,0.10307867439111293,-0.016868657505026016,0.01982420120286037,-0.08018635624464461,-0.04138222737432916,-0.09072835009966615,0.05116988197207678,0.48313900493654577,0.0034169945319607927,0.45263783478121367,1.2629983155069149,1.0996500062771999,0.10307867439111293,-0.016868657505026016,0.01982420120286037,-0.08018635624464461,-0.04138222737432916,-0.09072835009966615,0.05116988197207678,0.48313900493654577,0.0034169945319607927,0.45263783478121367,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5666677999999999,0.0,1.0,1.0,0.0,0.12719781576381492,0.18144115876081532,0.5396405952600871,0.9722120736244302,0.020262969008933464,-0.027685293802007672,0.23157422242755182,0.706522277924406,-0.06391366853695135,0.00109377148104575,-0.36299606804794915,0.9247640289772352,0.22457073847156483,1.6891665796878712,1.0868526682529804,0.1431444650817339,-0.02448457226389621,0.007465314943152681,-0.10297656329052016,-0.04466291215314104,-0.07687118521125172,0.07281163864007183,0.6124249037049526,0.06314457855226033,0.49783577657584605,1.6891665796878712,1.0868526682529804,0.1431444650817339,-0.02448457226389621,0.007465314943152681,-0.10297656329052016,-0.04466291215314104,-0.07687118521125172,0.07281163864007183,0.6124249037049526,0.06314457855226033,0.49783577657584605,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.5833345,0.0,1.0,1.0,0.0,0.13854648486840795,0.18580186870691057,0.5404543980680188,0.9720251752999521,0.01575088430502528,-0.02075368728511533,0.23342718927061337,0.7328645376220746,-0.09479619174985532,0.021312662886421092,-0.3579198455814528,0.8762777267277428,0.22664140161433222,2.04000731851515,0.9165170508380267,0.2612461528532854,-0.023574154508976947,0.007821010865774304,-0.09594830559822427,-0.04149643659659579,-0.07506686371762407,0.06881053640246167,0.7992686661145996,0.06123405388320413,0.5069609973310846,2.04000731851515,0.9165170508380267,0.2612461528532854,-0.023574154508976947,0.007821010865774304,-0.09594830559822427,-0.04149643659659579,-0.07506686371762407,0.06881053640246167,0.7992686661145996,0.06123405388320413,0.5069609973310846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6000012,0.0,1.0,1.0,0.0,0.15035602815578333,0.18966827030406375,0.5414491598280335,0.9717313505177332,0.010979957874624476,-0.014941440192850307,0.23536009923310597,0.732052154332477,-0.1308542194894437,0.016254105180870976,-0.37188600590527143,0.7199072695322521,0.16659368852974105,2.585172905320719,0.8859250281077284,0.46155244077585855,-0.018839339975144313,-0.0018584176210905553,-0.07098246827001102,-0.030729515106847502,-0.06136837342715171,0.049661758242553075,0.9973563294121414,0.07771124939163207,0.4754217970607747,2.585172905320719,0.8859250281077284,0.46155244077585855,-0.018839339975144313,-0.0018584176210905553,-0.07098246827001102,-0.030729515106847502,-0.06136837342715171,0.049661758242553075,0.9973563294121414,0.07771124939163207,0.4754217970607747,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6166678999999999,0.0,1.0,1.0,0.0,0.1622175856908918,0.19306267445654185,0.541768133054869,0.9716297933978282,0.0068589716642934746,-0.010588082295205681,0.23617025977610373,0.7259215546447362,-0.15129533651604235,-0.019186562721097013,-0.4422531347698042,0.5871310112773006,0.07251531406280656,3.1414411862007783,1.0754864378739666,0.4845546040519514,-0.014004177879320833,-0.019980805864703924,-0.04416801968542239,-0.019177366287913982,-0.045907805940883686,0.02755788804074208,1.218231787516199,0.20269810865662635,0.46825662756757497,3.1414411862007783,1.0754864378739666,0.4845546040519514,-0.014004177879320833,-0.019980805864703924,-0.04416801968542239,-0.019177366287913982,-0.045907805940883686,0.02755788804074208,1.218231787516199,0.20269810865662635,0.46825662756757497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6333346,0.0,1.0,1.0,0.0,0.17417508608106388,0.196301519977076,0.541344078285825,0.9715959625169437,0.0014931718194443342,-0.0071854943973913106,0.23653207970369822,0.7379040768384406,-0.170447695007127,-0.05169468520052529,-0.5735796045882962,0.44412315093194815,0.027269063361247996,3.526601819064787,1.1729933789112288,0.5399300341001433,-0.0059815161315351605,-0.03135367968912721,-0.00933959118742194,-0.007567267555510141,-0.040985285762130313,-0.0025639968363227145,1.436013664078993,0.38006927243597444,0.5045124671044393,3.526601819064787,1.1729933789112288,0.5399300341001433,-0.0059815161315351605,-0.03135367968912721,-0.00933959118742194,-0.007567267555510141,-0.040985285762130313,-0.0025639968363227145,1.436013664078993,0.38006927243597444,0.5045124671044393,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6500013,0.0,1.0,1.0,0.0,0.18669401995015453,0.1993325526146155,0.5404088018514759,0.9715899986616555,-0.004183632432458873,-0.005660023124006645,0.2365657115022165,0.7696289159457281,-0.1749097972235537,-0.06885068368845552,-0.6776366470978372,0.26713531297368037,0.010826155285679519,3.464175303285326,1.0339681742900622,0.6152337025917287,0.0036369288928376846,-0.034806541197091714,0.028049497188131173,0.0039254538643856704,-0.03915554836296913,-0.034272249774751046,1.6429770779172683,0.510340025181137,0.5484442400986832,3.464175303285326,1.0339681742900622,0.6152337025917287,0.0036369288928376846,-0.034806541197091714,0.028049497188131173,0.0039254538643856704,-0.03915554836296913,-0.034272249774751046,1.6429770779172683,0.510340025181137,0.5484442400986832,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.666668,0.0,1.0,1.0,0.0,0.1996660402085098,0.20290570081732967,0.5393436670744723,0.9715262948361514,-0.010534006121506175,-0.00553048133007214,0.2366328526076405,0.8089221646029627,-0.16998675408515804,-0.06273122981894326,-0.7996745500578594,0.11254857528199605,0.0292753181718344,3.084105601341847,0.8217513596143435,0.5467068712549265,0.01321178006616229,-0.032395512188338305,0.06393198806500405,0.01388861402090322,-0.04495813298551989,-0.06490786067247029,1.8503260113998674,0.5952783486608157,0.5090791157655973,3.084105601341847,0.8217513596143435,0.5467068712549265,0.01321178006616229,-0.032395512188338305,0.06393198806500405,0.01388861402090322,-0.04495813298551989,-0.06490786067247029,1.8503260113998674,0.5952783486608157,0.5090791157655973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.6833347,0.0,1.0,1.0,0.0,0.21327429248536992,0.20666578935347202,0.5386044870576221,0.9713365309037719,-0.017578328193325964,-0.0069845572158232375,0.23695476798379173,0.8215880355133462,-0.16505122703143885,-0.056012577576487685,-0.8038636103479967,0.0316339729759956,0.05764857048335711,2.64929938951661,0.6884360714222028,0.29156904460002214,0.017021051508737124,-0.024692974734943113,0.07677593908616358,0.01731645591239838,-0.048552064252879015,-0.07464843034738573,2.031790913501198,0.6883009512478949,0.4053741918103841,2.64929938951661,0.6884360714222028,0.29156904460002214,0.017021051508737124,-0.024692974734943113,0.07677593908616358,0.01731645591239838,-0.048552064252879015,-0.07464843034738573,2.031790913501198,0.6883009512478949,0.4053741918103841,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7000014,0.0,1.0,1.0,0.0,0.2265464593428015,0.21058097089537145,0.5378274565964708,0.9710731900030154,-0.023679773109228842,-0.008174412289068974,0.2374643278191302,0.8095001652092366,-0.16165863619553725,-0.0563838019626419,-0.7650642547366845,-0.014044542527652942,0.09815614532047992,2.0978085400811834,0.4204063861740996,-0.07971650376565091,0.018432502078129746,-0.013418211343633033,0.07972934571912708,0.017777906627865808,-0.05309532149046083,-0.0755682743866471,2.17334907225356,0.8446592396760163,0.27812015151133707,2.0978085400811834,0.4204063861740996,-0.07971650376565091,0.018432502078129746,-0.013418211343633033,0.07972934571912708,0.017777906627865808,-0.05309532149046083,-0.0755682743866471,2.17334907225356,0.8446592396760163,0.27812015151133707,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7166681,0.0,1.0,1.0,0.0,0.23974500421706246,0.2142667140401731,0.537121048274178,0.9706405283026063,-0.029918351174919915,-0.010198026045880545,0.23844885687329098,0.8147234184632093,-0.16758018810573203,-0.05481419746313501,-0.6933719483947729,-0.1322096901895426,0.07245596539280066,1.6150861812424515,0.0937134636738701,-0.47688027474452216,0.020773983458150333,-0.010556990902964448,0.09060108357522136,0.023057575182015788,-0.04414949382998153,-0.0829128866372107,2.3411748576211644,1.0015811565950887,0.11332826437491986,1.6150861812424515,0.0937134636738701,-0.47688027474452216,0.020773983458150333,-0.010556990902964448,0.09060108357522136,0.023057575182015788,-0.04414949382998153,-0.0829128866372107,2.3411748576211644,1.0015811565950887,0.11332826437491986,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7333348,0.0,1.0,1.0,0.0,0.2532546573941979,0.2181306149493257,0.5365057270529994,0.9704228277351404,-0.03438116717924012,-0.013036238051442663,0.23859490198114744,0.8383138091081757,-0.1759557536092389,-0.07476251207498412,-0.734517443729675,-0.18255733104614918,-0.03100061509005927,1.4453737988472661,-0.22927827082686367,-0.7782797667552377,0.020754784587425575,-0.0282337953977683,0.10377143078144102,0.03072322367821569,-0.029972775467723232,-0.09328015663324422,2.4895574814040615,1.1834238163914201,-0.06402460255135026,1.4453737988472661,-0.22927827082686367,-0.7782797667552377,0.020754784587425575,-0.0282337953977683,0.10377143078144102,0.03072322367821569,-0.029972775467723232,-0.09328015663324422,2.4895574814040615,1.1834238163914201,-0.06402460255135026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7500015,0.0,1.0,1.0,0.0,0.26731252338240785,0.22189754054107552,0.5353121207689413,0.9702917054152276,-0.04106255981230661,-0.016093330013285796,0.23788416784887872,0.8607415330903749,-0.18189779763351746,-0.09537123648823112,-0.8138467684224605,-0.11959807704868233,-0.12735273616577095,1.2049371508316093,-0.46544712774228625,-0.9691015658161053,0.01712589054658907,-0.04966893408188932,0.10416983443202298,0.03343187990452662,-0.02091420988909338,-0.09351898951751421,2.6126397734923965,1.3370899099943527,-0.18754084389962303,1.2049371508316093,-0.46544712774228625,-0.9691015658161053,0.01712589054658907,-0.04966893408188932,0.10416983443202298,0.03343187990452662,-0.02091420988909338,-0.09351898951751421,2.6126397734923965,1.3370899099943527,-0.18754084389962303,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7666682,0.0,1.0,1.0,0.0,0.2816363934852346,0.22582790254453405,0.5342041482038795,0.9703453194506192,-0.04703113958683682,-0.018290035688150283,0.236396927907208,0.8699529532068705,-0.1816135008877321,-0.09178143888906479,-0.7909050123911844,-0.01836723665702039,-0.2188693063592062,0.7141417158862737,-0.5338752218291831,-1.0736639576121907,0.010147755745757882,-0.06765714177592541,0.08857047551086494,0.03102134803113019,-0.007906206503890161,-0.07938441179088991,2.7192062311641125,1.3775981440747804,-0.28398372867450744,0.7141417158862737,-0.5338752218291831,-1.0736639576121907,0.010147755745757882,-0.06765714177592541,0.08857047551086494,0.03102134803113019,-0.007906206503890161,-0.07938441179088991,2.7192062311641125,1.3775981440747804,-0.28398372867450744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.7833349,0.0,1.0,1.0,0.0,0.29599406435817033,0.22964797956581948,0.5332577103671776,0.9705256207340962,-0.053711093473450065,-0.019681735448243632,0.23411058759981135,0.8838587434444164,-0.18307732198669174,-0.053892094072628856,-0.7473609781012025,0.08313342502498589,-0.27836505946035917,0.29587814532855083,-0.6156940993432231,-0.9861723539805403,0.0037071368747142465,-0.07955966613023159,0.07053878923075411,0.026682141858990868,0.0015616516545979577,-0.06334068757281955,2.705308263932377,1.3683566779622394,-0.40842587110779444,0.29587814532855083,-0.6156940993432231,-0.9861723539805403,0.0037071368747142465,-0.07955966613023159,0.07053878923075411,0.026682141858990868,0.0015616516545979577,-0.06334068757281955,2.705308263932377,1.3683566779622394,-0.40842587110779444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8000016,0.0,1.0,1.0,0.0,0.3107201364493514,0.23370916957570465,0.5334965818190508,0.9707973705941504,-0.059350832253107895,-0.02011485170517472,0.2315714505271024,0.9059421486340996,-0.18279892792274832,-0.009999163305518782,-0.6003417587586006,0.1871733858396517,-0.3352935941121459,0.07097789827791691,-0.5261812962362035,-0.7532196825123748,-0.004411924947250268,-0.08787878131932467,0.04142074387038212,0.01893980309699137,0.016782611672613613,-0.03767371943872607,2.6369496712656932,1.2641787411852183,-0.5041864421908845,0.07097789827791691,-0.5261812962362035,-0.7532196825123748,-0.004411924947250268,-0.08787878131932467,0.04142074387038212,0.01893980309699137,0.016782611672613613,-0.03767371943872607,2.6369496712656932,1.2641787411852183,-0.5041864421908845,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8166683,1.0,1.0,1.0,0.0,0.3256762811610366,0.23786552955007734,0.5340352528702073,0.9712926018172952,-0.06403122778277558,-0.019308812206340956,0.2282933492128056,0.9035244088012347,-0.18440608829535382,0.008978018444994552,-0.43807083357524346,0.24397166056979883,-0.4351750563818841,0.0456140767820671,-0.23597363289605258,-0.33244338725242134,-0.012062705880576582,-0.10186173328825696,0.018490165683342705,0.014808494879001368,0.04043959188179167,-0.017429360367363266,2.531188148995589,1.0387857033162398,-0.5652774040354319,0.0456140767820671,-0.23597363289605258,-0.33244338725242134,-0.012062705880576582,-0.10186173328825696,0.018490165683342705,0.014808494879001368,0.04043959188179167,-0.017429360367363266,2.531188148995589,1.0387857033162398,-0.5652774040354319,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8333349999999999,1.0,1.0,1.0,0.0,0.3403667369917016,0.24171898095969074,0.5348611197451747,0.9720665717717356,-0.06723086117003742,-0.01830592068299187,0.2241238153749585,0.89676323330948,-0.1931385258159597,0.01710232181187575,-0.3528287354853479,0.19689396362217942,-0.5429811204836572,0.08698681185244153,-0.07702519792450173,-0.05004912224846855,-0.015304177941239916,-0.11587444609242448,0.019257355811797345,0.019117964099019783,0.06199127756595888,-0.017373019822415084,2.4151691682409058,0.8057708047312317,-0.6345708106284664,0.08698681185244153,-0.07702519792450173,-0.05004912224846855,-0.015304177941239916,-0.11587444609242448,0.019257355811797345,0.019117964099019783,0.06199127756595888,-0.017373019822415084,2.4151691682409058,0.8057708047312317,-0.6345708106284664,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8500017,1.0,1.0,1.0,0.0,0.35529723509234973,0.24530076514625304,0.5356571061131264,0.9729819389310653,-0.07032099214834103,-0.01804823841756235,0.21916971886472036,0.8788792080865248,-0.19982754077326165,0.022937421119055584,-0.24299546918418174,0.1150248698964887,-0.5557487706796335,0.08823213664844388,-0.06935814701126473,-0.027074999586859973,0.1466790852665606,-0.08764381345922251,0.09819291682886316,0.021527954919523362,0.07071361142892293,-0.01788826263988998,2.181835543227829,0.5622632646904329,-0.633470479158601,0.08823213664844388,-0.06935814701126473,-0.027074999586859973,0.1466790852665606,-0.08764381345922251,0.09819291682886316,0.021527954919523362,0.07071361142892293,-0.01788826263988998,2.181835543227829,0.5622632646904329,-0.633470479158601,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8666684,1.0,0.0,1.0,0.0,0.36960272657334625,0.24843143983896626,0.5367077122138603,0.9738534259109306,-0.07142567210845671,-0.017987632371704698,0.21490538217331678,0.8219860215671828,-0.2066498968312464,0.018714981841857645,-0.03917323649319829,0.02949194610255286,-0.5163263517571648,0.07902429444841295,-0.05109464323069414,0.003613249692380208,0.4508811410214237,0.002469958559369291,0.2327806107310907,0.01965364474370445,0.07687624069379276,-0.009163079472103687,1.6413819665333726,0.25602827292412167,-0.39270645694011314,0.07902429444841295,-0.05109464323069414,0.003613249692380208,0.4508811410214237,0.002469958559369291,0.2327806107310907,0.01965364474370445,0.07687624069379276,-0.009163079472103687,1.6413819665333726,0.25602827292412167,-0.39270645694011314,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.8833350999999999,1.0,0.0,1.0,1.0,0.3829727957735912,0.25074005869592436,0.537404487937363,0.9747939470525153,-0.07090944869562392,-0.018331499410365243,0.21074289313006148,0.7474813467961192,-0.21390645008713727,-0.014057169890192248,0.1765083964602588,-0.0557468891802512,-0.5170869180352408,0.07592754746823772,-0.035664816341170545,0.03603492122672733,0.7612302942360563,0.13426630282961366,0.303718036448293,0.01910633253197033,0.09000871268901676,0.00025171404177270384,0.6098780940592038,0.0740710586433788,-0.12390034010672989,0.07592754746823772,-0.035664816341170545,0.03603492122672733,0.7612302942360563,0.13426630282961366,0.303718036448293,0.01910633253197033,0.09000871268901676,0.00025171404177270384,0.6098780940592038,0.0740710586433788,-0.12390034010672989,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9000018,1.0,0.0,1.0,1.0,0.39523065266999485,0.2522469477983096,0.5374307679591562,0.9758573573389093,-0.06820490854856026,-0.01889376322679303,0.2066241377199981,0.6884018956924334,-0.1883533055598511,-0.08456168698304857,0.4386388909626562,-0.1780884425519843,-0.47155712879319445,0.06620765549262493,-0.012003747707203827,0.07719187031701284,1.0945715133811131,0.3844482210895527,0.5180063902745274,0.017533891253696036,0.09893866879737781,0.010580445043023756,-0.0629252937663862,0.049818971272500644,-0.07707457634675194,0.06620765549262493,-0.012003747707203827,0.07719187031701284,1.0945715133811131,0.3844482210895527,0.5180063902745274,0.017533891253696036,0.09893866879737781,0.010580445043023756,-0.0629252937663862,0.049818971272500644,-0.07707457634675194,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9166685,1.0,0.0,1.0,1.0,0.40664295966575303,0.2540158222658151,0.5356981840592073,0.9768530469682263,-0.06301698081089173,-0.020266327329675926,0.20341155506740155,0.6624427447675607,-0.16584884935171462,-0.1508988451456463,0.681018549981943,-0.3050051920205761,-0.46436470833167787,0.06311925595230079,0.006158966369271315,0.1181995237803074,1.4538344331282367,0.7018332631781898,0.9553475105184923,0.018419618733809012,0.11241695614414242,0.018790180922802244,-0.057822215605741786,0.05994300978912987,-0.1175902711881176,0.06311925595230079,0.006158966369271315,0.1181995237803074,1.4538344331282367,0.7018332631781898,0.9553475105184923,0.018419618733809012,0.11241695614414242,0.018790180922802244,-0.057822215605741786,0.05994300978912987,-0.1175902711881176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9333351999999999,1.0,0.0,1.0,1.0,0.4179776602997336,0.25547394671945867,0.5334792902480205,0.9780294341085831,-0.055926129911714084,-0.022041319996017175,0.19961180882697277,0.6629618705606664,-0.15940598607343281,-0.17359870349141596,0.8198863487110648,-0.3040596918105656,-0.47422377469679344,0.06082696524214426,0.011207656462211018,0.13133311178501492,1.6628449406791257,0.8129387488050527,1.360164504639595,0.015835081301449616,0.12133979347749294,0.033202472061095924,-0.060612218610043504,0.06763314714378561,-0.13152653652331886,0.06082696524214426,0.011207656462211018,0.13133311178501492,1.6628449406791257,0.8129387488050527,1.360164504639595,0.015835081301449616,0.12133979347749294,0.033202472061095924,-0.060612218610043504,0.06763314714378561,-0.13152653652331886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9500019,1.0,0.0,1.0,1.0,0.4293994854308286,0.25725984540907487,0.5310407688981018,0.979082138474217,-0.048464194072968134,-0.022941846646288552,0.19627292142847957,0.6614639676172269,-0.16364649841625045,-0.13935504060642329,0.7935342030930149,-0.25050037730065233,-0.42945622504468345,0.05294920788000185,0.010008552821618829,0.12002074841580042,1.6668992072888584,0.6376503889882993,1.5580450374334605,0.012371343152942565,0.11208124037961402,0.03953439578206148,-0.056639250457515944,0.06507041396128349,-0.12044983120858502,0.05294920788000185,0.010008552821618829,0.12002074841580042,1.6668992072888584,0.6376503889882993,1.5580450374334605,0.012371343152942565,0.11208124037961402,0.03953439578206148,-0.056639250457515944,0.06507041396128349,-0.12044983120858502,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9666686,1.0,0.0,1.0,1.0,0.4406859415288713,0.25858912167988,0.5299986768109581,0.979987142368941,-0.04199435788766773,-0.02387825924994854,0.19311008112564104,0.6474508996430873,-0.16250062299134135,-0.06415545304572362,0.7387857300196445,-0.22837002572780996,-0.3829073914754518,0.04673056692379661,0.009032623020926923,0.11089176775634971,1.7747494585020007,0.44739000295727555,1.5510233179738744,0.011143903000814014,0.10107316321846657,0.03892225605311756,-0.050311301466389,0.06110981475552215,-0.11045373028607094,0.04673056692379661,0.009032623020926923,0.11089176775634971,1.7747494585020007,0.44739000295727555,1.5510233179738744,0.011143903000814014,0.10107316321846657,0.03892225605311756,-0.050311301466389,0.06110981475552215,-0.11045373028607094,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +0.9833353,1.0,0.0,1.0,1.0,0.4515210599883286,0.26032172289346117,0.5300680283425885,0.9807420536755845,-0.035509978389164656,-0.02456566828152606,0.1904746532452025,0.6757315053074493,-0.1502411731831909,-0.02942947373681349,0.6415193315224238,-0.26203198046290144,-0.3135338437316551,0.040315084701275455,0.010072158818201471,0.10562143584473312,1.9976187487784036,0.24948677570776562,1.3142943021283668,0.012768895637993488,0.08529640718789028,0.027217310708540336,-0.03738225961124588,0.05375731246261928,-0.10272987535874539,0.040315084701275455,0.010072158818201471,0.10562143584473312,1.9976187487784036,0.24948677570776562,1.3142943021283668,0.012768895637993488,0.08529640718789028,0.027217310708540336,-0.03738225961124588,0.05375731246261928,-0.10272987535874539,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.000002,1.0,0.0,1.0,1.0,0.4634716592309499,0.262352661722129,0.5301976831022491,0.981265002449016,-0.030551731342378385,-0.026310237404258124,0.18839681018649782,0.696412795385372,-0.149016321627145,0.02418027909889369,0.4209871450065279,-0.23119614241585681,-0.2918592768884797,0.04133643373163685,-0.001248367847069178,0.07955059843404423,2.333244596716006,0.1379284810757571,0.9112443746801951,0.11335050546385848,0.1750704075367428,0.12222736181451649,-0.03295748251140331,0.04347512687494051,-0.07539017715281927,0.04133643373163685,-0.001248367847069178,0.07955059843404423,2.333244596716006,0.1379284810757571,0.9112443746801951,0.11335050546385848,0.1750704075367428,0.12222736181451649,-0.03295748251140331,0.04347512687494051,-0.07539017715281927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0166686999999999,1.0,0.0,0.0,1.0,0.4748325260118891,0.2643769809204929,0.532149895416564,0.9817802916146888,-0.027768917618836184,-0.027167539273230706,0.1860061047952259,0.6700899500785595,-0.13358916108416594,0.10076252442759726,0.29366884342115734,-0.07270330207068737,-0.3112209131875555,0.04126460628066632,-0.014649966847187675,0.043642613498759246,2.827036523467229,0.25789535925724577,0.27195021519178175,0.2248157808527787,0.2619393895965944,0.2581378523072584,-0.04255785488957745,0.038135694581007865,-0.04294185559903191,0.04126460628066632,-0.014649966847187675,0.043642613498759246,2.827036523467229,0.25789535925724577,0.27195021519178175,0.2248157808527787,0.2619393895965944,0.2581378523072584,-0.04255785488957745,0.038135694581007865,-0.04294185559903191,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0333354,1.0,0.0,0.0,1.0,0.4856352556056025,0.26655558430721543,0.5347949036758233,0.9823332321208785,-0.025376862724894873,-0.026732181638100178,0.18347432074832076,0.6651539447586086,-0.10823923135598629,0.09403995376145644,0.22247462407881957,0.05612804629161256,-0.29174370178601505,0.03518330228603392,-0.019906521013250692,0.016875582252222767,3.1414015833271702,0.3054556156821705,-0.31829320502085445,0.2842897626820621,0.24498867496468307,0.3325620159123495,-0.04601400391024125,0.03212823183069559,-0.01947856713975617,0.03518330228603392,-0.019906521013250692,0.016875582252222767,3.1414015833271702,0.3054556156821705,-0.31829320502085445,0.2842897626820621,0.24498867496468307,0.3325620159123495,-0.04601400391024125,0.03212823183069559,-0.01947856713975617,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0500021,1.0,0.0,0.0,1.0,0.4965817828454713,0.2691643662632984,0.5364493215001722,0.9827937959361942,-0.024166496207340026,-0.025689590152736846,0.18130741873451114,0.6849928763260702,-0.10239610487595022,0.05228430149001724,0.17283273416817274,0.10993105759848056,-0.24213078519818212,0.027023168728162968,-0.018849584267107398,0.003183112510483392,3.39118174975162,0.21462071494485233,-0.5143545397607348,0.44854231849483023,0.25524439896253803,0.45579058815593854,-0.04146371617443725,0.025520544080216565,-0.007077910542612073,0.027023168728162968,-0.018849584267107398,0.003183112510483392,3.39118174975162,0.21462071494485233,-0.5143545397607348,0.44854231849483023,0.25524439896253803,0.45579058815593854,-0.04146371617443725,0.025520544080216565,-0.007077910542612073,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0666688,1.0,0.0,0.0,1.0,0.5080459708167002,0.2716028380963398,0.5376801817203077,0.9831819941496936,-0.02277367624326846,-0.024507684220238024,0.1795380167662538,0.693692610724809,-0.10978643704649077,0.030918621628828524,0.0895455062248524,0.11152923956931407,-0.18420616408439214,0.020372731000173897,-0.017229498945190422,-0.005969875884073358,3.645791920954173,0.06304255022454378,-0.43819903034579955,0.644517485882333,0.3034252230098772,0.5564916320938603,-0.03249490706146576,0.017285418550300673,0.0024408721289944377,0.020372731000173897,-0.017229498945190422,-0.005969875884073358,3.645791920954173,0.06304255022454378,-0.43819903034579955,0.644517485882333,0.3034252230098772,0.5564916320938603,-0.03249490706146576,0.017285418550300673,0.0024408721289944377,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.0833355,1.0,0.0,0.0,1.0,0.5194162209155143,0.27397074868776333,0.5385989600709455,0.983426424985696,-0.022957685480685483,-0.023661939195320836,0.17828495155435903,0.7012991445929023,-0.11377244368952522,0.002325584952264252,0.08965261597667325,0.11230563856603845,-0.1585565763787973,0.01659840868221922,-0.014632384064764671,-0.006400408751544143,3.5060061379639658,-0.11860430563457462,-0.35043014884842894,0.8659944972742792,0.3681354963868763,0.6012046350937026,-0.028983120349478916,0.015328377016297681,0.0028633182522440565,0.01659840868221922,-0.014632384064764671,-0.006400408751544143,3.5060061379639658,-0.11860430563457462,-0.35043014884842894,0.8659944972742792,0.3681354963868763,0.6012046350937026,-0.028983120349478916,0.015328377016297681,0.0028633182522440565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1000022,1.0,0.0,0.0,1.0,0.5312318880088851,0.27628101997618226,0.538857353004036,0.9837305097281069,-0.021575015810275475,-0.02246320107272735,0.17692995088574354,0.7131624774212542,-0.11709293084424455,-0.03288841468926493,0.2749341654452227,0.06233570844316877,-0.21314579210425902,0.022257301471948657,-0.009822137582582366,0.01967949137816503,3.049312020794863,-0.2576762544705303,-0.5913927075290699,1.1670459329146652,0.4468089628204334,0.6604072088837666,-0.0360177964588805,0.028840071419275654,-0.022600925604690455,0.022257301471948657,-0.009822137582582366,0.01967949137816503,3.049312020794863,-0.2576762544705303,-0.5913927075290699,1.1670459329146652,0.4468089628204334,0.6604072088837666,-0.0360177964588805,0.028840071419275654,-0.022600925604690455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1166689,1.0,0.0,0.0,1.0,0.5430877440222567,0.2785760098877226,0.5385706398962291,0.9841733658088804,-0.01855568060479989,-0.021906995287783636,0.17486725338717224,0.7164518356834173,-0.14454113720782807,-0.0527452728295827,0.3637581675211322,0.012696296941241136,-0.32699093295630105,0.03871285941089021,-0.016419948707130427,0.03686870110503179,2.618559154089466,-0.369924100862029,-1.066597130197017,1.4642258367216014,0.5533920352395844,0.719655311137833,-0.04987503860412789,0.04314425142340292,-0.038527994501157216,0.03871285941089021,-0.016419948707130427,0.03686870110503179,2.618559154089466,-0.369924100862029,-1.066597130197017,1.4642258367216014,0.5533920352395844,0.719655311137833,-0.04987503860412789,0.04314425142340292,-0.038527994501157216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1333355999999999,1.0,0.0,0.0,1.0,0.5553718761107327,0.27994971127118495,0.5381897738956158,0.9847976576445512,-0.015526395358340104,-0.021292473434448168,0.1716948896153445,0.7298133078090404,-0.16750953686211767,-0.05987407601458205,0.5196135290638182,0.0594799574804622,-0.3866090683077997,0.042071296226112054,-0.016343814654574646,0.04557629079100846,2.2676913088743804,-0.5034371837832626,-1.5255505024127622,1.7393722675469732,0.6639913856494539,0.7216728678750772,-0.062304032598708765,0.05516074975943036,-0.048800901529291424,0.042071296226112054,-0.016343814654574646,0.04557629079100846,2.2676913088743804,-0.5034371837832626,-1.5255505024127622,1.7393722675469732,0.6639913856494539,0.7216728678750772,-0.062304032598708765,0.05516074975943036,-0.048800901529291424,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1500023,1.0,0.0,0.0,1.0,0.5679374296250621,0.28152058889411313,0.5376797020706032,0.9854237890714239,-0.0100562345770321,-0.01955202360375491,0.16869068276359467,0.7562658683684835,-0.16564672300813343,-0.07438000410280651,0.8787321486564725,0.18113792728244088,-0.35141349635831043,0.024466301078606402,0.0022246072611462908,0.062060648047036406,1.6858894580946182,-0.531919155185762,-1.7155280542095406,2.003161421749431,0.7253167822875737,0.6627880504641728,-0.0686041323892955,0.06811201949960183,-0.06909084488863203,0.024466301078606402,0.0022246072611462908,0.062060648047036406,1.6858894580946182,-0.531919155185762,-1.7155280542095406,2.003161421749431,0.7253167822875737,0.6627880504641728,-0.0686041323892955,0.06811201949960183,-0.06909084488863203,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.166669,1.0,0.0,0.0,1.0,0.5810642980105704,0.2831016848653739,0.5367445624168908,0.9859658492472301,-0.0014822965623144625,-0.01591766485242695,0.16617994722810414,0.7867931089917948,-0.1611433729670485,-0.06503078894657131,1.2580099870806924,0.2715428239157988,-0.2998567479804388,0.006290532212735554,0.023274151523069386,0.08574377451693661,0.9000989188357897,-0.4306611919271298,-1.6952356631192647,2.2728705919212167,0.7715376280348778,0.5618566064259863,-0.07197105666396743,0.0821925333343762,-0.09406694087314267,0.006290532212735554,0.023274151523069386,0.08574377451693661,0.9000989188357897,-0.4306611919271298,-1.6952356631192647,2.2728705919212167,0.7715376280348778,0.5618566064259863,-0.07197105666396743,0.0821925333343762,-0.09406694087314267,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.1833357,1.0,0.0,0.0,1.0,0.5945311567508917,0.28504650199894704,0.5363675213662504,0.9863282961731052,0.009946745166676731,-0.011623690154554715,0.16408060292441468,0.8391904914966403,-0.14628937808293568,-0.04237786336781834,1.5698157820321466,0.2722594057651711,-0.25378210119797034,-0.0049752264865329686,0.04074777377028604,0.11742528470409477,0.22844033735409966,-0.482490027773406,-1.3304070818067208,2.454649456110946,0.8411642019876935,0.45536572868520764,-0.07118064098388079,0.09636379459917685,-0.12222462293632938,-0.0049752264865329686,0.04074777377028604,0.11742528470409477,0.22844033735409966,-0.482490027773406,-1.3304070818067208,2.454649456110946,0.8411642019876935,0.45536572868520764,-0.07118064098388079,0.09636379459917685,-0.12222462293632938,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2000024,1.0,0.0,0.0,1.0,0.6091308534871147,0.28756970498478196,0.5359882628594355,0.9864253290144174,0.02362939679311613,-0.007116359042421242,0.16234555528246353,0.8878551050009977,-0.14077190445614768,-0.016179806490420688,1.6764011846911036,0.21735963819583393,-0.23490911805930348,-0.005358018651392049,0.045190538555523976,0.13738034933661988,0.01616178232157013,-0.027453629716708144,-0.489669028041539,2.5605006419751506,0.8583808466973486,0.32253819566964426,-0.06880061066672402,0.10468671840856159,-0.13611963518409506,-0.005358018651392049,0.045190538555523976,0.13738034933661988,0.01616178232157013,-0.027453629716708144,-0.489669028041539,2.5605006419751506,0.8583808466973486,0.32253819566964426,-0.06880061066672402,0.10468671840856159,-0.13611963518409506,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2166691,1.0,0.0,0.0,1.0,0.6240712727206608,0.29010198233955026,0.5362635102600469,0.986339042649152,0.036944780253619004,-0.003420298132207445,0.1604951018525274,0.9167276324262551,-0.14614307685158112,0.021628355457659502,1.5856119630793888,0.12281618759344404,-0.28952153969228334,0.01018672675733464,0.03254837779770664,0.14261861074577845,-0.009845334914126248,0.09810442865628839,-0.18862307606150372,2.6919775650339175,0.8416439370893396,0.15061902242379155,-0.07126249202245472,0.11026203562820508,-0.13503812694832942,0.01018672675733464,0.03254837779770664,0.14261861074577845,-0.009845334914126248,0.09810442865628839,-0.18862307606150372,2.6919775650339175,0.8416439370893396,0.15061902242379155,-0.07126249202245472,0.11026203562820508,-0.13503812694832942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2333357999999999,1.0,1.0,0.0,1.0,0.6396607794566636,0.2925761743191273,0.5369260985342161,0.9862443210159392,0.04937797982960741,-0.0006645613645672038,0.15774508781559243,0.9370467226859781,-0.1280688431353051,0.03511446513862791,1.4375770175392082,0.008603223610101352,-0.29397301114807384,0.020347895517394278,0.02307733201917511,0.14518642108020535,-0.07187398898917506,-0.151007737877071,-0.254160793024366,2.750153140339991,0.8466279778348477,0.023593652154575186,-0.06469611350810414,0.10872137267787614,-0.1320279175157701,0.020347895517394278,0.02307733201917511,0.14518642108020535,-0.07187398898917506,-0.151007737877071,-0.254160793024366,2.750153140339991,0.8466279778348477,0.023593652154575186,-0.06469611350810414,0.10872137267787614,-0.1320279175157701,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2500025,1.0,1.0,0.0,1.0,0.6550969993082117,0.29566875377362567,0.5375409245201511,0.9859501370315549,0.06055414705100298,0.000737059587201914,0.1556758790100403,0.9850181511953683,-0.135971621563794,0.022506207162710727,1.3457295330499595,-0.00475113957540485,-0.20560987438597964,0.2796103973758484,0.08286321229235138,0.19388827890671007,-0.03377784639443318,0.045861601743218953,-0.12850124074313687,2.760605339373353,0.8076246207248101,-0.09956238983517085,-0.051032485654995574,0.09890177431099106,-0.12336049439719483,0.2796103973758484,0.08286321229235138,0.19388827890671007,-0.03377784639443318,0.045861601743218953,-0.12850124074313687,2.760605339373353,0.8076246207248101,-0.09956238983517085,-0.051032485654995574,0.09890177431099106,-0.12336049439719483,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2666692,0.0,1.0,0.0,1.0,0.6723094578077424,0.29828951906747636,0.5376998848850001,0.9854202771778107,0.07150389238305385,0.0029481894762695415,0.15435471771115922,1.0031996313324938,-0.1541464161548225,0.016210038864027047,1.1643936212451496,0.0081567714901698,-0.2636192814576904,0.7638488743410384,0.21368894134627542,0.19475777867219238,-0.03489588700359705,0.026963684465462795,-0.11454781001937664,2.7767939951776857,0.7899044643986679,-0.23185092426090634,-0.056698619487679916,0.09482787546095915,-0.10152618840459515,0.7638488743410384,0.21368894134627542,0.19475777867219238,-0.03489588700359705,0.026963684465462795,-0.11454781001937664,2.7767939951776857,0.7899044643986679,-0.23185092426090634,-0.056698619487679916,0.09482787546095915,-0.10152618840459515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.2833359,0.0,1.0,0.0,1.0,0.688519020857508,0.30093910646011907,0.5378908091410796,0.9852657146138833,0.07964024155525537,0.004203588719159105,0.15129849098155118,0.9571706765416115,-0.14904829875643189,0.010064274217280747,0.8325204860717949,-0.09826053764556097,-0.3751938944506287,1.1718759900511668,0.4008112799843561,0.21237389368909076,-0.029188930971911265,-0.01211950863130493,-0.0705123931473528,2.7728277039307514,0.8366303462237182,-0.32594401376130006,-0.06066276425107488,0.08908473860723869,-0.08074840292647276,1.1718759900511668,0.4008112799843561,0.21237389368909076,-0.029188930971911265,-0.01211950863130493,-0.0705123931473528,2.7728277039307514,0.8366303462237182,-0.32594401376130006,-0.06066276425107488,0.08908473860723869,-0.08074840292647276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3000026,0.0,1.0,0.0,1.0,0.7042421333163753,0.3030931891592765,0.5377496916303407,0.9852863045580161,0.08539261444653684,0.0039413622670187165,0.1479981929344868,0.9284085277995965,-0.1511887754168621,-0.031048027746921586,0.5603612687580083,-0.1305019495673721,-0.38356924760270567,1.473722653986462,0.7012480457132132,0.2550135104805442,-0.0231794955537634,-0.03022532706045225,-0.041459177710241976,2.7334867954622335,0.8149566522167805,-0.388472528261783,-0.054926891964262516,0.07458059454167361,-0.05890103717939395,1.473722653986462,0.7012480457132132,0.2550135104805442,-0.0231794955537634,-0.03022532706045225,-0.041459177710241976,2.7334867954622335,0.8149566522167805,-0.388472528261783,-0.054926891964262516,0.07458059454167361,-0.05890103717939395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3166693,0.0,1.0,0.0,1.0,0.7195415546119569,0.30541293706994843,0.536558943863011,0.985432265499413,0.08914069318306515,0.003994908045540352,0.14477992830929612,0.9073319460740907,-0.13156250829340727,-0.06426921847214354,0.2733412939460803,-0.15058848258856725,-0.3759273159438659,1.6512317517914579,0.611310067099836,0.16985337233183714,-0.01683657466170435,-0.047671326731100507,-0.012788675483608562,2.6461301993926867,0.8114594415462862,-0.4224886784486066,-0.04752682852443469,0.05662130677672787,-0.03516417985067754,1.6512317517914579,0.611310067099836,0.16985337233183714,-0.01683657466170435,-0.047671326731100507,-0.012788675483608562,2.6461301993926867,0.8114594415462862,-0.4224886784486066,-0.04752682852443469,0.05662130677672787,-0.03516417985067754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.333336,0.0,1.0,0.0,1.0,0.734393762062787,0.3079867408519935,0.5354085007283192,0.9858039292457376,0.09021644448915649,0.0026948722379680767,0.14157804876117236,0.8903395824760798,-0.09626769309187422,-0.07553958042848605,-0.12072100324890717,-0.23371886643428724,-0.33409015070425563,1.9989643455565191,0.13786035127682322,0.15996012301951393,-0.003617773027372869,-0.06734301921405283,0.03583746507133752,2.493886382801638,0.8058495051991305,-0.4945184205420202,-0.03111450749415019,0.03032340073181789,-0.010774278072001726,1.9989643455565191,0.13786035127682322,0.15996012301951393,-0.003617773027372869,-0.06734301921405283,0.03583746507133752,2.493886382801638,0.8058495051991305,-0.4945184205420202,-0.03111450749415019,0.03032340073181789,-0.010774278072001726,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3500026999999999,0.0,1.0,0.0,1.0,0.7488458821840317,0.3111294949705949,0.5341092010261872,0.986410886352515,0.08768953890382199,0.0003834495343374676,0.13893869518077223,0.8894943827965787,-0.07753111163645021,-0.07437984392119766,-0.4639476269372012,-0.3383231110573199,-0.25639109338581434,2.3904876042596364,-0.0008306053710631469,0.27648171816452444,0.011292946591110438,-0.07771247284136142,0.08463591823802526,2.25756516303388,0.7303735538007357,-0.580656323889106,-0.010162731950604431,0.004592470359479495,0.005608489634083857,2.3904876042596364,-0.0008306053710631469,0.27648171816452444,0.011292946591110438,-0.07771247284136142,0.08463591823802526,2.25756516303388,0.7303735538007357,-0.580656323889106,-0.010162731950604431,0.004592470359479495,0.005608489634083857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3666694,0.0,1.0,0.0,1.0,0.7635448229921273,0.3140995995525089,0.5332199834374372,0.9870685303728934,0.08336433378972255,-0.0035605492931704355,0.13687010881862754,0.8660535888488756,-0.04008463394585271,-0.07783419120084775,-0.753608310686843,-0.475528886635507,-0.16726446378139595,2.6796726225820793,0.08660259976740646,0.34880724387441064,0.026590443161587134,-0.08231951358118242,0.13440249914777155,2.010593078862519,0.5685661391238218,-0.6325567762008559,0.012271823338716063,-0.017489012302175682,0.01359170950652228,2.6796726225820793,0.08660259976740646,0.34880724387441064,0.026590443161587134,-0.08231951358118242,0.13440249914777155,2.010593078862519,0.5685661391238218,-0.6325567762008559,0.012271823338716063,-0.017489012302175682,0.01359170950652228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.3833361,0.0,1.0,0.0,1.0,0.7769529021819688,0.3180746239693363,0.5321939587037422,0.9877921497487636,0.07637930434489171,-0.008917553756068534,0.1354745289621417,0.8188775094121036,-0.006844797313082407,-0.09298281952069934,-1.0844670123630649,-0.564595386581828,-0.14836616997348004,2.9831079256025297,0.18814822508724732,0.35949443059425107,0.0347294871776913,-0.09951423318021248,0.17987781911860995,1.6953858891105074,0.2838662195073753,-0.6636977752857433,0.023459214028668216,-0.03723468718457653,0.0329435937705756,2.9831079256025297,0.18814822508724732,0.35949443059425107,0.0347294871776913,-0.09951423318021248,0.17987781911860995,1.6953858891105074,0.2838662195073753,-0.6636977752857433,0.023459214028668216,-0.03723468718457653,0.0329435937705756,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4000028,0.0,1.0,0.0,1.0,0.7898863457155649,0.32162599757246507,0.5311691000173985,0.9886740783290211,0.06680732620633108,-0.015115021896217024,0.13353607796583866,0.7726609949590988,-0.014529642018999755,-0.08201349365784985,-1.2645894481459825,-0.6380115453605149,-0.146826047855087,3.1693892877394214,0.3545173075651945,0.3778611943815583,0.03760955447873669,-0.10819776628299031,0.20955812890471714,1.2633214325924367,-0.025502118029750217,-0.7322875656280707,0.029174540917629565,-0.046215827944511484,0.04175277928135936,3.1693892877394214,0.3545173075651945,0.3778611943815583,0.03760955447873669,-0.10819776628299031,0.20955812890471714,1.2633214325924367,-0.025502118029750217,-0.7322875656280707,0.029174540917629565,-0.046215827944511484,0.04175277928135936,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4166695,0.0,1.0,0.0,1.0,0.8019398079811667,0.324732704237118,0.530653104792245,0.9893594113062256,0.05699408030430489,-0.022076404719661828,0.13203129335395716,0.7258292717827872,-0.011534594260969644,-0.057604529712259586,-1.2775473546689977,-0.6907941760683178,-0.1198336383085011,3.2076012490001515,0.5179962028426139,0.40999500688493384,0.0378884884084497,-0.10122182582349723,0.22182365196010131,0.813528866629962,-0.28342868485303063,-0.838592170024808,0.03470328870878754,-0.047369516518444954,0.037520980698850376,3.2076012490001515,0.5179962028426139,0.40999500688493384,0.0378884884084497,-0.10122182582349723,0.22182365196010131,0.813528866629962,-0.28342868485303063,-0.838592170024808,0.03470328870878754,-0.047369516518444954,0.037520980698850376,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4333362,0.0,1.0,0.0,1.0,0.8133699909871244,0.32774511267071593,0.5306431793840086,0.9898967497021548,0.047306289658053474,-0.0292037695670529,0.1304364969284761,0.6907873003086931,0.0019740737352028637,-0.046020504840065354,-1.219722913979234,-0.6857542304750717,-0.12234254246023882,3.144529144203746,0.6616290154707027,0.4543879155332855,0.03305009817430767,-0.09464852649935744,0.2177434000394045,0.5476244169792298,-0.47776607589063597,-0.5545423520865699,0.032771546814420564,-0.043335069821941775,0.03397788599034848,3.144529144203746,0.6616290154707027,0.4543879155332855,0.03305009817430767,-0.09464852649935744,0.2177434000394045,0.5476244169792298,-0.47776607589063597,-0.5545423520865699,0.032771546814420564,-0.043335069821941775,0.03397788599034848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4500028999999999,0.0,1.0,1.0,1.0,0.8241958844963734,0.33083395614433075,0.5307497158144001,0.9902631252898856,0.03842214835862085,-0.03594606159082717,0.12888196872613747,0.6773090048152693,0.016469474133850026,-0.0517757668838467,-1.1411847953783472,-0.6441838719706077,-0.14102066410536426,2.9635604075642266,0.8217776587725277,0.46185274539650123,0.025912130677695683,-0.08993573522362358,0.20552010166259205,0.28444150711406696,-0.28844960426760424,-0.20447952091394864,0.026674353806580627,-0.037528399322514554,0.032541039432851,2.9635604075642266,0.8217776587725277,0.46185274539650123,0.025912130677695683,-0.08993573522362358,0.20552010166259205,0.28444150711406696,-0.28844960426760424,-0.20447952091394864,0.026674353806580627,-0.037528399322514554,0.032541039432851,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4666696,0.0,1.0,1.0,1.0,0.8351027532482426,0.3341220720272411,0.5307944660818307,0.9905505943828095,0.029943304809726592,-0.04219994769974647,0.1270121367392631,0.6929159776957171,0.03130617111580586,-0.07394208193798328,-0.9996441809740867,-0.5670795177353048,-0.19022383859113629,2.5870101665605807,0.8880429030106787,0.37557661461698294,0.016109622775497046,-0.08761086265580602,0.18076949322250688,0.06608373510452968,-0.002423130657920179,-0.16664040957549023,0.03775913091013532,-0.0748772225658235,0.2670694046155209,2.5870101665605807,0.8880429030106787,0.37557661461698294,0.016109622775497046,-0.08761086265580602,0.18076949322250688,0.06608373510452968,-0.002423130657920179,-0.16664040957549023,0.03775913091013532,-0.0748772225658235,0.2670694046155209,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.4833363,0.0,1.0,1.0,0.0,0.8463877452223623,0.33776803599876354,0.5304555598069494,0.9907842041774811,0.023258290021706717,-0.04733646100841121,0.12475965756950746,0.684795938091888,0.048196450563242066,-0.054288273314377,-0.9249409157969758,-0.40401712887882485,-0.23119017430361477,2.2617138047312833,0.9065107031415766,0.262854574655513,0.004741316501006298,-0.08889756258176075,0.14904380211385165,0.0593369911659408,0.0011278485681772072,-0.13821502986088108,0.15719731526597122,0.02847585965179007,0.39811996551975554,2.2617138047312833,0.9065107031415766,0.262854574655513,0.004741316501006298,-0.08889756258176075,0.14904380211385165,0.0593369911659408,0.0011278485681772072,-0.13821502986088108,0.15719731526597122,0.02847585965179007,0.39811996551975554,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.500003,0.0,1.0,1.0,0.0,0.856874974934417,0.3413745679981328,0.5313236023738838,0.9910738013981635,0.015697461087114412,-0.05070458828461959,0.12229208733397014,0.6423174506647097,0.04879551779395902,0.009862350020046247,-0.904333878439711,-0.09118858584910172,-0.14198518634016552,2.0127109917577193,0.8689732262413018,0.15079050256184617,-0.0025215511846767955,-0.07280263203546067,0.10095202858187732,0.034827401011021566,-0.018326376437853467,-0.0996431796411821,0.34226528939102396,0.2103493030057293,0.37440104355585635,2.0127109917577193,0.8689732262413018,0.15079050256184617,-0.0025215511846767955,-0.07280263203546067,0.10095202858187732,0.034827401011021566,-0.018326376437853467,-0.0996431796411821,0.34226528939102396,0.2103493030057293,0.37440104355585635,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5166697,0.0,1.0,1.0,0.0,0.8666192338251568,0.34448667201998584,0.5330469462164632,0.9912486847287356,0.008629273860822151,-0.05063712613863081,0.12160370928802773,0.6595522767179318,0.04142492108197915,0.025905020677005883,-0.6109455026265826,0.2441911323418217,0.017372585746884595,1.7037237441916389,0.7279902526727919,-0.06279244017334255,-0.005914797790679882,-0.03160011460988793,0.022965390995500733,-0.0025755021176497297,-0.03453098562887879,-0.032174754547062936,0.5007847523332928,0.29020301989961356,0.5873298890815017,1.7037237441916389,0.7279902526727919,-0.06279244017334255,-0.005914797790679882,-0.03160011460988793,0.022965390995500733,-0.0025755021176497297,-0.03453098562887879,-0.032174754547062936,0.5007847523332928,0.29020301989961356,0.5873298890815017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5333364,0.0,1.0,1.0,0.0,0.8776781718756452,0.3479698892264155,0.5344423469435775,0.9913501535577697,0.005096697101325737,-0.04790607201105908,0.12208155054763686,0.7424283907871485,0.025795361458589516,-0.011280134346559945,-0.2413627276341493,0.4540995200141167,0.19727580995910918,1.3490776037517944,0.7689163736367616,-0.3863076082100568,-0.0036866331961161124,0.016613933998129955,-0.04415253336898558,-0.03541005395456285,-0.046779525990995524,0.028258902636783153,0.5340332455551774,0.3610309157880273,0.7445660135571774,1.3490776037517944,0.7689163736367616,-0.3863076082100568,-0.0036866331961161124,0.016613933998129955,-0.04415253336898558,-0.03541005395456285,-0.046779525990995524,0.028258902636783153,0.5340332455551774,0.3610309157880273,0.7445660135571774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5500030999999999,0.0,1.0,1.0,0.0,0.8903423308558036,0.3513071567104389,0.5350527311275316,0.9912284636109322,0.0035650397993924857,-0.04363344156935434,0.12469781953006816,0.7964704039747783,0.026538099921737723,-0.045660407256560606,0.050467928593408845,0.5219721253785339,0.3480708123155395,0.9619548626205595,0.972780563773358,-0.6313413038291151,0.0011968855289142945,0.05642595608139299,-0.08235466377964103,-0.055198967294570286,-0.0558644142339037,0.06447320391905946,0.5570323191899768,0.6127817341110697,0.6537896491119782,0.9619548626205595,0.972780563773358,-0.6313413038291151,0.0011968855289142945,0.05642595608139299,-0.08235466377964103,-0.055198967294570286,-0.0558644142339037,0.06447320391905946,0.5570323191899768,0.6127817341110697,0.6537896491119782,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5666698,0.0,1.0,1.0,0.0,0.9032118408860371,0.3554091643643262,0.5352429270296336,0.9910033061122897,0.00459455750655844,-0.03919100325267426,0.12788824253964592,0.8178490813006593,0.04964535129200204,-0.0878090805718233,0.22729950241347424,0.49170899990905403,0.3867638941863971,0.6293843837486097,0.9807547993628001,-0.7505747120073272,0.0027326844680822795,0.07248941935281718,-0.09499864411898007,-0.05873274645038727,-0.05301020612056638,0.07858769287696661,0.6569471792137709,0.8016770826838694,0.80668025983549,0.6293843837486097,0.9807547993628001,-0.7505747120073272,0.0027326844680822795,0.07248941935281718,-0.09499864411898007,-0.05873274645038727,-0.05301020612056638,0.07858769287696661,0.6569471792137709,0.8016770826838694,0.80668025983549,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.5833365,0.0,1.0,1.0,0.0,0.9164323844310551,0.3598641470873154,0.5342829911648206,0.9907083428823057,0.006020454826817699,-0.035056128085265356,0.13126995600952845,0.837956536125851,0.058906549089980664,-0.17021458189338398,0.3830211112963223,0.38524660895482155,0.3717277443892168,0.4399288293978078,0.6522824815709589,-0.7623039142967661,0.0036932500468391653,0.07919057325030013,-0.09424232895427262,-0.05376656170060235,-0.04226332179639845,0.08187366936252857,0.8363977436413221,0.8310762258741085,1.1663057610511198,0.4399288293978078,0.6522824815709589,-0.7623039142967661,0.0036932500468391653,0.07919057325030013,-0.09424232895427262,-0.05376656170060235,-0.04226332179639845,0.08187366936252857,0.8363977436413221,0.8310762258741085,1.1663057610511198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6000032,0.0,1.0,1.0,0.0,0.9299860831891131,0.3646781303894434,0.5315731289062686,0.9903772720324796,0.009861081751197723,-0.03202046318931926,0.1342769825597135,0.8554751198192367,0.06387162957081916,-0.209569491837203,0.5534703471564679,0.27473829635046826,0.32565787859628986,0.32592620232425445,0.2259964559680317,-0.6989150741647404,0.0031212717376346635,0.08188007720427484,-0.09417240717215376,-0.04708079762325673,-0.026587559453768297,0.08610485485383192,1.1557859679712585,0.9832341910311916,1.2449982471806444,0.32592620232425445,0.2259964559680317,-0.6989150741647404,0.0031212717376346635,0.08188007720427484,-0.09417240717215376,-0.04708079762325673,-0.026587559453768297,0.08610485485383192,1.1557859679712585,0.9832341910311916,1.2449982471806444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6166699,0.0,1.0,1.0,0.0,0.9437184569211804,0.3696788913199219,0.5292204164692643,0.9900348307076323,0.014367665229698795,-0.02933293723408571,0.1369824184878428,0.8726787390960709,0.07308615134505836,-0.16885854594125022,0.5716804042120017,0.28044431514485013,0.30240202700965557,0.1746276735946114,-0.023886922687539953,-0.6524791211251599,0.00034268712693935957,0.07960815469280033,-0.0964098313742942,-0.0455468467714028,-0.023444554661137203,0.0888969214258524,1.4843836610114318,0.8737911809144063,1.2412268340349448,0.1746276735946114,-0.023886922687539953,-0.6524791211251599,0.00034268712693935957,0.07960815469280033,-0.0964098313742942,-0.0455468467714028,-0.023444554661137203,0.0888969214258524,1.4843836610114318,0.8737911809144063,1.2412268340349448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6333366,0.0,1.0,1.0,0.0,0.9575756228065446,0.37509279173898524,0.5278102876590639,0.9896870173393544,0.01850450193931443,-0.026160938262841254,0.1396166051267482,0.8684955791695511,0.0780745930659541,-0.10129379392759762,0.43265882911238923,0.3267822577996886,0.28110720848626664,0.01780261044241016,-0.16766341915197014,-0.5931141782519052,-0.002472559784667838,0.06878955685696181,-0.08947982100975313,-0.04344967106555079,-0.02825133249696554,0.08075041213361678,1.7674972898606263,0.6892980431629454,1.07956433302261,0.01780261044241016,-0.16766341915197014,-0.5931141782519052,-0.002472559784667838,0.06878955685696181,-0.08947982100975313,-0.04344967106555079,-0.02825133249696554,0.08075041213361678,1.7674972898606263,0.6892980431629454,1.07956433302261,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6500033,1.0,1.0,1.0,0.0,0.9709357790666948,0.38029885665089413,0.5275758737060635,0.9893960066869287,0.020620447265594827,-0.023026822883854218,0.14191583609450087,0.8594530435632608,0.0842221902468413,-0.05463027926354143,0.31067279229370315,0.35988863725488973,0.29201964059102853,-0.061060902265652,-0.10168673996546453,-0.28910787145323874,-0.003130730791341729,0.06418880836874599,-0.08214012523936169,-0.04288437209462606,-0.03649333199460919,0.07251517177226638,2.109764713324902,0.7393298484523264,0.7835264545565007,-0.061060902265652,-0.10168673996546453,-0.28910787145323874,-0.003130730791341729,0.06418880836874599,-0.08214012523936169,-0.04288437209462606,-0.03649333199460919,0.07251517177226638,2.109764713324902,0.7393298484523264,0.7835264545565007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6666699999999999,1.0,1.0,1.0,0.0,0.9843210350032917,0.385888857317406,0.527562007368689,0.9890254947200193,0.022664894406286062,-0.019593051245359195,0.14467544953539876,0.8615854487454733,0.08886259058814883,-0.023515293073081867,0.2041688060833483,0.39402224445851936,0.34012004488761016,-0.06831750590433877,0.04519907226605779,-0.038506459861516115,-0.0017321619060611962,0.06666190930994856,-0.07620660991682403,-0.04498775593383259,-0.049413593887889566,0.0655608308187069,2.504780811459199,0.8056515071766024,0.4833022464804922,-0.06831750590433877,0.04519907226605779,-0.038506459861516115,-0.0017321619060611962,0.06666190930994856,-0.07620660991682403,-0.04498775593383259,-0.049413593887889566,0.0655608308187069,2.504780811459199,0.8056515071766024,0.4833022464804922,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.6833367,1.0,1.0,1.0,0.0,0.9976059727871269,0.3913668203897911,0.5282108440934093,0.9886276002635939,0.022925886138955603,-0.016173660266490288,0.1477439828059866,0.8737062969584823,0.1001363935028034,0.0057952194276075135,0.15097912763441707,0.40482749697767006,0.4559655117623199,-0.08454969017004682,0.05538935493778785,-0.04478733397725949,0.003259269769386233,0.08362265318668251,-0.07152432458124013,-0.05058498132733267,-0.06941520532826968,0.06080167232159925,2.804350136298108,0.8115264088687152,0.16351591202620788,-0.08454969017004682,0.05538935493778785,-0.04478733397725949,0.003259269769386233,0.08362265318668251,-0.07152432458124013,-0.05058498132733267,-0.06941520532826968,0.06080167232159925,2.804350136298108,0.8115264088687152,0.16351591202620788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7000034,1.0,1.0,1.0,0.0,1.0111755302866592,0.39755404327395316,0.5290188824954791,0.9879477050376761,0.02403802299092407,-0.012722791142161202,0.1523799072943334,0.9225536325713808,0.09572729296367188,0.011063824429691137,0.08548857775969443,0.3881365677682289,0.5520050763820837,-0.09692874083413634,0.0628221471543362,-0.048099758910365976,0.008766876322165579,0.09688997934508453,-0.06158661892423355,-0.053225708818189825,-0.08664265091449225,0.05146040869988047,2.9567303503133404,0.7268496025539296,-0.022283192029832057,-0.09692874083413634,0.0628221471543362,-0.048099758910365976,0.008766876322165579,0.09688997934508453,-0.06158661892423355,-0.053225708818189825,-0.08664265091449225,0.05146040869988047,2.9567303503133404,0.7268496025539296,-0.022283192029832057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7166701,1.0,1.0,1.0,0.0,1.025950509238175,0.40362708356358423,0.5297166290952723,0.9872746178466549,0.02323322067157113,-0.009795741485032884,0.1570130244970977,0.9686277061186269,0.07982151420196543,0.024971959523750392,-0.18483380032236676,0.38555861497057375,0.5614736632001932,-0.09437775414048072,0.0509397041602199,-0.07487343453797507,0.012062789718691888,0.08405624147027602,-0.034963340622875407,-0.04786622709619159,-0.10025274171352895,0.02402541476248067,2.973914096120344,0.6215135903142203,-0.10379434713944287,-0.09437775414048072,0.0509397041602199,-0.07487343453797507,0.012062789718691888,0.08405624147027602,-0.034963340622875407,-0.04786622709619159,-0.10025274171352895,0.02402541476248067,2.973914096120344,0.6215135903142203,-0.10379434713944287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7333368,1.0,1.0,1.0,0.0,1.041028865622604,0.41003539965133934,0.5308241796287504,0.9866065740768875,0.01989725566040985,-0.007091426513574339,0.16174448638347472,1.0146442618207296,0.07810004309931318,0.04610482977561002,-0.5241194709666155,0.364603407406884,0.5726506647987825,-0.08989953588183607,0.03583788598968019,-0.10616906066127939,0.01793907369584264,0.0683903906205784,0.0009093109700458531,-0.040566076215393335,-0.11691915170845588,-0.012184429831397826,2.90389875131637,0.5829129652578668,-0.21681642945424423,-0.08989953588183607,0.03583788598968019,-0.10616906066127939,0.01793907369584264,0.0683903906205784,0.0009093109700458531,-0.040566076215393335,-0.11691915170845588,-0.012184429831397826,2.90389875131637,0.5829129652578668,-0.21681642945424423,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7500035,1.0,1.0,1.0,0.0,1.0571558010030946,0.41681310069469985,0.5320392825824583,0.9859336011163511,0.013569138882998313,-0.005417346267785614,0.1664976426834111,1.056603260500239,0.07538694729154471,0.07004018158358219,-0.8998626208738012,0.3128788807279906,0.5328882994149375,-0.07554796683004505,0.012771053669076141,-0.13673161365283656,0.024024307844317482,0.04312888121861941,0.04483391310416891,-0.02823439094165713,-0.1276052961098627,-0.05489633822412427,2.87454604197641,0.6325649348243058,-0.34335507514181973,-0.07554796683004505,0.012771053669076141,-0.13673161365283656,0.024024307844317482,0.04312888121861941,0.04483391310416891,-0.02823439094165713,-0.1276052961098627,-0.05489633822412427,2.87454604197641,0.6325649348243058,-0.34335507514181973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7666701999999999,1.0,1.0,1.0,0.0,1.073454493179571,0.42389937803943634,0.5337559367188175,0.9853384979269418,0.004196882524038578,-0.004587027655087289,0.17049747756916836,1.0658122917414432,0.08658705946948148,0.054186096713187346,-1.2026146510706992,0.2488762137938793,0.48674937864038603,-0.060367065334140185,-0.008553516479786248,-0.1579240325639867,0.22949024539130675,0.03752993570241306,0.20609391396905968,-0.01605820239125286,-0.1350267594466943,-0.0906736152015038,2.851369205842581,0.6240266451111683,-0.4772157914028934,-0.060367065334140185,-0.008553516479786248,-0.1579240325639867,0.22949024539130675,0.03752993570241306,0.20609391396905968,-0.01605820239125286,-0.1350267594466943,-0.0906736152015038,2.851369205842581,0.6240266451111683,-0.4772157914028934,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.7833369,1.0,0.0,1.0,0.0,1.0896323309824492,0.4314492660501561,0.5342366993745956,0.9846345798731954,-0.006920557884690839,-0.004789125639910869,0.17442452313853646,1.0888894966570428,0.10969269930702602,-0.003611875714367146,-1.4349405159527617,0.16197484061451484,0.4197343207104736,-0.041441640446754816,-0.029315093834680596,-0.1675201780309737,0.684115787709551,0.13378732767895515,0.3374199771960058,-0.0025295733822158256,-0.13706972858763608,-0.12182429664708085,2.8621991605668007,0.5245916173277546,-0.6619100593310394,-0.041441640446754816,-0.029315093834680596,-0.1675201780309737,0.684115787709551,0.13378732767895515,0.3374199771960058,-0.0025295733822158256,-0.13706972858763608,-0.12182429664708085,2.8621991605668007,0.5245916173277546,-0.6619100593310394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8000036,1.0,0.0,1.0,0.0,1.1062863863061114,0.4398013432524575,0.5338343037179402,0.9839450530598085,-0.019850452189572654,-0.006071069268630707,0.17726035717253794,1.0940883676859599,0.10902630284563747,-0.028209039412199287,-1.5936055286691715,0.10060717047978263,0.2669220922564311,-0.011953704087596207,-0.05651001353996724,-0.17228967965055705,1.2931001564041422,0.4437837139849731,0.3481756573721364,0.012953617948459522,-0.12412682514192044,-0.14238610414451988,2.998720235855691,0.5312065440501373,-0.8344360591251254,-0.011953704087596207,-0.05651001353996724,-0.17228967965055705,1.2931001564041422,0.4437837139849731,0.3481756573721364,0.012953617948459522,-0.12412682514192044,-0.14238610414451988,2.998720235855691,0.5312065440501373,-0.8344360591251254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8166703,1.0,0.0,1.0,0.0,1.1225584899078123,0.4475479989168312,0.5333264781359695,0.9833228217527031,-0.03337448002960936,-0.00777968574555574,0.17861088654602036,1.0780239603632908,0.1111982749362968,-0.037988258711871815,-1.475025935338257,0.05380515207829317,0.2130290023779901,-0.0031644934221469094,-0.058577736233146965,-0.15262413481604822,2.1627704851784086,1.037210794181302,0.37287273798783654,0.016983320276471373,-0.11229499602889836,-0.13368405298119282,3.1518930998051466,0.5250121602693922,-1.0194571947808462,-0.0031644934221469094,-0.058577736233146965,-0.15262413481604822,2.1627704851784086,1.037210794181302,0.37287273798783654,0.016983320276471373,-0.11229499602889836,-0.13368405298119282,3.1518930998051466,0.5250121602693922,-1.0194571947808462,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.833337,1.0,0.0,1.0,0.0,1.1386578986004152,0.45582467655080966,0.5324387908067296,0.9825279363342841,-0.0442135627373709,-0.009449892012146119,0.18054006406811873,1.066368000005282,0.11846037575546003,-0.06523015126733327,-1.0621561058237348,0.021699453937315816,0.2624854022505645,-0.01664705257316889,-0.03254818848441386,-0.10802253637903844,2.7178703816750747,1.626481982812748,0.3632071323387433,0.008614552094786185,-0.09898685496246812,-0.09554040837813246,3.221013896351733,0.3260615042851093,-1.1744658008533084,-0.01664705257316889,-0.03254818848441386,-0.10802253637903844,2.7178703816750747,1.626481982812748,0.3632071323387433,0.008614552094786185,-0.09898685496246812,-0.09554040837813246,3.221013896351733,0.3260615042851093,-1.1744658008533084,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8500037,1.0,0.0,1.0,0.0,1.1544581184127773,0.46368263029148443,0.530897074711966,0.9817902080134662,-0.050877657141719566,-0.010416050273206922,0.18273192755878986,1.0583880695230121,0.08223842731892128,-0.07850517128700069,-0.7731855188008718,-0.022088927335113584,0.2710854811479547,-0.02174856377005932,-0.015439243988378383,-0.07378666924180662,2.861478179922625,2.0590246797698497,0.43953442424586464,0.005099913572775232,-0.08506339277032084,-0.07210840180334399,3.1663732707260586,0.09843521991945614,-1.197200458096538,-0.02174856377005932,-0.015439243988378383,-0.07378666924180662,2.861478179922625,2.0590246797698497,0.43953442424586464,0.005099913572775232,-0.08506339277032084,-0.07210840180334399,3.1663732707260586,0.09843521991945614,-1.197200458096538,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8666703999999998,1.0,0.0,1.0,0.0,1.1706953589076612,0.4708132861384778,0.5296173438322009,0.9810459310304955,-0.0568439203935873,-0.011935036672850376,0.18486536945142923,1.0535687490731331,0.0439457610207627,-0.09239535498470659,-0.36245373525167,-0.08826107170727655,0.3163598824959705,-0.03489280506849206,0.014400356088416139,-0.02647931704479528,3.179851649336641,2.46987288725843,0.5529173590692977,-0.002415529740641924,-0.0683600676053242,-0.040356169043272834,3.059419745336689,-0.06809648931526184,-1.0846089930121103,-0.03489280506849206,0.014400356088416139,-0.02647931704479528,3.179851649336641,2.46987288725843,0.5529173590692977,-0.002415529740641924,-0.0683600676053242,-0.040356169043272834,3.059419745336689,-0.06809648931526184,-1.0846089930121103,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.8833370999999999,1.0,0.0,1.0,0.0,1.186774242666715,0.47749411256074076,0.5277524697870373,0.9804697685141202,-0.0565990674037674,-0.012657275039618998,0.18792384624486302,1.0277239439416037,0.031696121330407334,-0.12192971877807235,0.26219851326856297,-0.1461486495536247,0.398553335999474,-0.05923319532472986,0.06036278767026257,0.03927817436425333,3.4337597732126257,2.7963878420800157,0.5667323905341031,-0.017254822245296828,-0.044585779357680135,0.012110025049898753,2.7054327475808786,-0.14846477305783018,-0.8508974811020398,-0.05923319532472986,0.06036278767026257,0.03927817436425333,3.4337597732126257,2.7963878420800157,0.5667323905341031,-0.017254822245296828,-0.044585779357680135,0.012110025049898753,2.7054327475808786,-0.14846477305783018,-0.8508974811020398,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9000038,1.0,0.0,1.0,0.0,1.202321788227303,0.48402991234794285,0.5255795944794648,0.9800024042202327,-0.05218622916950025,-0.013113096880009618,0.19157226286142737,0.9780984979385368,0.013618644979366934,-0.15292295620309324,0.5368004862939795,-0.2700730724969198,0.3301403665086598,-0.0508011556528151,0.0726678643897918,0.08513016002798547,3.5995054168795653,2.9751033823679442,0.6158474193286736,-0.013721092444387874,-0.017610588531737383,0.021507358266430722,1.9062352493355357,-0.0970420865794547,-0.43694296978169306,-0.0508011556528151,0.0726678643897918,0.08513016002798547,3.5995054168795653,2.9751033823679442,0.6158474193286736,-0.013721092444387874,-0.017610588531737383,0.021507358266430722,1.9062352493355357,-0.0970420865794547,-0.43694296978169306,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9166705,1.0,0.0,1.0,1.0,1.217036401912434,0.4897031039193592,0.5228218946908177,0.9798244450860542,-0.047034962851652186,-0.015057672994509403,0.1936621686477258,0.9302622182468413,-3.3440430390607734e-05,-0.19290965410634642,0.7334285103698304,-0.4489057354222117,0.221190103154325,-0.032722993073781834,0.07708023141462174,0.13306007980014486,3.7280143737332265,2.938962416850297,0.6500377519736622,-0.0039019346996908414,0.011031222784073282,0.016641562942804982,0.7237258855233105,-0.008984443499647155,-0.1588190235636143,-0.032722993073781834,0.07708023141462174,0.13306007980014486,3.7280143737332265,2.938962416850297,0.6500377519736622,-0.0039019346996908414,0.011031222784073282,0.016641562942804982,0.7237258855233105,-0.008984443499647155,-0.1588190235636143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9333372,1.0,0.0,1.0,1.0,1.231297869528336,0.4952857616600882,0.5195308248430542,0.9797285485346416,-0.03881271287938208,-0.017896188797468078,0.19571732404586045,0.8831071394912551,-0.004045504579837322,-0.20048343639945176,1.1623590471052727,-0.5733441202359488,0.24169422793063383,-0.042046430687901114,0.10330528236639218,0.19378782105444806,3.6530360265723303,2.7334083044123565,0.5429179461821437,-0.0088069127182638,0.03175250178654711,0.0426559023785634,0.04753767195092054,0.03544288754757423,-0.18800399710825919,-0.042046430687901114,0.10330528236639218,0.19378782105444806,3.6530360265723303,2.7334083044123565,0.5429179461821437,-0.0088069127182638,0.03175250178654711,0.0426559023785634,0.04753767195092054,0.03544288754757423,-0.18800399710825919,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9500039,1.0,0.0,1.0,1.0,1.2445867293207522,0.5004475265954929,0.5167597506348052,0.9795694249327929,-0.02625767973158528,-0.020466696832148978,0.19833151618623768,0.8496470955010892,0.006144309338464493,-0.17310033422210305,1.734467716843726,-0.4792268220570095,0.4404005437451001,-0.09047933318270421,0.1447086232906705,0.235798343328596,3.450116564779171,2.5034248523908054,0.22928811532155338,-0.036592589635729734,0.027094683912116283,0.11073392218530623,0.06163755709808464,0.048482843823866084,-0.23255093956783113,-0.09047933318270421,0.1447086232906705,0.235798343328596,3.450116564779171,2.5034248523908054,0.22928811532155338,-0.036592589635729734,0.027094683912116283,0.11073392218530623,0.06163755709808464,0.048482843823866084,-0.23255093956783113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9666706,1.0,0.0,1.0,1.0,1.257579782167841,0.5062592593375709,0.5146020264987753,0.9787815158599648,-0.009076467693273539,-0.019816568172300663,0.20374411788062757,0.8467557065446527,0.03321549131788487,-0.1242149538962767,2.0520697669267687,-0.2547397409592198,0.5401366551208238,-0.12195928909559943,0.156896745401978,0.23643406876908957,3.0687813873703265,2.2557827399360835,-0.23545382417404567,0.21385541001147432,0.10701983018049985,0.35537307935849405,0.05644731752996926,0.05870849987827579,-0.23494801985961447,-0.12195928909559943,0.156896745401978,0.23643406876908957,3.0687813873703265,2.2557827399360835,-0.23545382417404567,0.21385541001147432,0.10701983018049985,0.35537307935849405,0.05644731752996926,0.05870849987827579,-0.23494801985961447,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +1.9833372999999999,1.0,0.0,0.0,1.0,1.2701811936153249,0.5126900403127596,0.5135850915742026,0.9779634301707181,0.007893042059746554,-0.01755248417421153,0.20788732389224718,0.8694847896859434,0.052153043718063286,-0.07751312154698664,1.852483488355591,-0.036572193509885054,0.43573994583944886,-0.10942545047266307,0.12600348825629204,0.1898226609935226,2.5320846640421606,1.9947899481684852,-0.6733075007266957,0.6193333092054252,0.21152296348904995,0.6608633943840323,0.03132770354756164,0.05888750918565636,-0.1877986817269087,-0.10942545047266307,0.12600348825629204,0.1898226609935226,2.5320846640421606,1.9947899481684852,-0.6733075007266957,0.6193333092054252,0.21152296348904995,0.6608633943840323,0.03132770354756164,0.05888750918565636,-0.1877986817269087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.000004,1.0,0.0,0.0,1.0,1.2834125661774134,0.5196827347388829,0.5131244522757832,0.9770654431339711,0.021109829881581964,-0.014058731260762672,0.2114233832647775,0.9424912889485626,0.05435872437336875,-0.0467642542294851,1.2914738280584726,0.14855845972499349,0.30161706679786154,-0.08273241865963683,0.08154692719024874,0.10862245984966615,2.0243682608700397,1.7490428862827474,-0.8677291894832493,0.9270760117928262,0.3511578118054485,0.8059122554275097,0.01128125626257126,0.039705826057040566,-0.10880586848974581,-0.08273241865963683,0.08154692719024874,0.10862245984966615,2.0243682608700397,1.7490428862827474,-0.8677291894832493,0.9270760117928262,0.3511578118054485,0.8059122554275097,0.01128125626257126,0.039705826057040566,-0.10880586848974581,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0166707,1.0,0.0,0.0,1.0,1.298055818872961,0.527372989380746,0.5132357812458046,0.9765423112911986,0.02832484808124832,-0.010687583300741838,0.21318675569182916,1.0298518728117423,0.08365234043078978,-0.0030841842152985553,0.8465491347395033,0.34706411100858575,0.25072805491115396,-0.07324616009753568,0.05383718956518042,0.03549014543941263,1.5544504917323931,1.3342556546229305,-1.0787852361433676,1.230755806031907,0.6064573451861405,0.7750261808645873,0.002253391643146079,0.016330788555131925,-0.040736067893726774,-0.07324616009753568,0.05383718956518042,0.03549014543941263,1.5544504917323931,1.3342556546229305,-1.0787852361433676,1.230755806031907,0.6064573451861405,0.7750261808645873,0.002253391643146079,0.016330788555131925,-0.040736067893726774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0333373999999997,1.0,0.0,0.0,1.0,1.3134510255150031,0.5364919934715513,0.5142945329626184,0.9758348525835735,0.03360994697201518,-0.005530667915033163,0.21583818860467568,1.1037594455000204,0.12640755935778747,0.02755673699401953,0.5803323742320291,0.47018836143218024,0.36827594550177317,-0.091193473014139,0.05197020299146734,-0.008404572169213047,1.0867510003166259,0.44390516301141136,-1.4380274526776349,1.63006465703777,0.775983050717298,0.5963586347421217,0.01860372050813297,-0.009187922686319988,-0.0004986495803619143,-0.091193473014139,0.05197020299146734,-0.008404572169213047,1.0867510003166259,0.44390516301141136,-1.4380274526776349,1.63006465703777,0.775983050717298,0.5963586347421217,0.01860372050813297,-0.009187922686319988,-0.0004986495803619143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0500040999999998,1.0,0.0,0.0,1.0,1.3296445156002328,0.5466068127681009,0.5153494793540381,0.9749443636275299,0.03604580357359527,-0.0011725229039023805,0.21950583834077037,1.1720651851878876,0.15752230517116766,0.062526325937021,0.16970997782601835,0.4829768020955718,0.4926750938790685,-0.10306060845529304,0.04642188385251597,-0.05068587850651516,0.42267712796752077,0.20908832431662885,-0.8005158370736057,2.0095027065183366,0.906326416453247,0.5182015300410098,0.045601431344664344,-0.0397647510444158,0.039640686055328805,-0.10306060845529304,0.04642188385251597,-0.05068587850651516,0.42267712796752077,0.20908832431662885,-0.8005158370736057,2.0095027065183366,0.906326416453247,0.5182015300410098,0.045601431344664344,-0.0397647510444158,0.039640686055328805,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0666708,1.0,0.0,0.0,1.0,1.346535322271391,0.5577942096756121,0.5174472442953645,0.973936279984843,0.03459739568562576,0.002625081575845198,0.22415229574505371,1.2330789386961065,0.1992559128158487,0.10081980523254792,-0.2716569707689132,0.45629827367634396,0.6496006161210012,-0.11782315937114357,0.042255482711847675,-0.09037999288252285,-0.16946587531602478,0.38424778799653675,-0.0956993806372969,2.261820997625054,0.9961465567815145,0.543998370947871,0.08069267675263217,-0.07196857339860792,0.0776517861298259,-0.11782315937114357,0.042255482711847675,-0.09037999288252285,-0.16946587531602478,0.38424778799653675,-0.0956993806372969,2.261820997625054,0.9961465567815145,0.543998370947871,0.08069267675263217,-0.07196857339860792,0.0776517861298259,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.0833375,1.0,0.0,0.0,1.0,1.3637868505325295,0.5702965694338135,0.5195848145011412,0.9726374100096136,0.029973015424506082,0.004831899553586633,0.23033614510722658,1.2723664596933344,0.23633666678671955,0.10536908406604002,-0.48135251814524505,0.39409989796384226,0.7708885552376882,-0.13005298466957824,0.04327458587879248,-0.10184954902666198,-0.07472377748807427,0.06282654123379797,-0.23072169957078217,2.440118756149314,1.042433757349136,0.5015626025758491,0.10707873792253944,-0.08735836302155635,0.0899067724215472,-0.13005298466957824,0.04327458587879248,-0.10184954902666198,-0.07472377748807427,0.06282654123379797,-0.23072169957078217,2.440118756149314,1.042433757349136,0.5015626025758491,0.10707873792253944,-0.08735836302155635,0.0899067724215472,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1000042,1.0,1.0,0.0,1.0,1.3809992574111818,0.583640910821075,0.5216169109913467,0.9711833203231717,0.025346032042929637,0.006782464973149366,0.23688506739477377,1.2865687262334566,0.24646329208611906,0.10415702081865713,-0.6385037605406407,0.33999151802717353,0.7979478641553484,-0.1289465814831464,0.037318395457894005,-0.10982800335385236,0.09501470196113966,0.01350652947448245,-0.12773239144464188,2.5693210777379,1.1444437529006077,0.30040174199483927,0.11876784113122649,-0.09286119721236245,0.09905476427399497,-0.1289465814831464,0.037318395457894005,-0.10982800335385236,0.09501470196113966,0.01350652947448245,-0.12773239144464188,2.5693210777379,1.1444437529006077,0.30040174199483927,0.11876784113122649,-0.09286119721236245,0.09905476427399497,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1166709,1.0,1.0,0.0,1.0,1.3981657685496847,0.5971669069273831,0.5234328005724653,0.9697040439885595,0.018394273394835577,0.007461711981951396,0.24347492814006222,1.3000914665418906,0.24472080413342037,0.10975289593852425,-0.802917917642485,0.24102168485807635,0.8188515583892185,-0.012256214134457806,0.13526258376772932,-0.019455630664090392,0.023832313145994276,0.10330207306240669,0.04697396529768134,2.7807217381772094,1.2461676165575133,-0.008077522713776026,0.13132255797501186,-0.09653676590486862,0.10417481775644813,-0.012256214134457806,0.13526258376772932,-0.019455630664090392,0.023832313145994276,0.10330207306240669,0.04697396529768134,2.7807217381772094,1.2461676165575133,-0.008077522713776026,0.13132255797501186,-0.09653676590486862,0.10417481775644813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1333376,0.0,1.0,0.0,1.0,1.4154289851910302,0.6111836670453923,0.5253541444196526,0.968073761961274,0.011500166300151857,0.007170804857633541,0.25029885564043075,1.2959145025156216,0.23887285803960623,0.11784747058949284,-0.7847714316161132,0.1325298783267284,0.8224167178404281,0.3535412726411097,0.43984688613257883,0.02253718430168591,0.026979303334106836,0.10801322124448823,0.060159899496362156,2.950957405427142,1.328941646968373,-0.25139702255847957,0.13683541426230375,-0.08983820916278126,0.09056962049915834,0.3535412726411097,0.43984688613257883,0.02253718430168591,0.026979303334106836,0.10801322124448823,0.060159899496362156,2.950957405427142,1.328941646968373,-0.25139702255847957,0.13683541426230375,-0.08983820916278126,0.09056962049915834,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1500043,0.0,1.0,0.0,1.0,1.4321657334008033,0.624997368622384,0.527214434641596,0.9664119291241969,0.0052830205278683335,0.006171777040140766,0.2568695819062998,1.2554276811056801,0.21994978955485664,0.11331047135546533,-0.7119928382078581,0.00580585520062693,0.7986801450285694,1.0153600242288212,0.8635054219439458,0.017452147698450885,0.028805233104835147,0.11118134641775566,0.07068822251046378,3.087424636675414,1.4191662970699763,-0.4641127183899804,0.1375108374949734,-0.07893856858663925,0.06931488994515399,1.0153600242288212,0.8635054219439458,0.017452147698450885,0.028805233104835147,0.11118134641775566,0.07068822251046378,3.087424636675414,1.4191662970699763,-0.4641127183899804,0.1375108374949734,-0.07893856858663925,0.06931488994515399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.166671,0.0,1.0,0.0,1.0,1.4481668141862536,0.6383002379696199,0.528843159752261,0.9647200123081288,9.674650140893584e-05,0.0041517695837966825,0.2632452303492722,1.2028720570013929,0.20586763129875577,0.1071512488107211,-0.5452424952523353,-0.17259277394145645,0.7627482042049079,1.7022637989091713,1.5935147993349867,0.0007741359886821231,0.03011138833695424,0.11766904356279995,0.07985216598917266,3.2188190116280353,1.503679912551214,-0.616171581978829,0.13596522535630118,-0.06261337884373125,0.032020117195239846,1.7022637989091713,1.5935147993349867,0.0007741359886821231,0.03011138833695424,0.11766904356279995,0.07985216598917266,3.2188190116280353,1.503679912551214,-0.616171581978829,0.13596522535630118,-0.06261337884373125,0.032020117195239846,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.1833377,0.0,1.0,0.0,1.0,1.4632463868231247,0.6512810272922438,0.5304831590115943,0.9630846232665256,-0.002665429320103565,0.0010170765803702352,0.26918370951702064,1.1620927798397174,0.18930467924627403,0.07767722459730478,-0.40612199834603113,-0.37607306130783613,0.709557757661509,2.164724516621592,2.2309773113317832,0.06335423997309174,0.03282511284433866,0.12038807186086828,0.09620961449879606,3.3404479843333426,1.563047933407886,-0.6871787516928146,0.1337104174078103,-0.04649700879661146,-0.0059560822457877935,2.164724516621592,2.2309773113317832,0.06335423997309174,0.03282511284433866,0.12038807186086828,0.09620961449879606,3.3404479843333426,1.563047933407886,-0.6871787516928146,0.1337104174078103,-0.04649700879661146,-0.0059560822457877935,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2000044,0.0,1.0,0.0,1.0,1.4780190956428991,0.6637949707538107,0.53127194865296,0.9615217091607369,-0.004711787837434452,-0.0036720461526456505,0.27466400919130884,1.1234304643502666,0.16193330955593854,0.015955707675393598,-0.32409796073999664,-0.5434397803685144,0.6652543187749765,2.7760704635165556,2.4322750738687366,0.2969814204017538,0.03515676582953709,0.12106064753865903,0.11321309055141508,3.4057050578623387,1.6099607604554373,-0.7335942017064802,0.13297900736635482,-0.03472518711232787,-0.03363026355011294,2.7760704635165556,2.4322750738687366,0.2969814204017538,0.03515676582953709,0.12106064753865903,0.11321309055141508,3.4057050578623387,1.6099607604554373,-0.7335942017064802,0.13297900736635482,-0.03472518711232787,-0.03363026355011294,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2166711,0.0,1.0,0.0,1.0,1.4921869851049512,0.6756487572080281,0.5311226924662973,0.9599779827933417,-0.005406643680083034,-0.009115897181836155,0.27987486699365055,1.0695571767747176,0.13835829918186343,-0.05028974114105912,-0.2524035840975339,-0.6399588839907678,0.6480982192993127,3.3744138635437735,2.790488013460646,0.3799200468852131,0.034582594135442485,0.12394551675433882,0.12107576104840319,3.3541015310707656,1.6483868938212352,-0.7225048788136527,0.1336440534430009,-0.026658743839385015,-0.05142233865518144,3.3744138635437735,2.790488013460646,0.3799200468852131,0.034582594135442485,0.12394551675433882,0.12107576104840319,3.3541015310707656,1.6483868938212352,-0.7225048788136527,0.1336440534430009,-0.026658743839385015,-0.05142233865518144,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2333378,0.0,1.0,0.0,1.0,1.5056365592563512,0.6868363105232937,0.5300406789477664,0.9583758709437077,-0.005860825172757271,-0.015028696759677579,0.28505346690557826,1.0405761673294849,0.11992877026009063,-0.1031411703916585,-0.24701100342467042,-0.7360852395333678,0.6543251366837268,3.6226928075585594,3.2093160182439457,0.4624551256047315,0.035259277577846256,0.12809800139528313,0.13572619058891505,3.262605761405732,1.658250928095463,-0.6572516611663826,0.13987224235049456,-0.022451894965122766,-0.06221841949641111,3.6226928075585594,3.2093160182439457,0.4624551256047315,0.035259277577846256,0.12809800139528313,0.13572619058891505,3.262605761405732,1.658250928095463,-0.6572516611663826,0.13987224235049456,-0.022451894965122766,-0.06221841949641111,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2500044999999997,0.0,1.0,0.0,1.0,1.5191474277325674,0.6979449935312938,0.5284905527601098,0.9566532610550554,-0.006014072097537589,-0.02198101428261916,0.29033636365540033,1.0452185357553614,0.10081170305720163,-0.13876230735025252,-0.29300841657110205,-0.8044606583518773,0.623631326969253,3.6776131156425342,3.4301914756899623,0.6428342464577529,0.03572072487651868,0.1224450451434124,0.15157467110577535,3.1167586710409205,1.5887318346639874,-0.5698564034502368,0.14052369787888336,-0.019338273798699603,-0.06444744348895749,3.6776131156425342,3.4301914756899623,0.6428342464577529,0.03572072487651868,0.1224450451434124,0.15157467110577535,3.1167586710409205,1.5887318346639874,-0.5698564034502368,0.14052369787888336,-0.019338273798699603,-0.06444744348895749,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2666711999999998,0.0,1.0,0.0,1.0,1.5329146347273057,0.7089990469287143,0.526682108688652,0.9550364808455069,-0.0068622089754974466,-0.029214369149270232,0.2949656776260871,1.0082317311928308,0.09268550100253375,-0.1754590396422821,-0.2741921337712917,-0.8063358393737428,0.5859635659323336,3.4048211037010327,3.49684814649475,0.7985283374401617,0.03207925710083644,0.11651000901244794,0.15070190578672515,2.8377532301539077,1.4035784735234345,-0.39839458603437883,0.1356516792222986,-0.015131424708512173,-0.06488470065135647,3.4048211037010327,3.49684814649475,0.7985283374401617,0.03207925710083644,0.11651000901244794,0.15070190578672515,2.8377532301539077,1.4035784735234345,-0.39839458603437883,0.1356516792222986,-0.015131424708512173,-0.06488470065135647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.2833379,0.0,1.0,1.0,1.0,1.5454604006222599,0.7194690626761137,0.5242980145807066,0.9533492018900678,-0.006701883812610414,-0.03609156836789687,0.2996294089399077,0.9250541946183067,0.09394448432657922,-0.20056824527317435,-0.21742684688248612,-0.8543223087115723,0.6091224453983726,2.8732925734506507,3.369841699098435,0.8103075081337233,0.028861976086012157,0.12411395431301836,0.15321756448337884,1.3525272357235998,0.5996186180247033,-0.20392815391129673,0.14137615227026648,-0.010576465442776649,-0.07437047642468668,2.8732925734506507,3.369841699098435,0.8103075081337233,0.028861976086012157,0.12411395431301836,0.15321756448337884,1.3525272357235998,0.5996186180247033,-0.20392815391129673,0.14137615227026648,-0.010576465442776649,-0.07437047642468668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3000046,0.0,1.0,1.0,1.0,1.5568322848043419,0.7292583017320075,0.5219048689123081,0.9514486453012013,-0.006415293928516472,-0.04380556060252305,0.30460694709513503,0.8567135079450231,0.10246588361764115,-0.1903885288871681,-0.25102377135091714,-0.9071914035465342,0.6225605026461573,2.395735061894152,3.1257972154674873,0.6021705867484872,0.027566549398991124,0.12610827005033887,0.1656965082946963,0.05150858957993395,-0.08063342635865327,-0.13505126850573257,0.14798433674888364,-0.009164393325261816,-0.07518505167860369,2.395735061894152,3.1257972154674873,0.6021705867484872,0.027566549398991124,0.12610827005033887,0.1656965082946963,0.05150858957993395,-0.08063342635865327,-0.13505126850573257,0.14798433674888364,-0.009164393325261816,-0.07518505167860369,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3166713,0.0,1.0,1.0,1.0,1.5671845665152786,0.7389111932190726,0.5201125947372871,0.9494998620597238,-0.006529332604873853,-0.05168703257065485,0.3094120722084716,0.8109144342361296,0.10562958355629214,-0.1659450269121716,-0.49784715888820147,-0.8309553960116909,0.6013358721669033,2.088560311780429,2.786764875564418,0.3568233384027513,0.026803533000773767,0.10912717703719983,0.17998103222949827,0.06062712474602376,-0.08832888607495053,-0.14937014299381032,0.1463580937538238,-0.01962334363162485,-0.039143056415902086,2.088560311780429,2.786764875564418,0.3568233384027513,0.026803533000773767,0.10912717703719983,0.17998103222949827,0.06062712474602376,-0.08832888607495053,-0.14937014299381032,0.1463580937538238,-0.01962334363162485,-0.039143056415902086,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.333338,0.0,1.0,1.0,1.0,1.577041634469952,0.7481138335437612,0.5187910357591901,0.9475813774130176,-0.010523418960722185,-0.059476984153870684,0.3137535325528395,0.7983335021565713,0.12042773527529906,-0.1601018111710091,-0.7324130483251656,-0.5986066112761137,0.5547747329864964,1.8054507529512973,2.322596809381503,0.008335684975270154,0.022572376923655966,0.08488027588302412,0.1681377211300286,0.06076024224313444,-0.09768322424490669,-0.1432233228624609,0.21632549901270315,-0.08459358052027678,0.15522983190096457,1.8054507529512973,2.322596809381503,0.008335684975270154,0.022572376923655966,0.08488027588302412,0.1681377211300286,0.06076024224313444,-0.09768322424490669,-0.1432233228624609,0.21632549901270315,-0.08459358052027678,0.15522983190096457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3500047,0.0,1.0,1.0,0.0,1.5866230636205876,0.7580836626641929,0.5174087618578694,0.9458951705686471,-0.015522676913449452,-0.06488128744732706,0.3175402200281537,0.8445850697347227,0.0987343299311373,-0.18797450621107933,-1.032699609631056,-0.29427838652382277,0.6702737347121833,1.487028897435106,1.8575635456585684,-0.552513170401768,0.016744303247592077,0.08563761763615269,0.15178237779461476,0.05955428703008364,-0.1384046873978246,-0.1343216380287209,0.39547110641909744,-0.1849911364971098,0.38865234204948407,1.487028897435106,1.8575635456585684,-0.552513170401768,0.016744303247592077,0.08563761763615269,0.15178237779461476,0.05955428703008364,-0.1384046873978246,-0.1343216380287209,0.39547110641909744,-0.1849911364971098,0.38865234204948407,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3666714,0.0,1.0,1.0,0.0,1.5981405088465346,0.7677825745611655,0.5155267218633196,0.943412584745671,-0.0259848456745399,-0.06941721090346747,0.32323170260533846,0.9144791061648001,0.04172233992316826,-0.14132442150471664,-1.1087028711487101,0.06092845775793776,0.902610021921984,0.8301840072300968,1.7641174099586787,-1.0067749403715665,0.00594892235187961,0.11463996029501546,0.10283941781125074,0.0444154118307151,-0.190640144142802,-0.09697496200325384,0.5883240345094165,-0.22933417607821363,0.4867172981264156,0.8301840072300968,1.7641174099586787,-1.0067749403715665,0.00594892235187961,0.11463996029501546,0.10283941781125074,0.0444154118307151,-0.190640144142802,-0.09697496200325384,0.5883240345094165,-0.22933417607821363,0.4867172981264156,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.3833381,0.0,1.0,1.0,0.0,1.6102953714900223,0.7778631691280719,0.5160996140938222,0.940654825043668,-0.03436253915009916,-0.069478039346501,0.33039448856448916,0.9791393297155496,-0.009251917887613065,-0.016514301601515402,-0.9295609239716413,0.4517521980560974,1.0377853868514824,0.21838670567718207,1.4441589545211488,-1.2019153676817682,-0.007970956947077064,0.13436587335878172,0.021833899742824018,0.01673894627345698,-0.21756037419891397,-0.030291230212299583,0.7836856539848273,-0.1506005909309487,0.536579167908228,0.21838670567718207,1.4441589545211488,-1.2019153676817682,-0.007970956947077064,0.13436587335878172,0.021833899742824018,0.01673894627345698,-0.21756037419891397,-0.030291230212299583,0.7836856539848273,-0.1506005909309487,0.536579167908228,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4000048,0.0,1.0,1.0,0.0,1.623612551641719,0.7879747336798377,0.5185419710330643,0.9376741606826788,-0.04426675937650379,-0.06686419985038149,0.33813725198609046,1.049932214054383,-0.03817408167492839,0.055308778776460246,-0.7477906662054025,0.7646983032210934,1.1079312722059567,0.1380830849939762,0.6157600275368955,-1.1463577720626894,-0.019501272369374167,0.1411834683327871,-0.048723828397492605,-0.006837522119306408,-0.2297973281806935,0.028273261423752034,1.0683583086509183,0.054220565459239416,0.5681988601318645,0.1380830849939762,0.6157600275368955,-1.1463577720626894,-0.019501272369374167,0.1411834683327871,-0.048723828397492605,-0.006837522119306408,-0.2297973281806935,0.028273261423752034,1.0683583086509183,0.054220565459239416,0.5681988601318645,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4166715,0.0,1.0,1.0,0.0,1.6374901711381091,0.7993565169883322,0.5214235001018037,0.9347298405960516,-0.05161983251463273,-0.060900053153197325,0.34627547056697366,1.1247776101283296,-0.027224101970973635,0.0789158290225158,-0.38754163775866685,0.9087547262719788,1.1580656780201741,0.11166517785512325,0.013512708860936322,-0.7304003760574606,-0.03196007780458721,0.1554341843919183,-0.11196386714599756,-0.028194638750209857,-0.2255574367071243,0.0833291162343178,1.4142684168414021,0.39250265577935406,0.4519064479507731,0.11166517785512325,0.013512708860936322,-0.7304003760574606,-0.03196007780458721,0.1554341843919183,-0.11196386714599756,-0.028194638750209857,-0.2255574367071243,0.0833291162343178,1.4142684168414021,0.39250265577935406,0.4519064479507731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4333382,0.0,1.0,1.0,0.0,1.652024081994632,0.8119391535848817,0.5241930269699733,0.9315900097973908,-0.056729254057513126,-0.053923796643949064,0.35498460464543746,1.212232012831395,-0.016776000112630973,0.09877268897238584,-0.015373402894746091,0.9121976455693754,1.1576986849010875,0.08801015581152209,-0.19836004122021014,-0.34990868206716924,-0.04303113123699171,0.16448910575531867,-0.1539069267980733,-0.0415128764661521,-0.20811687426235742,0.1214638478370323,1.66335678670698,0.7770596707399903,0.30291935832371253,0.08801015581152209,-0.19836004122021014,-0.34990868206716924,-0.04303113123699171,0.16448910575531867,-0.1539069267980733,-0.0415128764661521,-0.20811687426235742,0.1214638478370323,1.66335678670698,0.7770596707399903,0.30291935832371253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4500049,1.0,1.0,1.0,0.0,1.6673821246464773,0.8261367578515968,0.5271884018225313,0.9287032926925716,-0.05831053344205381,-0.04570331437270631,0.36334733092046867,1.2755441008689161,-0.020889670284370554,0.09424673479772003,0.20498335980690582,0.8157506896709887,1.149379046141655,-0.05789201250816236,-0.09443883825418864,-0.1964976196219641,-0.05042710698693654,0.17223363812941606,-0.1637635766498734,-0.04167178093322029,-0.19395516732627102,0.1325642687525535,1.771364335015702,1.1149041860339852,0.321850874537234,-0.05789201250816236,-0.09443883825418864,-0.1964976196219641,-0.05042710698693654,0.17223363812941606,-0.1637635766498734,-0.04167178093322029,-0.19395516732627102,0.1325642687525535,1.771364335015702,1.1149041860339852,0.321850874537234,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4666715999999997,1.0,1.0,1.0,0.0,1.6832044792892848,0.8405888134697792,0.529206337659587,0.925458566290274,-0.05935508200869819,-0.038934107118376284,0.3721391562609154,1.2769257784722827,-0.025115132562282858,0.08413629069055101,0.3416064553439253,0.6834778716141383,1.1567517635448827,-0.23078678373753403,0.02650755384344245,-0.0980630904193708,-0.05657940961975335,0.18123757720542746,-0.1592174598518618,-0.03597666686774592,-0.18529241156834156,0.13125028938716893,1.7617035221649586,1.2891089363665251,0.4105318939785736,-0.23078678373753403,0.02650755384344245,-0.0980630904193708,-0.05657940961975335,0.18123757720542746,-0.1592174598518618,-0.03597666686774592,-0.18529241156834156,0.13125028938716893,1.7617035221649586,1.2891089363665251,0.4105318939785736,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.4833382999999998,1.0,1.0,1.0,0.0,1.6982748858781629,0.8552791492690962,0.5312679136916266,0.9223168082968017,-0.05803553949952068,-0.03187647304894402,0.38071967607960616,1.2567227402398726,-0.03916652389017711,0.10226689068711733,0.48487614209444513,0.6029530536804316,1.0885614010711138,-0.22562604249333834,0.03009031967907361,-0.06817073304700974,0.060412434445756946,0.23907789548382086,-0.03828029795020312,-0.034695872206381866,-0.16612695679628167,0.13476814425300332,1.8398768690768232,1.277746493329271,0.44759401465440324,-0.22562604249333834,0.03009031967907361,-0.06817073304700974,0.060412434445756946,0.23907789548382086,-0.03828029795020312,-0.034695872206381866,-0.16612695679628167,0.13476814425300332,1.8398768690768232,1.277746493329271,0.44759401465440324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.500005,1.0,0.0,1.0,0.0,1.7134272047309689,0.8695271668608232,0.5333688232481684,0.9193524145041336,-0.05630539204426907,-0.025531826570635827,0.3885472514432802,1.2398061122756276,-0.08239315290556752,0.10646488058413231,0.47070945922801616,0.46327205324649406,0.9452789865893105,-0.19797544699939026,0.02812082962220339,-0.04310415383593395,0.3514634696693748,0.3797124276259989,0.11389058195364068,-0.025842076727807976,-0.1406306897058599,0.114930320775083,2.067321169208524,1.3452062978250483,0.3331657079875074,-0.19797544699939026,0.02812082962220339,-0.04310415383593395,0.3514634696693748,0.3797124276259989,0.11389058195364068,-0.025842076727807976,-0.1406306897058599,0.114930320775083,2.067321169208524,1.3452062978250483,0.3331657079875074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5166717,1.0,0.0,1.0,0.0,1.7287021325550433,0.8833201479058445,0.5352603188512144,0.916854776206355,-0.054222064663032234,-0.020837877463691045,0.394972239422065,1.1958588110513086,-0.1098550770368407,0.08940055775876841,0.48288434640789385,0.2779513792049969,0.7910631256446071,-0.16784293078445844,0.030455856631495158,-0.009597949892086262,0.6432146616004707,0.6626295501002166,0.1349428090394419,-0.017957931823768782,-0.11111720445301929,0.09123920678985312,2.2058619039193115,1.4760277428782698,0.16911670638455129,-0.16784293078445844,0.030455856631495158,-0.009597949892086262,0.6432146616004707,0.6626295501002166,0.1349428090394419,-0.017957931823768782,-0.11111720445301929,0.09123920678985312,2.2058619039193115,1.4760277428782698,0.16911670638455129,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5333384,1.0,0.0,1.0,0.0,1.7432197835074326,0.8962373493909452,0.5365688672337969,0.9146886993992244,-0.05102716169794662,-0.017381525041338358,0.4005479928143995,1.1243188671802116,-0.129579300173228,0.06169234696173264,0.5508381044751595,0.11705344342763627,0.631074091391299,-0.13912806974986178,0.034978020832016475,0.02467789561416678,0.9613778707283681,1.2037966750225473,0.15694696118889975,-0.015471789217933837,-0.07906555112007926,0.0753294979493579,2.2751452501285514,1.520115850109341,0.0236466546552105,-0.13912806974986178,0.034978020832016475,0.02467789561416678,0.9613778707283681,1.2037966750225473,0.15694696118889975,-0.015471789217933837,-0.07906555112007926,0.0753294979493579,2.2751452501285514,1.520115850109341,0.0236466546552105,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5500051,1.0,0.0,1.0,0.0,1.7571391008391979,0.9081007740294083,0.5374278207223702,0.9131535549709248,-0.04678943684411409,-0.014828242832681165,0.40464979532710504,1.0710917890994516,-0.1476665451534669,0.03804734052270314,0.5112277177119764,-0.05620540038325568,0.505595162559458,-0.11096661681279135,0.0371305231200458,0.04977741558491165,1.2704817943133226,1.7555226441026859,0.24533564559885665,-0.008021454753257268,-0.05638444299226599,0.047988405475839484,2.4426343030898336,1.60797869968761,-0.16415547840085082,-0.11096661681279135,0.0371305231200458,0.04977741558491165,1.2704817943133226,1.7555226441026859,0.24533564559885665,-0.008021454753257268,-0.05638444299226599,0.047988405475839484,2.4426343030898336,1.60797869968761,-0.16415547840085082,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5666718,1.0,0.0,1.0,0.0,1.7707634481884522,0.9194764576734857,0.5379256015796131,0.9116730082202427,-0.04298448226262833,-0.014395442575231421,0.40840841274431444,1.0382344473411171,-0.16478013560100557,0.009158916956372568,0.37568085186061995,-0.19851465102931776,0.43516442081045004,-0.08902380162043153,0.03557733593954865,0.05963879954911803,1.4503939709708615,2.078655285536835,0.3817113775817775,0.002837683351417793,-0.047029773972464536,0.01630144721817312,2.701091559416393,1.7395210681044908,-0.32825630908749237,-0.08902380162043153,0.03557733593954865,0.05963879954911803,1.4503939709708615,2.078655285536835,0.3817113775817775,0.002837683351417793,-0.047029773972464536,0.01630144721817312,2.701091559416393,1.7395210681044908,-0.32825630908749237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.5833385,1.0,0.0,1.0,0.0,1.7842523338256011,0.9302953351113381,0.5379202264179802,0.9104189876766341,-0.039830733257106454,-0.014975654132033136,0.41149302466672744,0.9952763864401086,-0.18243148124862157,-0.033312252314171696,0.32132216673075537,-0.23664048274226612,0.3310661645054801,-0.06727678606459679,0.03179089711895181,0.06178200062949223,1.5075827523486567,2.3609470791225435,0.49415153264809075,0.0043875329732792675,-0.03185757965786734,0.004980109306770989,2.9023139585416526,1.8131966731887876,-0.43913434866604084,-0.06727678606459679,0.03179089711895181,0.06178200062949223,1.5075827523486567,2.3609470791225435,0.49415153264809075,0.0043875329732792675,-0.03185757965786734,0.004980109306770989,2.9023139585416526,1.8131966731887876,-0.43913434866604084,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6000052,1.0,0.0,1.0,0.0,1.7973051119593477,0.9403042717769987,0.5371523283590007,0.9095590116818776,-0.036568073140324626,-0.015559222177768579,0.4136702683301193,0.9280901926375987,-0.2062752071385769,-0.059201730645376066,0.30419822919795375,-0.25115937118461407,0.25556027194799696,-0.052753760143178445,0.029345603355589073,0.06352297504474003,1.5859001880939845,2.737709946597403,0.5715564860841359,0.0038539016749793886,-0.020188860737639616,0.0005234213801967501,3.012561586562562,1.8299189892110488,-0.505565584293767,-0.052753760143178445,0.029345603355589073,0.06352297504474003,1.5859001880939845,2.737709946597403,0.5715564860841359,0.0038539016749793886,-0.020188860737639616,0.0005234213801967501,3.012561586562562,1.8299189892110488,-0.505565584293767,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6166719,1.0,0.0,1.0,0.0,1.8098678092695166,0.9490005459592845,0.536438637288974,0.9087788759436104,-0.033552934227809014,-0.016529754879535757,0.4155982705052979,0.8719444053408354,-0.21557869921504946,-0.044865993884437044,0.3114663868110653,-0.27264286442858693,0.31639506829069547,-0.06347491935758535,0.031197889564940597,0.06700576774067074,1.618937486278278,3.1469907052312642,0.47716851829830437,0.0062963785394329706,-0.028768891634063536,-0.0010990567788907947,3.0820530116134153,1.8074934915225338,-0.5258933735982413,-0.06347491935758535,0.031197889564940597,0.06700576774067074,1.618937486278278,3.1469907052312642,0.47716851829830437,0.0062963785394329706,-0.028768891634063536,-0.0010990567788907947,3.0820530116134153,1.8074934915225338,-0.5258933735982413,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6333386,1.0,0.0,1.0,0.0,1.82182058398888,0.9575332579106828,0.536260566529369,0.9074615403960536,-0.03005055921463882,-0.01735720562486775,0.41869946740568614,0.8496181372363766,-0.19644160599192992,-0.0113538439516536,0.38752544910782616,-0.3201650239546384,0.46160542792838843,-0.09170713064917484,0.03820031650681735,0.08017329356558743,1.4275397141042558,3.4292156106933964,0.3397062773345243,0.009294931076760656,-0.04699064851269269,0.001298779717116516,3.1482717455251774,1.8009803003661764,-0.5122898923235677,-0.09170713064917484,0.03820031650681735,0.08017329356558743,1.4275397141042558,3.4292156106933964,0.3397062773345243,0.009294931076760656,-0.04699064851269269,0.001298779717116516,3.1482717455251774,1.8009803003661764,-0.5122898923235677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6500053,1.0,0.0,1.0,0.0,1.8332321975962995,0.9662956603531879,0.5366928776244555,0.9056513263892148,-0.025591055677661616,-0.01843725501782452,0.42284848410058967,0.820052346723883,-0.18172659956442022,0.019305871554491403,0.4842227111168179,-0.39153506590564224,0.5555970459478824,-0.11123885887428592,0.04508782022915697,0.09973008077756601,1.2166727368963606,3.5983587416507676,0.2818434628903324,0.011105015944567734,-0.055637177926802214,0.002066627837032106,3.129007106742283,1.7756108747037564,-0.48373889177833684,-0.11123885887428592,0.04508782022915697,0.09973008077756601,1.2166727368963606,3.5983587416507676,0.2818434628903324,0.011105015944567734,-0.055637177926802214,0.002066627837032106,3.129007106742283,1.7756108747037564,-0.48373889177833684,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.666672,1.0,0.0,1.0,0.0,1.8439604377317544,0.9746315709849058,0.5375993297240901,0.9036255593071373,-0.020152930795209224,-0.019615051895327425,0.4273990614009003,0.7859447592750768,-0.16510307419409634,0.04360455126425145,0.6036143743514171,-0.4676695637194951,0.6700379373729819,-0.13537967760404807,0.05203411802061429,0.12247878421488359,1.0673210805412523,3.662249981980275,0.16598614079237325,0.013128797048400422,-0.0664513198171172,0.004104710489076178,2.952448010590911,1.6842189634606692,-0.42878346845375837,-0.13537967760404807,0.05203411802061429,0.12247878421488359,1.0673210805412523,3.662249981980275,0.16598614079237325,0.013128797048400422,-0.0664513198171172,0.004104710489076178,2.952448010590911,1.6842189634606692,-0.42878346845375837,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.6833386999999997,1.0,0.0,1.0,0.0,1.8540090401657239,0.9830925474896461,0.5389141860340375,0.9009127332975289,-0.013388784221003362,-0.020956987759374837,0.4332871935604749,0.7733384226807708,-0.1484598129997473,0.07617497515308935,0.7210381915696451,-0.5545457254871644,0.8535120120297577,-0.17161517084375547,0.05874746844101299,0.14654855730437652,0.8489862191713192,3.5348936644421247,0.08091652346844727,0.018463724713371772,-0.0876149839918442,0.004429065673686275,2.6226124369154533,1.538019328053113,-0.35396767975079985,-0.17161517084375547,0.05874746844101299,0.14654855730437652,0.8489862191713192,3.5348936644421247,0.08091652346844727,0.018463724713371772,-0.0876149839918442,0.004429065673686275,2.6226124369154533,1.538019328053113,-0.35396767975079985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7000053999999998,1.0,0.0,1.0,0.0,1.8637721316380942,0.9916974754495222,0.5410189273162196,0.8974118764281516,-0.005620382328383974,-0.02254819910551109,0.4405813364922363,0.7656058755691584,-0.13588338953853257,0.10371518016336573,0.8051367789397658,-0.5913087538978504,1.0510814866384846,-0.21028463337382663,0.060157084529233865,0.16029718736211973,0.6012704756558751,3.2840682925330964,-0.015639684878636543,0.024966679821771837,-0.11398438669871937,0.006784324872609951,2.101914667353609,1.2924801422282386,-0.27653605349846067,-0.21028463337382663,0.060157084529233865,0.16029718736211973,0.6012704756558751,3.2840682925330964,-0.015639684878636543,0.024966679821771837,-0.11398438669871937,0.006784324872609951,2.101914667353609,1.2924801422282386,-0.27653605349846067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7166721,1.0,0.0,1.0,0.0,1.8730193258417533,1.0004750139872631,0.5434097344035931,0.8930297142173902,0.002594822477960248,-0.023799803544896372,0.4493603963105103,0.736562116107796,-0.1257746796451723,0.10479211252795141,0.755839244929155,-0.5651885873637517,1.2556752376286162,-0.24576042583490568,0.05319211941482697,0.15183761616357858,0.36776571771020483,2.677533184274032,-0.2232505103999897,0.036900415314812626,-0.1474038356984988,0.002657619827611517,1.4811268861531046,0.880043511217952,-0.2908926615424741,-0.24576042583490568,0.05319211941482697,0.15183761616357858,0.36776571771020483,2.677533184274032,-0.2232505103999897,0.036900415314812626,-0.1474038356984988,0.002657619827611517,1.4811268861531046,0.880043511217952,-0.2908926615424741,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7333388,1.0,0.0,1.0,0.0,1.8816060887569714,1.0088093840321903,0.5456791594753664,0.8877460505820183,0.009365016188537707,-0.02538144894436258,0.4595378419644044,0.6962674714586615,-0.1324775900025109,0.08612463699248823,0.7570588982384702,-0.5555650863802667,1.5090521348668826,-0.2923301245668286,0.04561681689122541,0.15038980317932146,0.25580441293048095,1.6449892107695845,-0.6834130365454897,0.05123109476727259,-0.18605246475287565,0.0007580093271900464,0.928961206713557,0.38479375186631914,-0.2686224324624856,-0.2923301245668286,0.04561681689122541,0.15038980317932146,0.25580441293048095,1.6449892107695845,-0.6834130365454897,0.05123109476727259,-0.18605246475287565,0.0007580093271900464,0.928961206713557,0.38479375186631914,-0.2686224324624856,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7500055,1.0,0.0,1.0,1.0,1.88989649637603,1.0167355174588428,0.5475516104190921,0.8810797288829688,0.017402065118859552,-0.026458855964834993,0.4719063555644756,0.6703512491466997,-0.1736853921118409,0.033517311806042595,0.8635557565455686,-0.5915970630364312,1.7788732524489328,-0.3452403221661643,0.03885517096865754,0.16706427135234062,0.11683725192799066,0.8525248616414997,-1.118496072836941,0.06570074106418834,-0.22108385131990296,0.0022072089765276972,0.48518145958636766,0.11761873869695394,-0.17046074653991014,-0.3452403221661643,0.03885517096865754,0.16706427135234062,0.11683725192799066,0.8525248616414997,-1.118496072836941,0.06570074106418834,-0.22108385131990296,0.0022072089765276972,0.48518145958636766,0.11761873869695394,-0.17046074653991014,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7666722,1.0,0.0,1.0,1.0,1.89875359333403,1.024100829901002,0.5481700402924367,0.8732152443097362,0.025914920474083423,-0.027800765809258006,0.48585046199661935,0.6683436778303126,-0.20910117420600677,-0.057746848502018104,0.9399497883036647,-0.6096662717886033,1.8865211049859136,-0.3679056544578704,0.027099222560172442,0.17906852224741696,-0.2784859443505482,0.685704884499997,-1.0004095593899736,0.33765125372536375,-0.1593784668922386,0.1484133065642203,0.277989376532527,0.10028536115574521,-0.15640377488371449,-0.3679056544578704,0.027099222560172442,0.17906852224741696,-0.2784859443505482,0.685704884499997,-1.0004095593899736,0.33765125372536375,-0.1593784668922386,0.1484133065642203,0.277989376532527,0.10028536115574521,-0.15640377488371449,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.7833389,1.0,0.0,0.0,1.0,1.9075918215825642,1.0320755297028263,0.5471477575862544,0.8651100540664676,0.03513369152621508,-0.028522676080154883,0.49953646015289094,0.634850180474406,-0.1916772984687167,-0.13177241460023667,1.0453552512607847,-0.45356297474065826,1.9099431536657463,-0.38005694718215216,0.008919054090832965,0.1684711895016211,-0.3869595469689273,0.5685927804196993,-0.6182304956638114,0.6777704165209973,-0.07913817097512274,0.3647007242302893,0.268792089251225,0.10718231634518907,-0.14814639170712873,-0.38005694718215216,0.008919054090832965,0.1684711895016211,-0.3869595469689273,0.5685927804196993,-0.6182304956638114,0.6777704165209973,-0.07913817097512274,0.3647007242302893,0.268792089251225,0.10718231634518907,-0.14814639170712873,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8000056,1.0,1.0,0.0,1.0,1.9149173084824884,1.0395560608884447,0.5453764227341954,0.8564708909399701,0.04381474243426308,-0.026769669162177948,0.5136353435374756,0.5672636862537808,-0.15723556384374943,-0.10931113790980752,1.019854801072059,-0.13172570700299574,1.9230031480913452,-0.38742754545128244,-0.015612346963689308,0.12023992057726518,-0.23353553668311555,0.3638324867883261,-0.2626066959344845,0.8862456093894905,-0.011040854928459014,0.5097574037464881,0.2593307459602197,0.09882777259372263,-0.10859792729380041,-0.38742754545128244,-0.015612346963689308,0.12023992057726518,-0.23353553668311555,0.3638324867883261,-0.2626066959344845,0.8862456093894905,-0.011040854928459014,0.5097574037464881,0.2593307459602197,0.09882777259372263,-0.10859792729380041,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8166723,1.0,1.0,0.0,1.0,1.9211231695333533,1.046585752868789,0.5449921672649456,0.8478512579124945,0.049929487882273194,-0.02311695316144991,0.5273716878753978,0.5619777926573701,-0.1391431108915667,-0.026548645619840418,0.7144931098553391,0.22703055064896166,1.85039093025719,-0.367723863872344,-0.04137244111967568,0.0379258104960346,-0.20498893225820816,0.30400693633607195,-0.07008795235534056,1.0924330258434787,0.18280867374039336,0.5908940017445842,0.25060495897377694,0.07437047351985612,-0.038726179200610514,-0.367723863872344,-0.04137244111967568,0.0379258104960346,-0.20498893225820816,0.30400693633607195,-0.07008795235534056,1.0924330258434787,0.18280867374039336,0.5908940017445842,0.25060495897377694,0.07437047351985612,-0.038726179200610514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.833339,1.0,1.0,0.0,1.0,1.927356542546593,1.054326190284742,0.5459380464085811,0.8397144201687264,0.051191180848282704,-0.018895037021634996,0.5402796804804055,0.6078557880309271,-0.12883328894612484,0.023942540377700612,0.25091360857836736,0.5218148865996873,1.756045063034912,-0.3358579185391989,-0.06407390741921512,-0.05223668015384119,-0.19057648780786998,0.25938110965089634,-0.07146651266041924,1.2931937689224977,0.48206943178318157,0.4891155035352332,0.2501910208048139,0.04641635901829103,0.03909860695141967,-0.3358579185391989,-0.06407390741921512,-0.05223668015384119,-0.19057648780786998,0.25938110965089634,-0.07146651266041924,1.2931937689224977,0.48206943178318157,0.4891155035352332,0.2501910208048139,0.04641635901829103,0.03909860695141967,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8500057,1.0,1.0,0.0,1.0,1.9334653654216005,1.0630816868233617,0.5472677366746621,0.831987367847809,0.048193232474994595,-0.015117213497558044,0.5524906351616785,0.6610552199731594,-0.11144228965087304,0.041398863283856724,-0.08393076161193269,0.6595016437924222,1.7185269097316784,-0.3156798004154153,-0.08109715641352393,-0.10654870572544932,-0.18147079497193425,0.23293161479007793,-0.06289400707680222,1.656025410190003,0.7403343620252891,0.2939741181992937,0.2570101878649139,0.034395414511827045,0.08693243092607837,-0.3156798004154153,-0.08109715641352393,-0.10654870572544932,-0.18147079497193425,0.23293161479007793,-0.06289400707680222,1.656025410190003,0.7403343620252891,0.2939741181992937,0.2570101878649139,0.034395414511827045,0.08693243092607837,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8666724,1.0,1.0,0.0,1.0,1.9393886393082682,1.0729883461024938,0.548802849513098,0.8241152537689191,0.04353020267626841,-0.01192735358933112,0.5646210306007988,0.6926008814142929,-0.10524581940548033,0.057509849724217216,-0.2204214626594228,0.6693315212143776,1.758632375278621,-0.31421661500147013,-0.09474614377540257,-0.12144052077951312,-0.18576346750812742,0.22856397788695942,-0.05340374830062958,2.116012354661182,0.8113563935482275,0.15389023851557568,0.26846726245162017,0.04043832240702651,0.10114078235521919,-0.31421661500147013,-0.09474614377540257,-0.12144052077951312,-0.18576346750812742,0.22856397788695942,-0.05340374830062958,2.116012354661182,0.8113563935482275,0.15389023851557568,0.26846726245162017,0.04043832240702651,0.10114078235521919,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.8833390999999997,1.0,1.0,0.0,1.0,1.9451505853627726,1.0831213682812995,0.5505611888262627,0.8157223177227633,0.03852710178205267,-0.00927613862063687,0.5770846697405585,0.6803490091673778,-0.10981043564951812,0.05861150066842523,-0.21882416617380315,0.6224476041791709,1.7819018480891247,-0.3065778501295184,0.07098809880542886,-0.07113767618096203,-0.19384600224688975,0.22740294120737248,-0.04897066485413915,2.5030873150773973,0.7697461086472566,0.0881855123792116,0.270916719806414,0.05315224489851764,0.09548774330081437,-0.3065778501295184,0.07098809880542886,-0.07113767618096203,-0.19384600224688975,0.22740294120737248,-0.04897066485413915,2.5030873150773973,0.7697461086472566,0.0881855123792116,0.270916719806414,0.05315224489851764,0.09548774330081437,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9000057999999997,0.0,1.0,0.0,1.0,1.950464174938135,1.092968169156714,0.5519111878775257,0.8072208917389395,0.03429426862770902,-0.006703405239918324,0.589214222025972,0.6590911007965274,-0.11337435330260273,0.02810714723052933,-0.12805971578284367,0.5346766136197232,1.7842793439073246,-0.25884674513255274,0.3609025189169458,0.010851079999707539,-0.20377985696340956,0.22673169423335587,-0.046964867701562975,2.73374121455916,0.8041791812227647,0.04480605518489458,0.26564410619194784,0.06923304232269896,0.07592080099701645,-0.25884674513255274,0.3609025189169458,0.010851079999707539,-0.20377985696340956,0.22673169423335587,-0.046964867701562975,2.73374121455916,0.8041791812227647,0.04480605518489458,0.26564410619194784,0.06923304232269896,0.07592080099701645,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9166725,0.0,1.0,0.0,1.0,1.9554881229160526,1.102804539700521,0.5524420571945641,0.7983364622596517,0.03135833386330815,-0.004339964322597675,0.6013790091396105,0.6424654959236786,-0.1168795453329875,-0.009968298783612677,0.0306298256061876,0.41763646356082207,1.8189249851039873,-0.255426426863918,0.5803276678696562,0.044145301208486004,-0.22067061552733774,0.23265268257919322,-0.04599977263156857,2.821569859642213,0.9571221694760975,-0.03413353565064406,0.2613155421702114,0.08952315685783546,0.04580715540309066,-0.255426426863918,0.5803276678696562,0.044145301208486004,-0.22067061552733774,0.23265268257919322,-0.04599977263156857,2.821569859642213,0.9571221694760975,-0.03413353565064406,0.2613155421702114,0.08952315685783546,0.04580715540309066,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9333392,0.0,1.0,0.0,1.0,1.9601205504686476,1.1124737443299955,0.5523609637925367,0.7890066243539218,0.030381926957246966,-0.0017596762938379956,0.6136304985733146,0.6163250872249575,-0.13011822127535366,-0.025664206242440035,0.23157706088593233,0.3472255652728773,1.8826365823592552,-0.5586952400145441,1.0230794811339283,0.027914289326632976,-0.244982187195856,0.24036355622948713,-0.05468001025182243,2.849016678975014,1.0759623636347648,-0.1385180995960448,0.2576890175918917,0.10960271624777328,0.01660005566572886,-0.5586952400145441,1.0230794811339283,0.027914289326632976,-0.244982187195856,0.24036355622948713,-0.05468001025182243,2.849016678975014,1.0759623636347648,-0.1385180995960448,0.2576890175918917,0.10960271624777328,0.01660005566572886,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9500059,0.0,1.0,0.0,1.0,1.9647314803828482,1.1216755802354108,0.5522126603941143,0.7789678565005138,0.030785850971287988,0.0016630864598859985,0.6263054718445269,0.5657941860793073,-0.15397692022642573,-0.02301265230491236,0.409587241228045,0.3456563289219866,1.9799490799926487,-1.0356042677141146,1.3557200431826484,-0.01653169878974736,-0.2746809115939181,0.2474990579708013,-0.07007319752388719,2.796056681023097,1.1396788390584744,-0.19764184597183537,0.2583538041438356,0.12782351075478632,-0.0028096078303590944,-1.0356042677141146,1.3557200431826484,-0.01653169878974736,-0.2746809115939181,0.2474990579708013,-0.07007319752388719,2.796056681023097,1.1396788390584744,-0.19764184597183537,0.2583538041438356,0.12782351075478632,-0.0028096078303590944,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9666726,0.0,1.0,0.0,1.0,1.9691604029011922,1.1298169891215242,0.5520168903730251,0.7681071890484051,0.03213388904169883,0.006002104819584669,0.6394863048142221,0.5097867894147528,-0.1669724294801765,-0.020745276777768162,0.4517940716947987,0.36219228311695256,2.0634720467708934,-1.176292693293406,1.3385529539017285,-0.12192353364765177,-0.2967030495506225,0.24834487868259678,-0.07421707240485814,2.7207193875104063,1.218215054616772,-0.24091838705692617,0.26327576489538246,0.14276188907556311,-0.0075289165152917,-1.176292693293406,1.3385529539017285,-0.12192353364765177,-0.2967030495506225,0.24834487868259678,-0.07421707240485814,2.7207193875104063,1.218215054616772,-0.24091838705692617,0.26327576489538246,0.14276188907556311,-0.0075289165152917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +2.9833393,0.0,1.0,0.0,1.0,1.9732557069344836,1.1374025000167778,0.5517468487403236,0.7566914894701496,0.03292343885270874,0.009999420916249968,0.6528660264701313,0.46174311625778697,-0.15816758031042777,-0.031263882993328475,0.3713316740044441,0.3684025467359372,2.109997301263791,-1.2212322772882116,1.3161658150110327,-0.13223555837226836,-0.30746929416241525,0.24198062078450386,-0.0656243708760408,2.6941388785943676,1.3824782619371911,-0.25714806229743037,0.26895302313154856,0.1544244871177613,-0.00133227872306076,-1.2212322772882116,1.3161658150110327,-0.13223555837226836,-0.30746929416241525,0.24198062078450386,-0.0656243708760408,2.6941388785943676,1.3824782619371911,-0.25714806229743037,0.26895302313154856,0.1544244871177613,-0.00133227872306076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.000006,0.0,1.0,0.0,1.0,1.9765732028043652,1.1443063740072654,0.5510744426358936,0.7448810593189046,0.033169146029838455,0.01352091441417994,0.6662350937116734,0.430706973303918,-0.13532256689942368,-0.04132394305554882,0.21409509781731817,0.33439498767094644,2.1754742263007714,-1.4235289353963307,1.3583970039626432,0.005511985158568075,-0.315894725703854,0.23838053054492447,-0.04375611049646714,2.5732736540670103,1.5442048847394025,-0.21708657748436025,0.2807836186690647,0.17038096458505575,0.007375661571647838,-1.4235289353963307,1.3583970039626432,0.005511985158568075,-0.315894725703854,0.23838053054492447,-0.04375611049646714,2.5732736540670103,1.5442048847394025,-0.21708657748436025,0.2807836186690647,0.17038096458505575,0.007375661571647838,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0166727,0.0,1.0,0.0,1.0,1.979246591305806,1.1512118747615958,0.550414094451574,0.7323325519849034,0.032391865749599486,0.015306801422425473,0.6800040456988128,0.38983909892440083,-0.13823756990774239,-0.03694457365768701,-0.0850677981311639,0.2381007113565051,2.1524587045633456,-1.5528134140484737,1.4868471535024879,0.24444581565679666,-0.30246521797676484,0.22715939342537592,-0.0009120438889834632,2.287825594884427,1.5818607525938662,-0.20839765212477115,0.2883373665368898,0.1815580089611606,0.0238417904403788,-1.5528134140484737,1.4868471535024879,0.24444581565679666,-0.30246521797676484,0.22715939342537592,-0.0009120438889834632,2.287825594884427,1.5818607525938662,-0.20839765212477115,0.2883373665368898,0.1815580089611606,0.0238417904403788,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0333394,0.0,1.0,0.0,1.0,1.9820471356978302,1.1569576540863595,0.5498127004372889,0.7204844125504856,0.03003251279124618,0.01427086160284967,0.6926735175797742,0.33695418015065487,-0.1558399917413476,-0.02583658787041985,-0.44776603283165695,0.0866452783548805,2.0383823227717524,-1.7298981087440821,1.4615976298659135,0.48217478020946203,-0.27146670142945456,0.20986241462877317,0.05384910611970639,1.969783674847048,1.517868339930708,-0.2748234599361019,0.2868687854524875,0.18733381010687228,0.04222719061559969,-1.7298981087440821,1.4615976298659135,0.48217478020946203,-0.27146670142945456,0.20986241462877317,0.05384910611970639,1.969783674847048,1.517868339930708,-0.2748234599361019,0.2868687854524875,0.18733381010687228,0.04222719061559969,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0500061,0.0,1.0,0.0,1.0,1.9848227799983713,1.162251939862877,0.5494636093185844,0.7090009367198429,0.02655437884281278,0.01013686714682618,0.7046345014396509,0.33734449084070656,-0.15020200647199705,-0.041286500735477356,-0.7965690212902045,-0.08620079345147869,2.023070572608003,-1.970538400937146,1.1546906553970613,0.5222416280343022,-0.25589302191758895,0.20603529276132285,0.11085572576076998,1.6729840761621508,1.373482934990155,-0.3588086315129961,0.2964626282234031,0.20376920609384536,0.05859619322385591,-1.970538400937146,1.1546906553970613,0.5222416280343022,-0.25589302191758895,0.20603529276132285,0.11085572576076998,1.6729840761621508,1.373482934990155,-0.3588086315129961,0.2964626282234031,0.20376920609384536,0.05859619322385591,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0666728,0.0,1.0,0.0,1.0,1.9870519432876175,1.168203519568417,0.5484378286645927,0.6970694997245191,0.02202200330021751,0.0029863135630844966,0.7166590722622276,0.3431981301956493,-0.11929542494671959,-0.040123753765550496,-1.0118124979909715,-0.24451252624983688,2.092817811540602,-2.2548182594301833,0.8273227703774809,0.43724142089887164,-0.2626169650211826,0.21035296771206324,0.15277826133116587,1.385675082061518,1.160065829005068,-0.3349093048700527,0.30784753169450996,0.2287721635482185,0.06604275910212774,-2.2548182594301833,0.8273227703774809,0.43724142089887164,-0.2626169650211826,0.21035296771206324,0.15277826133116587,1.385675082061518,1.160065829005068,-0.3349093048700527,0.30784753169450996,0.2287721635482185,0.06604275910212774,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.0833395,0.0,1.0,1.0,1.0,1.9884361283593495,1.173830722725659,0.5483018309692176,0.6843671284485937,0.01784245407447005,-0.005547168104984557,0.7288981473825006,0.28650989930237203,-0.10186472670949241,-0.03866768550822523,-1.2105766583510564,-0.37835738501448984,2.102450950154267,-2.6057731198508933,0.5357717106327903,0.4037299533557015,-0.26357309413096064,0.20749473042958239,0.18960808455854342,0.795657586927975,0.4381142416852399,-0.2410457469995813,0.30938276365544176,0.2470682678675544,0.07646276225768296,-2.6057731198508933,0.5357717106327903,0.4037299533557015,-0.26357309413096064,0.20749473042958239,0.18960808455854342,0.795657586927975,0.4381142416852399,-0.2410457469995813,0.30938276365544176,0.2470682678675544,0.07646276225768296,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1000061999999997,0.0,1.0,1.0,1.0,1.989818158311898,1.1779862753311527,0.5474152608725283,0.6718393064377757,0.01266760706677487,-0.0166795638443013,0.7404007497338009,0.22002351190423822,-0.08860657725179673,-0.06078474033659042,-1.323175571744762,-0.4431932146906947,2.153972711611638,-2.6983234494632797,0.050296836224156094,0.43099021175078656,-0.277175694279544,0.20329319927710077,0.20594269750601657,0.3533620862182164,-0.15103404855035596,-0.1924059796245134,0.31020231770067747,0.26620809034846027,0.08977281745157674,-2.6983234494632797,0.050296836224156094,0.43099021175078656,-0.277175694279544,0.20329319927710077,0.20594269750601657,0.3533620862182164,-0.15103404855035596,-0.1924059796245134,0.31020231770067747,0.26620809034846027,0.08977281745157674,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1166728999999997,0.0,1.0,1.0,1.0,1.9906721662961286,1.181494225855195,0.546602071338502,0.6579322758685818,0.007872033890249049,-0.027276549697865783,0.75254178707192,0.17167983778612214,-0.06724422330046982,-0.025524588285443347,-1.1451043533936016,-0.36901279387462516,2.2553613894280593,-2.4441941228546633,-0.23094757174068592,0.49671749356930356,-0.3123886267647111,0.1960284819883558,0.1723214465616124,0.367096790529176,-0.15159486377224995,-0.15968657655512122,0.4684637245674737,0.2340049894376225,0.1474392054876818,-2.4441941228546633,-0.23094757174068592,0.49671749356930356,-0.3123886267647111,0.1960284819883558,0.1723214465616124,0.367096790529176,-0.15159486377224995,-0.15968657655512122,0.4684637245674737,0.2340049894376225,0.1474392054876818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1333396,0.0,1.0,1.0,0.0,1.9912916258894984,1.183991980817642,0.5469078153281667,0.6435546507305008,0.003665742711358711,-0.03537109633031482,0.7645736455031058,0.17725532057978244,-0.03427391607542718,-0.046275932440138536,-0.7310395152789052,-0.29605752217931136,2.375111805061184,-2.001277834677402,-0.30474319527908217,0.4100324859034845,-0.3607470706509983,0.18681596596437547,0.11391781607627426,0.37002594644670395,-0.15613201154982925,-0.1046145231501411,0.6436307320482393,0.21403277180058242,0.20961901188145224,-2.001277834677402,-0.30474319527908217,0.4100324859034845,-0.3607470706509983,0.18681596596437547,0.11391781607627426,0.37002594644670395,-0.15613201154982925,-0.1046145231501411,0.6436307320482393,0.21403277180058242,0.20961901188145224,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1500063,0.0,1.0,1.0,0.0,1.990844145665569,1.1875911946310098,0.5454219554206166,0.6275300012301159,0.0023210057179953916,-0.03985008474809307,0.7775684415112006,0.19501876116654882,-0.01179325328203129,-0.07997424136167512,-0.3186245627279214,-0.19184105674274504,2.547290583716406,-1.5544620717346649,-0.6859491720057818,-0.10626412792010957,-0.4147173673792532,0.17723594622560396,0.05288536409181543,0.3798321095088411,-0.16556883777156314,-0.04899466640238655,0.6901197889927404,0.2726652613989568,0.22261169413748272,-1.5544620717346649,-0.6859491720057818,-0.10626412792010957,-0.4147173673792532,0.17723594622560396,0.05288536409181543,0.3798321095088411,-0.16556883777156314,-0.04899466640238655,0.6901197889927404,0.2726652613989568,0.22261169413748272,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.166673,0.0,1.0,1.0,0.0,1.9904182935771344,1.190589943969655,0.5446223026928079,0.6104238566446936,0.0010668803784775732,-0.04160087613819158,0.79098100110547,0.188506727093286,-0.015829710251579088,-0.06564693139788001,0.025661551775703662,-0.030071124373995783,2.6572879988049944,-1.2388987287207907,-1.1288252925286806,-0.7371303188376241,-0.4531006641942959,0.1568985702166848,-0.009811388122661293,0.38539061163870736,-0.17243063210390908,0.006198748012204219,0.767841661406563,0.3605442967800862,0.23264549108739566,-1.2388987287207907,-1.1288252925286806,-0.7371303188376241,-0.4531006641942959,0.1568985702166848,-0.009811388122661293,0.38539061163870736,-0.17243063210390908,0.006198748012204219,0.767841661406563,0.3605442967800862,0.23264549108739566,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.1833397,0.0,1.0,1.0,0.0,1.9898603561267085,1.193937938177262,0.5436050747240697,0.5924725614933068,0.001058704579836466,-0.03983622451517473,0.8046043861666111,0.21403754560768984,-0.014362431371691159,-0.09938877078448427,0.4011384155360205,0.06305132127939919,2.728050803859459,-0.8378921993762259,-1.3627046991425695,-1.1874434840659238,-0.48664960117522305,0.1332065307632869,-0.0630851264110913,0.3840431583571769,-0.1724265625381903,0.0543496542355337,0.9183094801958657,0.4322713721989643,0.2643762345672811,-0.8378921993762259,-1.3627046991425695,-1.1874434840659238,-0.48664960117522305,0.1332065307632869,-0.0630851264110913,0.3840431583571769,-0.1724265625381903,0.0543496542355337,0.9183094801958657,0.4322713721989643,0.2643762345672811,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2000064,0.0,1.0,1.0,0.0,1.9888997630042897,1.197749212942187,0.5416988836292025,0.5738695333304213,0.0023170285911891797,-0.035618340406520246,0.8181685180452235,0.24039371189156922,-0.015861147232045056,-0.1395988446525004,0.5988392281008967,0.1488646370114468,2.732222384307158,-0.24448903774129815,-1.2279359743048963,-1.3380790907944664,-0.5000421394245246,0.10553223753702239,-0.09448315687632432,0.38320065881577914,-0.16383048140500955,0.08284585320318455,1.0936107757298243,0.48937372232926113,0.3284722204902675,-0.24448903774129815,-1.2279359743048963,-1.3380790907944664,-0.5000421394245246,0.10553223753702239,-0.09448315687632432,0.38320065881577914,-0.16383048140500955,0.08284585320318455,1.0936107757298243,0.48937372232926113,0.3284722204902675,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2166731,0.0,1.0,1.0,0.0,1.98779432917943,1.201924023192277,0.5393509994023198,0.5552837407861767,0.0031091842927651677,-0.030363279790194948,0.8311006987314631,0.265153561545624,-0.0021532816691409995,-0.161704359690954,0.7132940201295355,0.2143053762646697,2.6566445905745044,0.12379367119120957,-0.5920601097675472,-0.6421132427566841,-0.4950495015442821,0.07521544212418257,-0.11367078760308438,0.37432958208823025,-0.14892909469905163,0.10089183964225583,1.206200774222751,0.627152408342414,0.29850169468988286,0.12379367119120957,-0.5920601097675472,-0.6421132427566841,-0.4950495015442821,0.07521544212418257,-0.11367078760308438,0.37432958208823025,-0.14892909469905163,0.10089183964225583,1.206200774222751,0.627152408342414,0.29850169468988286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2333398,1.0,1.0,1.0,0.0,1.9857321365508813,1.2062234269186214,0.5366658604905205,0.537154114441673,0.004573179956699757,-0.023877765060044378,0.843133676055703,0.2865226536804324,0.0075308653490479965,-0.14611581978307717,0.6047012037081785,0.23466237248966565,2.683583793020182,-0.04798062075730824,-0.30479672234603455,0.000748571361588699,-0.49844471325313894,0.05392786674405656,-0.10217596187820861,0.39083394306648406,-0.12942349555558225,0.09071287503573157,1.4220509773993708,0.858922245354719,0.2210848811899275,-0.04798062075730824,-0.30479672234603455,0.000748571361588699,-0.49844471325313894,0.05392786674405656,-0.10217596187820861,0.39083394306648406,-0.12942349555558225,0.09071287503573157,1.4220509773993708,0.858922245354719,0.2210848811899275,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2500065,1.0,1.0,1.0,0.0,1.9836153571882593,1.2106870455400245,0.5347959947078123,0.5176086911974279,0.004222936025897392,-0.02001142256864157,0.8553729903235117,0.303290954201435,-0.006351121679824989,-0.10616374981528341,0.23289819032060527,0.21337667906473787,2.705354448269613,-0.2388918752673084,-0.441255648180504,-0.029009265474670008,-0.4887585018411992,0.03982831403382504,-0.06035460291777608,0.41673295499070806,-0.10095515965305918,0.0515318052696494,1.6352017564829553,1.20685176819137,0.24823399242105715,-0.2388918752673084,-0.441255648180504,-0.029009265474670008,-0.4887585018411992,0.03982831403382504,-0.06035460291777608,0.41673295499070806,-0.10095515965305918,0.0515318052696494,1.6352017564829553,1.20685176819137,0.24823399242105715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2666732,1.0,1.0,1.0,0.0,1.9812751892013694,1.215408558687798,0.533418815364722,0.49865391198824666,0.002698973944481157,-0.01893557549985997,0.8665901197099781,0.3263436298386882,0.0014611369359582294,-0.07611129092371553,-0.07802992521648203,0.19366080938489888,2.6155387938361683,-0.19803161839031624,-0.42723301353618326,-0.0547828870543461,-0.460968095577335,0.024299881120801475,-0.026843504905345622,0.4204471836439085,-0.06990600268636953,0.019765955266053393,1.6575428933915384,1.591124344314842,0.35452464056123884,-0.19803161839031624,-0.42723301353618326,-0.0547828870543461,-0.460968095577335,0.024299881120801475,-0.026843504905345622,0.4204471836439085,-0.06990600268636953,0.019765955266053393,1.6575428933915384,1.591124344314842,0.35452464056123884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.2833399,1.0,1.0,1.0,0.0,1.9781411428212752,1.2201530892576065,0.5325156507995659,0.4799003503962947,-8.140379226210562e-06,-0.01967362317802478,0.8771023897894117,0.34511279777833004,0.03383489020885912,-0.05705752160932047,-0.12726404660411927,0.18156560831068785,2.6241744365432957,-0.17733590696176438,-0.43545008734649565,-0.05830970428604421,-0.46104207780956596,0.005156244262456538,-0.02301955626107466,0.426412021797814,-0.049753795337112265,0.016204592447483953,1.592596310574232,1.9366483559362873,0.39218369458535984,-0.17733590696176438,-0.43545008734649565,-0.05830970428604421,-0.46104207780956596,0.005156244262456538,-0.02301955626107466,0.426412021797814,-0.049753795337112265,0.016204592447483953,1.592596310574232,1.9366483559362873,0.39218369458535984,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3000066,1.0,1.0,1.0,0.0,1.9741566317576933,1.2245511008605101,0.5316964932699005,0.4603516457058513,-0.0018569151879671876,-0.019322901476585108,0.8875243881947275,0.38127563002265097,0.039431557647849565,-0.025873150449788853,-0.15386225680230853,0.14351376529353038,2.6609620926356152,-0.1606446633012456,-0.44648532147252845,-0.054813182688527695,-0.46787862659256235,-0.012698058803693837,-0.01636307203835002,0.43390986643627605,-0.028520460875640877,0.010691311165293435,1.3148571663932997,2.2667860891940412,0.24493265532559194,-0.1606446633012456,-0.44648532147252845,-0.054813182688527695,-0.46787862659256235,-0.012698058803693837,-0.01636307203835002,0.43390986643627605,-0.028520460875640877,0.010691311165293435,1.3148571663932997,2.2667860891940412,0.24493265532559194,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3166732999999997,1.0,1.0,1.0,0.0,1.9697630154989643,1.2298110916640246,0.5317907454694382,0.44058003744150687,-0.004127975573749717,-0.02077540646690011,0.897463410347095,0.4117555637002002,0.02066682568361433,0.016770153640443274,-0.26539337124144935,0.13372254397846567,2.636597147256227,-0.13453454688668642,-0.44483334670505387,-0.06500440827904845,-0.4582206315129088,-0.029531259949084322,-0.00622761315046571,0.4354830867318484,-0.005232634382536958,0.0010954710206010887,0.9771951153590409,2.5294506537534693,0.09962056675954352,-0.13453454688668642,-0.44483334670505387,-0.06500440827904845,-0.4582206315129088,-0.029531259949084322,-0.00622761315046571,0.4354830867318484,-0.005232634382536958,0.0010954710206010887,0.9771951153590409,2.5294506537534693,0.09962056675954352,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3333399999999997,1.0,1.0,1.0,0.0,1.9652012679487927,1.2349678069080468,0.5323763672224475,0.4209493771909532,-0.006719678565312511,-0.022137245118320013,0.9067890659580645,0.4176497770089523,0.0452401998435449,0.05066648255770216,-0.29768877804837235,0.15096905933653088,2.5890605931165176,-0.1104071272033105,-0.4414589935271557,-0.07102529065778017,-0.43022735320096595,0.05930095349066986,0.08276761396676195,0.4295317833506876,0.013909911619362931,0.0027093308922669494,0.635963574582209,2.6366656004877296,-0.011336283701400583,-0.1104071272033105,-0.4414589935271557,-0.07102529065778017,-0.43022735320096595,0.05930095349066986,0.08276761396676195,0.4295317833506876,0.013909911619362931,0.0027093308922669494,0.635963574582209,2.6366656004877296,-0.011336283701400583,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3500067,1.0,0.0,1.0,0.0,1.9595735251982722,1.2394130435269957,0.5334985535523896,0.4014788557009189,-0.009442888178152439,-0.02392918414434678,0.9155069384958924,0.4243265916657992,0.074924805613204,0.09058220819542918,-0.36690185511432183,0.1382106801977188,2.5286067298652535,-0.08623446217021083,-0.4320733771538852,-0.07621717335827514,-0.5175470644553941,0.21836701498166086,0.20729436383832245,0.4213742734256828,0.034660642837917845,-0.0028938772539396263,0.191834829297581,2.6363468701218364,-0.15704030790767334,-0.08623446217021083,-0.4320733771538852,-0.07621717335827514,-0.5175470644553941,0.21836701498166086,0.20729436383832245,0.4213742734256828,0.034660642837917845,-0.0028938772539396263,0.191834829297581,2.6363468701218364,-0.15704030790767334,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3666734,1.0,0.0,1.0,0.0,1.9536741942397158,1.2435729055562037,0.5352906345947998,0.38236977971322245,-0.012275607813470615,-0.026416848843475414,0.9235501129403064,0.42678898768789286,0.07673650144791422,0.11509568179143202,-0.47476926862180324,0.11094899257098044,2.4601730278070995,-0.062104606551557175,-0.41790630085163116,-0.08327245938740643,-0.9172350474227385,0.3561041554565817,0.2152961791884212,0.41225020409681545,0.05641253735970476,-0.013812309095857468,-0.15884218161932753,2.639730947586293,-0.22610187991080238,-0.062104606551557175,-0.41790630085163116,-0.08327245938740643,-0.9172350474227385,0.3561041554565817,0.2152961791884212,0.41225020409681545,0.05641253735970476,-0.013812309095857468,-0.15884218161932753,2.639730947586293,-0.22610187991080238,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.3833401,1.0,0.0,1.0,0.0,1.947542041484428,1.2475124307258711,0.5371445781382953,-0.36356505338355133,0.01523423585568069,0.030030642211176368,-0.9309600048039086,0.4475074895959175,0.08779161690793749,0.09950600355917551,-0.4520574200274897,0.051535842617103166,2.369722975804521,-0.045609618291944126,-0.40330601382594433,-0.07341606328082496,-1.6100722599187158,0.41797413126348915,0.1426222290040408,0.3928956153681864,0.0718953630061858,-0.015973621197296853,-0.4156304196890733,2.598836350539635,-0.2462297012633121,-0.045609618291944126,-0.40330601382594433,-0.07341606328082496,-1.6100722599187158,0.41797413126348915,0.1426222290040408,0.3928956153681864,0.0718953630061858,-0.015973621197296853,-0.4156304196890733,2.598836350539635,-0.2462297012633121,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4000068,1.0,0.0,1.0,0.0,1.9405628087900806,1.2513880524337173,0.5383065522297237,-0.34552303145861973,0.01702009823152533,0.032496598418994674,-0.9376929785804251,0.47738737603252845,0.11509579997994096,0.06098663273133153,-0.32686227821327535,0.015202196633757468,2.2382294697962863,-0.03348450217436282,-0.38546636691178354,-0.055833351502959754,-2.2972365112748245,0.3612494555495401,0.04813026187473393,0.36336077392876653,0.07913788013214186,-0.007219567087343328,-0.6113468344322045,2.5302183692212643,-0.2553321573173357,-0.03348450217436282,-0.38546636691178354,-0.055833351502959754,-2.2972365112748245,0.3612494555495401,0.04813026187473393,0.36336077392876653,0.07913788013214186,-0.007219567087343328,-0.6113468344322045,2.5302183692212643,-0.2553321573173357,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4166735,1.0,0.0,1.0,0.0,1.9328455587864628,1.2548290922501806,0.5387424841305213,-0.3285118115053044,0.01857392098554156,0.03441481360082921,-0.9436898959751272,0.5060406667397624,0.12865419907677028,0.038365743867029664,-0.2808609494463299,0.01129673192221117,2.0869895273249663,-0.0190954221090252,-0.36122407064883566,-0.050028386980567906,-2.5868942240667123,0.2558769117248886,0.040118814743348274,0.3349570470767416,0.08498460860662897,-0.0029357848303098876,-0.7329172244852882,2.459756760656457,-0.2118627701864732,-0.0190954221090252,-0.36122407064883566,-0.050028386980567906,-2.5868942240667123,0.2558769117248886,0.040118814743348274,0.3349570470767416,0.08498460860662897,-0.0029357848303098876,-0.7329172244852882,2.459756760656457,-0.2118627701864732,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4333402,1.0,0.0,1.0,0.0,1.924619954364912,1.2584481019901215,0.5390406955529562,-0.31262710284535533,0.019932514458593387,0.03620531886217026,-0.9489763771137647,0.4920075744521896,0.10315346914872378,0.03950531042902351,-0.10206357769788205,0.003995389003233457,1.9898721514253035,-0.012265801361633492,-0.3525257647406598,-0.031491899962284214,-2.70147427254012,0.09446762959165403,0.14070443830951532,0.3103701142915578,0.08431200732201283,0.013831027746826138,-0.7850541620879606,2.3375759578846176,-0.17645503121454895,-0.012265801361633492,-0.3525257647406598,-0.031491899962284214,-2.70147427254012,0.09446762959165403,0.14070443830951532,0.3103701142915578,0.08431200732201283,0.013831027746826138,-0.7850541620879606,2.3375759578846176,-0.17645503121454895,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4500069,1.0,0.0,1.0,0.0,1.9175492145001576,1.2617524983185526,0.5395265249871802,-0.2970135271209118,0.02041355146122965,0.03533326979851261,-0.9540009495117292,0.45889765414796746,0.0728903219519481,0.046880518349941565,0.18148907546937307,-0.027283327041207697,1.915738842413863,-0.012281330257326863,-0.35228054465203734,0.0020162637297978705,-2.9868746814933647,-0.06762272424520845,0.22032078625478918,0.2851092617650397,0.07861626958594829,0.03635344196209859,-0.7589363023214409,2.1566082036918557,-0.16664778847689052,-0.012281330257326863,-0.35228054465203734,0.0020162637297978705,-2.9868746814933647,-0.06762272424520845,0.22032078625478918,0.2851092617650397,0.07861626958594829,0.03635344196209859,-0.7589363023214409,2.1566082036918557,-0.16664778847689052,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4666736,1.0,0.0,1.0,0.0,1.9105678625597673,1.2650574610698448,0.5401301862695097,-0.28221891006832256,0.019756857263359153,0.032785298976731464,-0.9585860824995999,0.46113817241298755,0.07449716882299381,0.0386475751820395,0.3752167235994531,-0.07197496413006886,1.8128855797768506,-0.010439046550700423,-0.3423489550617103,0.030067280673173755,-3.3647229625181696,-0.2498564080481586,0.14248356687258493,0.25897682271065825,0.0747752945046405,0.047244754925786205,-0.6653349096366719,1.9005522234851677,-0.14764855659812362,-0.010439046550700423,-0.3423489550617103,0.030067280673173755,-3.3647229625181696,-0.2498564080481586,0.14248356687258493,0.25897682271065825,0.0747752945046405,0.047244754925786205,-0.6653349096366719,1.9005522234851677,-0.14764855659812362,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.4833403,1.0,0.0,1.0,0.0,1.9032254756799944,1.2679402985463508,0.5403294551434246,-0.26813828993110633,0.018509583075211073,0.02907111694230727,-0.9627637939634677,0.4373230487301496,0.07415464304520172,0.034547193907784046,0.4785828486162309,-0.10984620732050229,1.6957176117456887,-0.006665765867832328,-0.3254845213442863,0.04901180245360003,-3.702132975425539,-0.4892396253005486,0.0636887592097175,0.23456776396801687,0.07242101167776074,0.04976393402528435,-0.5564643729403096,1.5366546378962267,-0.14006070046349864,-0.006665765867832328,-0.3254845213442863,0.04901180245360003,-3.702132975425539,-0.4892396253005486,0.0636887592097175,0.23456776396801687,0.07242101167776074,0.04976393402528435,-0.5564643729403096,1.5366546378962267,-0.14006070046349864,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.500007,1.0,0.0,1.0,0.0,1.8967640132544592,1.2704343656885315,0.5408238379504768,-0.25511021272819373,0.01668593119586317,0.025064540575668346,-0.9664430287749162,0.37333321017748416,0.05358678729583004,0.02774019453922056,0.5939074888418288,-0.16888989377028882,1.5615096341239016,-0.00567523696359592,-0.30553806662927485,0.07229307851476509,-3.8615477751571143,-0.6896993178720674,0.10190478775704596,0.207259506116533,0.06747149698104697,0.050660168324851346,-0.48826139023234066,1.0512987804963498,-0.16438977605460905,-0.00567523696359592,-0.30553806662927485,0.07229307851476509,-3.8615477751571143,-0.6896993178720674,0.10190478775704596,0.207259506116533,0.06747149698104697,0.050660168324851346,-0.48826139023234066,1.0512987804963498,-0.16438977605460905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5166737,1.0,0.0,1.0,0.0,1.8914868002413672,1.2724986498852764,0.5409084954207485,-0.24308465488105627,0.0139381850671511,0.019774648162509546,-0.9697033262026281,0.33979226682233243,0.06428815341102405,0.019630422101646457,0.6616103964740664,-0.2213134839919459,1.4713690626235871,-0.0036774447069715726,-0.2909938806847833,0.09000066099407975,-3.8698143710226067,-0.8095650275344329,0.1774119419765221,0.18839998405241512,0.06582804905564746,0.04772045615689732,-0.41156916245529346,0.5032192514658037,-0.23063906999037226,-0.0036774447069715726,-0.2909938806847833,0.09000066099407975,-3.8698143710226067,-0.8095650275344329,0.1774119419765221,0.18839998405241512,0.06582804905564746,0.04772045615689732,-0.41156916245529346,0.5032192514658037,-0.23063906999037226,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5333403999999997,1.0,0.0,1.0,0.0,1.8857474769603382,1.2738716680944555,0.5411834316525845,-0.23141600995435607,0.01091055492595124,0.014922430769092608,-0.9726792437324624,0.3400194566894611,0.09129374783729009,0.03378189124198379,0.5881823794908516,-0.27310566093277383,1.4552277492889265,0.0030890138138699626,-0.28279309318472595,0.09302465536978244,-3.787355172594891,-0.8431364991139553,0.27516138727857686,0.18436488472996784,0.07466801121565282,0.03183035245369072,-0.26627032378206694,0.020186842580497757,-0.3330879548359692,0.0030890138138699626,-0.28279309318472595,0.09302465536978244,-3.787355172594891,-0.8431364991139553,0.27516138727857686,0.18436488472996784,0.07466801121565282,0.03183035245369072,-0.26627032378206694,0.020186842580497757,-0.3330879548359692,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5500070999999997,1.0,0.0,1.0,0.0,1.8799687770253661,1.274861924516637,0.541767799173231,-0.21953767381794348,0.007591948242949008,0.011025458971451275,-0.9755121789864807,0.334026802676716,0.09617945954735703,0.06839300484673502,0.5587092465414737,-0.330584744864565,1.4750401040694021,0.00928715017035573,-0.28302189038842845,0.10041695823206657,-3.5505942718247523,-0.8235247394900737,0.34655482456186937,0.18390672754362586,0.08355740154472048,0.01991535072984335,-0.10590690605108638,-0.2616922149477122,-0.3293576370402245,0.00928715017035573,-0.28302189038842845,0.10041695823206657,-3.5505942718247523,-0.8235247394900737,0.34655482456186937,0.18390672754362586,0.08355740154472048,0.01991535072984335,-0.10590690605108638,-0.2616922149477122,-0.3293576370402245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5666738,1.0,0.0,1.0,1.0,1.8742703140582158,1.2757049781046539,0.543271714833119,-0.2074445712834489,0.003765243645278267,0.006856175531076022,-0.9782155006144632,0.3267828098181995,0.08284382821804354,0.08937993823027597,0.5815791501332317,-0.353765447677307,1.5369737850781882,0.017612653224213348,-0.29361226089850867,0.10782577962986163,-3.056121927126402,-0.8413500016543756,0.2903545562772507,0.18909929534879752,0.09236322936759896,0.017115159322902352,-0.06601836872644339,-0.05622440533027145,-0.1816910921646653,0.017612653224213348,-0.29361226089850867,0.10782577962986163,-3.056121927126402,-0.8413500016543756,0.2903545562772507,0.18909929534879752,0.09236322936759896,0.017115159322902352,-0.06601836872644339,-0.05622440533027145,-0.1816910921646653,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.5833405,1.0,0.0,1.0,1.0,1.8688627840902805,1.2767244866876006,0.5446561607536192,-0.19447383643878247,-1.4064346361510593e-05,0.002674343046903588,-0.9809040598510353,0.3740343052722976,0.06513428267527653,0.0601398916609786,0.5936035009277747,-0.3249164819165817,1.5455934064867605,0.0273741717867338,-0.29501072467631684,0.10639437408955521,-2.4846126460453335,-0.8871595264445885,0.07398837168906518,0.18930555135060678,0.09667255831142914,0.019742171274767985,-0.09621079120072666,0.21540145392258675,-0.09867620310692592,0.0273741717867338,-0.29501072467631684,0.10639437408955521,-2.4846126460453335,-0.8871595264445885,0.07398837168906518,0.18930555135060678,0.09667255831142914,0.019742171274767985,-0.09621079120072666,0.21540145392258675,-0.09867620310692592,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6000072,1.0,0.0,1.0,1.0,1.8619151809525292,1.2784442912938574,0.5452782868648046,-0.18216188380512313,-0.003394780123968635,-0.001791916304921871,-0.9832610602441424,0.44833507139181145,0.04308988186913795,0.020585919256564514,0.6398957147768691,-0.25956687089689956,1.4991364785157235,0.03625015514661536,-0.28864766833975586,0.1032127921666199,-2.0717831365856756,-1.025005810635652,-0.06213306180253165,0.18291231910131062,0.09460068723402669,0.030180210290739442,-0.09795894680939717,0.2016642670439182,-0.09597617854171041,0.03625015514661536,-0.28864766833975586,0.1032127921666199,-2.0717831365856756,-1.025005810635652,-0.06213306180253165,0.18291231910131062,0.09460068723402669,0.030180210290739442,-0.09795894680939717,0.2016642670439182,-0.09597617854171041,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6166739,1.0,0.0,1.0,1.0,1.85440091945827,1.2807387489804825,0.5454391890769893,-0.16987402102836546,-0.006246370225313629,-0.006932483070321696,-0.9854216054649617,0.45463954777195653,0.010638499213863756,0.033255922256329076,0.7637407701751762,-0.12006641049309863,1.4639094234371768,0.047100383905542206,-0.2890534735668178,0.09698170067562083,-1.619419599774798,-1.0563148377429623,-0.2661206373073608,0.18118180883922508,0.08857050295634257,0.057874628333738534,-0.09694295961379638,0.18478371036533975,-0.09192389167549751,0.047100383905542206,-0.2890534735668178,0.09698170067562083,-1.619419599774798,-1.0563148377429623,-0.2661206373073608,0.18118180883922508,0.08857050295634257,0.057874628333738534,-0.09694295961379638,0.18478371036533975,-0.09192389167549751,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6333406,1.0,0.0,1.0,1.0,1.8475338887176305,1.2831979928651231,0.5465430941043943,-0.15804180604924423,-0.007673609847714827,-0.013826318980592214,-0.9873057966790457,0.43024390966445303,-0.012605703690637987,0.07656345575833182,0.910084920691556,0.07772512442378976,1.4327489482204554,0.06011829711278539,-0.29181649330976644,0.08554845417335417,-0.9883035693138436,-0.8901650070273597,-0.6290584986978147,0.18299890302552793,0.08174481583806974,0.09514934351434945,-0.09275893070964623,0.1665216573540067,-0.08365797503792119,0.06011829711278539,-0.29181649330976644,0.08554845417335417,-0.9883035693138436,-0.8901650070273597,-0.6290584986978147,0.18299890302552793,0.08174481583806974,0.09514934351434945,-0.09275893070964623,0.1665216573540067,-0.08365797503792119,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6500073,1.0,0.0,1.0,1.0,1.8409584016343579,1.2856798853844658,0.5481321737660579,-0.14615184029919356,-0.007680507704236202,-0.021911891670050025,-0.9889896452349762,0.452267295519063,-0.02000082474080439,0.06610769839348282,0.975578767829971,0.21906692528817223,1.4201369753486077,0.0722504559089637,-0.2926578670688702,0.07530300662102693,-0.4241727383420873,-0.8392142657898961,-0.8226554181468712,0.05083808504997083,0.2369473610932717,0.23205225415253425,-0.09007218629912177,0.1561486246263876,-0.07482282425267565,0.0722504559089637,-0.2926578670688702,0.07530300662102693,-0.4241727383420873,-0.8392142657898961,-0.8226554181468712,0.05083808504997083,0.2369473610932717,0.23205225415253425,-0.09007218629912177,0.1561486246263876,-0.07482282425267565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.666674,1.0,0.0,0.0,1.0,1.8333441995445146,1.2882893366166124,0.5488463889943543,-0.13442351248648682,-0.006953074294855642,-0.030249431667125397,-0.9904377546986289,0.6176781818132512,-0.07894259036565676,0.03564883844892843,0.25677671487442555,0.23970720423438963,1.2755906516565212,0.07922610469617926,-0.2344469935021831,0.0013901828639919385,-0.07922805222366704,-0.8744797063591437,-0.6655504338320408,-0.10610046125660953,0.4971853855758636,0.32458019870037963,-0.0728958976981763,0.1715736090303747,-0.004294248672040216,0.07922610469617926,-0.2344469935021831,0.0013901828639919385,-0.07922805222366704,-0.8744797063591437,-0.6655504338320408,-0.10610046125660953,0.4971853855758636,0.32458019870037963,-0.0728958976981763,0.1715736090303747,-0.004294248672040216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.6833407,1.0,0.0,0.0,1.0,1.8218407726194508,1.2937714846628705,0.5492717245703487,-0.12493313857158693,-0.005066237417000728,-0.026525685187421277,-0.9917975761970913,0.5529854208490471,-0.05205587230993494,-0.03029788208247258,0.4071674050127705,0.31086647311904075,1.50147152365338,0.10238744661787472,-0.27792642982518123,0.007660146320020051,0.06599452180451157,-0.831977417449591,-0.4308083894151179,-0.12509647303354163,0.6330600271250387,0.481109231751877,-0.08891743467626971,0.19226923083130062,-0.010619244353132813,0.10238744661787472,-0.27792642982518123,0.007660146320020051,0.06599452180451157,-0.831977417449591,-0.4308083894151179,-0.12509647303354163,0.6330600271250387,0.481109231751877,-0.08891743467626971,0.19226923083130062,-0.010619244353132813,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7000074,1.0,0.0,0.0,1.0,1.8159003753378056,1.294488998730869,0.5478075023578777,-0.10944434161761243,-0.0031620751943704124,-0.03750720755138089,-0.9932799941356164,0.4545696812103789,-0.008463596106556864,-0.08511076077967991,0.6398314955282788,0.2881626552894161,1.7032027983048939,0.11687223563339318,-0.31936482001343275,0.04216760389525556,0.03638676223485067,-0.2717062343263296,-0.3432689725687263,-0.28613885030031055,0.7580022205995148,0.605554854389173,-0.11381467078490684,0.2066875290939767,-0.042002693610766896,0.11687223563339318,-0.31936482001343275,0.04216760389525556,0.03638676223485067,-0.2717062343263296,-0.3432689725687263,-0.28613885030031055,0.7580022205995148,0.605554854389173,-0.11381467078490684,0.2066875290939767,-0.042002693610766896,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7166741,1.0,1.0,0.0,1.0,1.8070718724002077,1.2971346130168175,0.5463922987937954,-0.09652950774252411,-0.002669564047350614,-0.03757372670981114,-0.9946170834164874,0.563921201462197,-0.04412420244244869,-0.09392002577465239,-0.21882818083497563,0.06217002184736295,1.5511638044789269,0.11228623021724246,-0.24881638836060477,-0.014122966822631425,-0.1010814514687554,0.030835916136049225,-0.12141353877538764,-0.5429427296353385,0.8325422170581105,0.5109646570852492,-0.1098897490100669,0.23096188929658876,0.013920484505073848,0.11228623021724246,-0.24881638836060477,-0.014122966822631425,-0.1010814514687554,0.030835916136049225,-0.12141353877538764,-0.5429427296353385,0.8325422170581105,0.5109646570852492,-0.1098897490100669,0.23096188929658876,0.013920484505073848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7333407999999997,1.0,1.0,0.0,1.0,1.7976963334801195,1.2993091093346945,0.544538488325043,-0.08369986507681833,-0.0027990735158150326,-0.03391863254155388,-0.9959096465744705,0.5689722438912759,-0.011086382207570578,-0.09800389158726619,-0.4536860903854011,-0.057465782006288796,1.5923060899951693,0.11802173519188103,-0.24005039182526824,-0.022086035098333984,-0.19495171739733727,-0.18107414718374326,0.06842298773519959,-0.7265465119200741,0.9354223583514523,0.44351616765199725,-0.12282009962956812,0.2470362265346414,0.023137367693009996,0.11802173519188103,-0.24005039182526824,-0.022086035098333984,-0.19495171739733727,-0.18107414718374326,0.06842298773519959,-0.7265465119200741,0.9354223583514523,0.44351616765199725,-0.12282009962956812,0.2470362265346414,0.023137367693009996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7500074999999997,1.0,1.0,0.0,1.0,1.788396902859458,1.3004444391537682,0.5431059759549913,-0.0701496026156091,-0.003892594257743455,-0.029900956070241454,-0.9970806455793344,0.5578527758014764,0.014552306606604337,-0.06283644692145494,-0.5930108128152782,-0.1298350108463302,1.5885253744089687,0.12087669287526072,-0.22852511273180443,-0.027719216933576016,-0.1921765992296495,-0.17700304201022465,0.0917624037850534,-0.977236883104754,1.1480353794678901,0.38535292310693764,-0.13149924432038432,0.2508851394432996,0.029954140254751564,0.12087669287526072,-0.22852511273180443,-0.027719216933576016,-0.1921765992296495,-0.17700304201022465,0.0917624037850534,-0.977236883104754,1.1480353794678901,0.38535292310693764,-0.13149924432038432,0.2508851394432996,0.029954140254751564,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7666741999999998,1.0,1.0,0.0,1.0,1.7791919891745511,1.3013115186218693,0.5425432694341168,-0.05740757311858686,-0.005086323905785647,-0.023811701231203613,-0.9980538576360675,0.5642644043955709,0.01928911008925782,-0.022161868131380432,-0.7390010841161105,-0.15241014198584263,1.5181907210740555,0.12061960627510354,-0.2067692006279454,-0.04292921315858916,-0.1790393413197263,-0.16491644890388998,0.1069147326058401,-1.29104127970552,1.254534603800988,0.23882306689131824,-0.13188360611295943,0.2457062804679397,0.04514129049763213,0.12061960627510354,-0.2067692006279454,-0.04292921315858916,-0.1790393413197263,-0.16491644890388998,0.1069147326058401,-1.29104127970552,1.254534603800988,0.23882306689131824,-0.13188360611295943,0.2457062804679397,0.04514129049763213,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.7833409,1.0,1.0,0.0,1.0,1.7696299556329935,1.3019316479165521,0.542538598976739,-0.045019848331857515,-0.006330313179101539,-0.017335249967095557,-0.998815613364053,0.6013623404880951,0.02227273704295879,-0.0019876867634571705,-0.7309732197884331,-0.13755892920325846,1.5010979007251724,0.12498225251954503,-0.20090761950536593,-0.047506663877300855,-0.17189005521132847,-0.1688143815889882,0.1018972650050938,-1.6175767707435043,1.3181336963223662,-0.11434460890311225,-0.13556668388977974,0.23904100227303327,0.049795262895869254,0.12498225251954503,-0.20090761950536593,-0.047506663877300855,-0.17189005521132847,-0.1688143815889882,0.1018972650050938,-1.6175767707435043,1.3181336963223662,-0.11434460890311225,-0.13556668388977974,0.23904100227303327,0.049795262895869254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8000076,1.0,1.0,0.0,1.0,1.759161853032661,1.3023774397679335,0.5427253904028725,-0.03253806104004453,-0.007254396192181359,-0.011378018664948782,-0.9993794019344712,0.6392798757153976,0.01939997854712483,0.0014877718138701823,-0.6284780432691475,-0.08384424499713189,1.4756897297521125,-0.017180877767499898,-0.2400690450758294,0.01697540586412404,-0.16261090660021865,-0.17630127140069832,0.08181850885858499,-1.9027724735252283,1.251383285868155,-0.4459604328763881,-0.1365356795904901,0.22627900080959998,0.0493945026912173,-0.017180877767499898,-0.2400690450758294,0.01697540586412404,-0.16261090660021865,-0.17630127140069832,0.08181850885858499,-1.9027724735252283,1.251383285868155,-0.4459604328763881,-0.1365356795904901,0.22627900080959998,0.0493945026912173,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8166743,0.0,1.0,0.0,1.0,1.7483267543094172,1.3026770102657523,0.5428963882695916,-0.020535264708768933,-0.007653582523030143,-0.0066375832016456965,-0.9997377996590633,0.6531448884140343,0.014239886790821332,-0.0004621991736712492,-0.4426763411216122,-0.020345516022165028,1.4068547285864048,-0.30448347180014096,-0.32228112459159125,0.07500182986995038,-0.14852574482280767,-0.18092573208664547,0.051972877201686245,-2.089045384830667,1.1086231958280484,-0.618647143418973,-0.1325828546173226,0.2038883897748284,0.04108546891029853,-0.30448347180014096,-0.32228112459159125,0.07500182986995038,-0.14852574482280767,-0.18092573208664547,0.051972877201686245,-2.089045384830667,1.1086231958280484,-0.618647143418973,-0.1325828546173226,0.2038883897748284,0.04108546891029853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.833341,0.0,1.0,0.0,1.0,1.7373915445092991,1.302799164709831,0.5430436737424552,-0.009157671995814853,-0.007577620731367921,-0.0038104351987206767,-0.9999220956110857,0.6590938044906411,-0.0030756633887750184,-0.01824688112788047,-0.33696879706966765,-0.0023695833666822763,1.3528456546359042,-0.6747608596515837,-0.42004934174411807,0.04221563847988109,-0.1382762302106438,-0.18234447375034257,0.037537898975278226,-2.203693641427739,1.000415915197975,-0.6743981545708727,-0.13142862271405764,0.18812730085952542,0.03398925038740325,-0.6747608596515837,-0.42004934174411807,0.04221563847988109,-0.1382762302106438,-0.18234447375034257,0.037537898975278226,-2.203693641427739,1.000415915197975,-0.6743981545708727,-0.13142862271405764,0.18812730085952542,0.03398925038740325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8500077,0.0,1.0,0.0,1.0,1.7263557368821365,1.3031785844378185,0.542618848706621,0.0019678730496901498,-0.0077297632985105095,-0.0008533723375799751,-0.9999678244776993,0.6646674737800674,-0.015851381948189802,-0.04529366489172529,-0.37186811211878446,-0.011069030686351206,1.3146313757227261,-1.1672816820772398,-0.6519112842019286,0.03008462838387019,-0.13080593807944174,-0.17802878659333968,0.04120508644549572,-2.2513369789241393,0.9007571472636032,-0.649205095648123,-0.13213583217969635,0.18201960894532165,0.037528693874010255,-1.1672816820772398,-0.6519112842019286,0.03008462838387019,-0.13080593807944174,-0.17802878659333968,0.04120508644549572,-2.2513369789241393,0.9007571472636032,-0.649205095648123,-0.13213583217969635,0.18201960894532165,0.037528693874010255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8666744,0.0,1.0,0.0,1.0,1.7152133155783928,1.303238013802475,0.541875757696928,0.012703347968817558,-0.007799204272933036,0.0025568910167495084,-0.9998856232946951,0.6672158724852428,-0.016952430725718615,-0.06485860427027157,-0.45140841748036054,-0.012793609735615163,1.2131321417222074,-1.6948331494236402,-0.867228853109059,0.018833114076249644,-0.11744079052848445,-0.16155459825264074,0.048209459173311826,-2.2252935138871877,0.86181144093785,-0.6201355891696677,-0.12549331969622476,0.17064545312013554,0.04630272594491311,-1.6948331494236402,-0.867228853109059,0.018833114076249644,-0.11744079052848445,-0.16155459825264074,0.048209459173311826,-2.2252935138871877,0.86181144093785,-0.6201355891696677,-0.12549331969622476,0.17064545312013554,0.04630272594491311,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.8833411,0.0,1.0,0.0,1.0,1.7040768547661405,1.3031882210525783,0.5408056166153612,0.022126465315670252,-0.008000573087945684,0.0068226046738486985,-0.9996998861800291,0.6585309232555608,-0.027244644277496177,-0.09592329824697986,-0.5601575724187644,-0.023072573833727905,1.0639375057439266,-2.1277694475526916,-0.7856159754256401,0.1224381379576678,-0.10095902619165255,-0.13585201937949481,0.059440574353982305,-2.0638181085059553,0.8441355088028711,-0.40899140056247657,-0.11358150751824561,0.15535309535298256,0.05701416270331687,-2.1277694475526916,-0.7856159754256401,0.1224381379576678,-0.10095902619165255,-0.13585201937949481,0.059440574353982305,-2.0638181085059553,0.8441355088028711,-0.40899140056247657,-0.11358150751824561,0.15535309535298256,0.05701416270331687,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9000078,0.0,1.0,1.0,1.0,1.6931943544083905,1.3032141771315469,0.5390362342966933,0.03035828353581571,-0.008283147266872421,0.01202230322741648,-0.9994324531038715,0.6195965875825766,-0.03258792238259456,-0.11683004288487044,-0.6656720058847538,-0.06253339130299906,0.8876747745232638,-2.513080295737292,-0.6136148876739791,0.3115605676055078,-0.08475425603807944,-0.10589635192253374,0.07511682086576145,-0.936509702720388,0.4935414887529733,-0.1500243096492121,-0.0993530793050286,0.1372637628216906,0.06363810512058354,-2.513080295737292,-0.6136148876739791,0.3115605676055078,-0.08475425603807944,-0.10589635192253374,0.07511682086576145,-0.936509702720388,0.4935414887529733,-0.1500243096492121,-0.0993530793050286,0.1372637628216906,0.06363810512058354,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9166745,0.0,1.0,1.0,1.0,1.6833314755979134,1.303106400459282,0.537266462432474,0.03683651481145844,-0.009216696267934577,0.017995853411226677,-0.999116746404769,0.528076595803759,-0.03391153936222152,-0.11176669312451909,-0.7873162900981591,-0.17038940193203278,0.694394646918868,-2.889005325773822,-0.45997573191988167,0.47295914924466465,-0.0713443297682317,-0.07300995171257871,0.10334157773391818,0.0493177141409422,0.1342815295524418,-0.09628061239084713,-0.08600522456066471,0.11847543553264459,0.06336869217526754,-2.889005325773822,-0.45997573191988167,0.47295914924466465,-0.0713443297682317,-0.07300995171257871,0.10334157773391818,0.0493177141409422,0.1342815295524418,-0.09628061239084713,-0.08600522456066471,0.11847543553264459,0.06336869217526754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9333412,0.0,1.0,1.0,1.0,1.6754861435154025,1.3031706756103965,0.5356559837494587,0.04185776377156081,-0.011411705779607175,0.02512500551587354,-0.9987424265951013,0.43670718982634893,-0.03413467876127785,-0.10192936254340515,-0.9751612703438395,-0.2951648052750434,0.5194202909679356,-3.333134577735283,-0.46284798424022694,0.5178726612883481,-0.061001991667854166,-0.04055050664321919,0.14168239739642946,0.023778115090160475,0.12384043057739236,-0.12891433051524198,-0.07472365676435155,0.10528680729126891,0.06785841802691878,-3.333134577735283,-0.46284798424022694,0.5178726612883481,-0.061001991667854166,-0.04055050664321919,0.14168239739642946,0.023778115090160475,0.12384043057739236,-0.12891433051524198,-0.07472365676435155,0.10528680729126891,0.06785841802691878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9500078999999997,0.0,1.0,1.0,1.0,1.6686502648704482,1.3031806166637119,0.5342333783513367,0.04542327471334445,-0.014612225605631335,0.03411222719026323,-0.9982783003417866,0.41343212475131097,-0.0213882340826462,-0.0812212480907227,-1.0235823510905062,-0.38407275901579807,0.449124628313025,-3.5587519887807084,-0.44120346462615695,0.44717164636231105,-0.05776234002847412,-0.031273515539843394,0.15994427050866697,0.010608443490004605,0.11983002093879695,-0.14284622520350052,-0.0722967939292011,0.09811419506838066,0.06367331176045238,-3.5587519887807084,-0.44120346462615695,0.44717164636231105,-0.05776234002847412,-0.031273515539843394,0.15994427050866697,0.010608443490004605,0.11983002093879695,-0.14284622520350052,-0.0722967939292011,0.09811419506838066,0.06367331176045238,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9666745999999997,0.0,1.0,1.0,1.0,1.661616476777083,1.30279626626616,0.5333649074891793,0.04930767779342826,-0.018314539467891782,0.04197316971489398,-0.9977332226496136,0.4185892741845352,-0.025598589292242402,-0.059003190667716685,-0.9697578891152128,-0.425698493788441,0.5007535271414512,-3.5701688102522575,-0.25515180965064893,0.4583292410186167,-0.06242586106125509,-0.04546138570470161,0.16009418188104846,0.01112738203924941,0.12611064722470475,-0.14053375574826055,-0.08054329185482914,0.10011161441105838,0.05587631680992097,-3.5701688102522575,-0.25515180965064893,0.4583292410186167,-0.06242586106125509,-0.04546138570470161,0.16009418188104846,0.01112738203924941,0.12611064722470475,-0.14053375574826055,-0.08054329185482914,0.10011161441105838,0.05587631680992097,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +3.9833412999999998,0.0,1.0,1.0,1.0,1.6546118043681053,1.302793613036635,0.5328000327756283,0.053751844797037485,-0.022133948648832672,0.050042457088466594,-0.9970539503891829,0.42717831978271736,-0.05469255267000406,-0.051238359142840695,-0.8564019896516025,-0.3699524266823594,0.6054308652386922,-3.46893316220441,-0.17711921307131417,0.48339218230020486,-0.06706165525974556,-0.06835061855105841,0.13825008875551295,0.02241957641548176,0.13501341870370348,-0.12032907166481097,-0.08953219908641577,0.10527141643836309,0.05472279985142169,-3.46893316220441,-0.17711921307131417,0.48339218230020486,-0.06706165525974556,-0.06835061855105841,0.13825008875551295,0.02241957641548176,0.13501341870370348,-0.12032907166481097,-0.08953219908641577,0.10527141643836309,0.05472279985142169,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.000008,0.0,1.0,1.0,1.0,1.6471974594917937,1.303208249452176,0.5324053338610172,0.05935923675625632,-0.02470634417152504,0.05610686431076617,-0.9963523961664398,0.46426735669793595,-0.10256008936580238,-0.02268116095411172,-0.7112615462791223,-0.264754772142962,0.6473438808037252,-3.116712722225679,-0.14783921120790233,0.40374742943132136,-0.06455487509592286,-0.08102094237919703,0.10633424240521962,0.03152556862424478,0.1327664582424251,-0.09208298386306077,-0.11566839076396483,0.2354992925631566,0.17553876071559346,-3.116712722225679,-0.14783921120790233,0.40374742943132136,-0.06455487509592286,-0.08102094237919703,0.10633424240521962,0.03152556862424478,0.1327664582424251,-0.09208298386306077,-0.11566839076396483,0.2354992925631566,0.17553876071559346,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0166747,0.0,1.0,1.0,0.0,1.6388269854334938,1.3043755415671143,0.5331007463552586,0.06445336643128419,-0.026630236323072865,0.06186075949356257,-0.9956454391518759,0.5102006729020758,-0.12022147170925634,0.06179316888057879,-0.4280910601160981,-0.1256539591169878,0.6801711570753683,-2.5980692447662914,-0.05416318857748253,0.24373884241976013,-0.059857341751873516,-0.09541977541736246,0.054161586571364675,0.04426425771381546,0.11974864990758945,-0.04728044191369326,-0.17667384433354827,0.36210080369885284,0.2998585439155392,-2.5980692447662914,-0.05416318857748253,0.24373884241976013,-0.059857341751873516,-0.09541977541736246,0.054161586571364675,0.04426425771381546,0.11974864990758945,-0.04728044191369326,-0.17667384433354827,0.36210080369885284,0.2998585439155392,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0333414,0.0,1.0,1.0,0.0,1.6299806828930024,1.3046662485421636,0.5357200480094427,0.0705827628984201,-0.026522765524856984,0.06339062113556974,-0.995136295008169,0.5558531553587231,-0.11070264255012016,0.15267631648167923,-0.08608018278781328,0.013377710490828698,0.6833873584722128,-1.826365545764946,0.02857586405071691,-0.20175483222025795,-0.053124861898400044,-0.10651215477194918,-0.0031746404268847813,0.05568935280429409,0.09848293166002473,0.0016719602227640857,-0.2513403286027981,0.34594835839324084,0.3202121115703049,-1.826365545764946,0.02857586405071691,-0.20175483222025795,-0.053124861898400044,-0.10651215477194918,-0.0031746404268847813,0.05568935280429409,0.09848293166002473,0.0016719602227640857,-0.2513403286027981,0.34594835839324084,0.3202121115703049,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0500081,0.0,1.0,1.0,0.0,1.6203174090834103,1.304711023866885,0.5394335509496212,0.07573487646548993,-0.025781232531277475,0.06361068135119577,-0.9947629052965143,0.5959980585413402,-0.11224265716464915,0.17312121077260806,0.0833009268028215,0.051928449541675116,0.5566368958799204,-1.2424245496735635,-0.005003828715567976,-0.8244955664085477,-0.04045441950252977,-0.0919695823677294,-0.025152740642814416,0.049025173105509655,0.07079100858861768,0.020687728477671856,-0.30013659524392344,0.3592248430188642,0.35674063705922293,-1.2424245496735635,-0.005003828715567976,-0.8244955664085477,-0.04045441950252977,-0.0919695823677294,-0.025152740642814416,0.049025173105509655,0.07079100858861768,0.020687728477671856,-0.30013659524392344,0.3592248430188642,0.35674063705922293,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0666747999999995,0.0,1.0,1.0,0.0,1.6101684735721238,1.3045681042764785,0.5427520938000858,0.0797913727910668,-0.024959062774787367,0.06231577911617874,-0.9945487045321938,0.6247216586745389,-0.12371967498948383,0.1211766040289953,-0.06707329516469054,0.055307708907236415,0.43847727342268333,-0.9112866580126429,0.07196605285877451,-1.024107102857584,-0.031026496552225197,-0.0673604181512348,-0.007843435952269337,0.037000149536039625,0.06427178546609721,0.005727457738060477,-0.31709671333579603,0.41034210818174244,0.37520011885827576,-0.9112866580126429,0.07196605285877451,-1.024107102857584,-0.031026496552225197,-0.0673604181512348,-0.007843435952269337,0.037000149536039625,0.06427178546609721,0.005727457738060477,-0.31709671333579603,0.41034210818174244,0.37520011885827576,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.0833414999999995,0.0,1.0,1.0,0.0,1.599383414096767,1.3048960691020228,0.5447907278778492,0.08292046431012502,-0.02451319787766124,0.06497767592186744,-0.9941333921361845,0.6465345226761721,-0.1419506746732577,0.05925970968799367,-0.4528932371983502,0.020620402384871644,0.3572397737529201,-0.4151094384513455,0.24448976605283812,-1.0893224778159643,-0.02679504253475803,-0.04085482571699478,0.039156017244153664,0.02272627478508198,0.07772495094018779,-0.03466136284199138,-0.3603477342611675,0.49410112895670977,0.37669765425012647,-0.4151094384513455,0.24448976605283812,-1.0893224778159643,-0.02679504253475803,-0.04085482571699478,0.039156017244153664,0.02272627478508198,0.07772495094018779,-0.03466136284199138,-0.3603477342611675,0.49410112895670977,0.37669765425012647,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1000081999999995,0.0,1.0,1.0,0.0,1.5882920721358658,1.3053258546386992,0.5461570493472208,0.08550561608352837,-0.024865092104814142,0.06999137058931666,-0.9935651588375191,0.654672783332763,-0.1441381256309342,0.021077572831963945,-0.5491597672657277,-0.05334799429355899,0.22413016973828076,-0.04174769383075777,-0.08234045189278018,-0.9352205163421962,-0.020025940731547634,-0.018125197360877775,0.06247978644438192,0.006330964540781837,0.06630245669274426,-0.05371618213420844,-0.5230947936614437,0.5314505912360424,0.3203465748555178,-0.04174769383075777,-0.08234045189278018,-0.9352205163421962,-0.020025940731547634,-0.018125197360877775,0.06247978644438192,0.006330964540781837,0.06630245669274426,-0.05371618213420844,-0.5230947936614437,0.5314505912360424,0.3203465748555178,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1166749,0.0,1.0,1.0,0.0,1.5771505181534613,1.3057047940905295,0.5469912802130115,0.0864710030060082,-0.025923694560267316,0.0740863142963373,-0.9931575633974024,0.6328736697847792,-0.15049413902069797,-0.009369540752763736,-0.44793408148768454,-0.09941192342829716,0.09373751336014136,0.14840906265111065,0.007210514883852095,-0.27088680061260784,-0.01190188586616181,-0.0023418850198775308,0.06085468456917331,-0.005247819369150817,0.04256641678819505,-0.05141451097867234,-0.7908505379969463,0.5026497300544932,0.2792550369397022,0.14840906265111065,0.007210514883852095,-0.27088680061260784,-0.01190188586616181,-0.0023418850198775308,0.06085468456917331,-0.005247819369150817,0.04256641678819505,-0.05141451097867234,-0.7908505379969463,0.5026497300544932,0.2792550369397022,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1333416,0.0,1.0,1.0,0.0,1.5666776336635044,1.3065523839755013,0.5474252751082748,0.08698790929387473,-0.02704151041712598,0.077302800122241,-0.9928374174275978,0.6058483555621152,-0.1573573696596669,-0.03716584399478255,-0.34670803628839425,-0.08190893166441802,0.06059171687935354,0.10987509707812981,0.44990463699881444,-0.04807282079758487,-0.008414699608723975,-0.00029589857054870627,0.04807747418860815,-0.005418432132296344,0.03156337428242366,-0.04035226968957618,-1.0384201003919915,0.5019537286103781,0.37109896013814264,0.10987509707812981,0.44990463699881444,-0.04807282079758487,-0.008414699608723975,-0.00029589857054870627,0.04807747418860815,-0.005418432132296344,0.03156337428242366,-0.04035226968957618,-1.0384201003919915,0.5019537286103781,0.37109896013814264,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1500083,1.0,1.0,1.0,0.0,1.5563234290137045,1.3074196119004642,0.5474116326094174,0.08742255075191707,-0.027703586264875745,0.07973230816231605,-0.9925888211959687,0.5910148835901281,-0.15833778551783445,-0.04873452575168352,-0.3186802711220344,-0.025468145323153973,0.04465404014324121,-0.030806565253989816,0.2167233176784188,-0.12160108877912164,-0.004847444607376638,0.002877949218861962,0.03699478920222705,-0.003002567878363581,0.02718332082735151,-0.031100961303418447,-1.2346636796174437,0.49929367507116895,0.46708672517347943,-0.030806565253989816,0.2167233176784188,-0.12160108877912164,-0.004847444607376638,0.002877949218861962,0.03699478920222705,-0.003002567878363581,0.02718332082735151,-0.031100961303418447,-1.2346636796174437,0.49929367507116895,0.46708672517347943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.166675,1.0,1.0,1.0,0.0,1.546303815200699,1.3084257528532224,0.5474937277752739,0.08761179076682951,-0.02786858036470671,0.08255829062415929,-0.9923364575567614,0.5643608967171073,-0.17000076849248325,-0.04103378873441706,-0.28861797417790125,0.0459094121614195,0.0677817148264284,0.005701667919512313,0.011826829104716042,-0.034809809857658046,-0.14638550797613706,-0.009462920385403651,0.10950023105083206,0.003429526262877758,0.02779585355302063,-0.019255641260206822,-1.442533445273943,0.5532908521341982,0.46074099686571646,0.005701667919512313,0.011826829104716042,-0.034809809857658046,-0.14638550797613706,-0.009462920385403651,0.10950023105083206,0.003429526262877758,0.02779585355302063,-0.019255641260206822,-1.442533445273943,0.5532908521341982,0.46074099686571646,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.1833417,1.0,0.0,1.0,0.0,1.536774684371192,1.3097818895963074,0.5477891324111751,0.08834447052837496,-0.02727081533879821,0.08460464428261243,-0.9921157247638156,0.5324090136344453,-0.17286832807928534,-0.046787241963862296,-0.21392335279744745,0.12001631954948438,0.11592887410875433,0.015816432727183454,0.0034262327063692855,-0.04052665837448575,-0.4908467412315272,-0.013681859089975434,0.21524856761378935,0.012647564919575123,0.02882964401847807,-0.00268028273395934,-1.770205403410856,0.6347373102937808,0.27878176263318966,0.015816432727183454,0.0034262327063692855,-0.04052665837448575,-0.4908467412315272,-0.013681859089975434,0.21524856761378935,0.012647564919575123,0.02882964401847807,-0.00268028273395934,-1.770205403410856,0.6347373102937808,0.27878176263318966,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2000084,1.0,0.0,1.0,0.0,1.527769010539359,1.311077033471965,0.5476489312740247,0.08926073222977332,-0.026034970989936224,0.08632533838294863,-0.9919186649722989,0.5129098475763808,-0.15780375466363433,-0.0789283645499828,-0.2363339776918599,0.20925971699190993,0.14554936371565264,0.022851126687691566,0.004428535533135946,-0.05664036355799309,-1.0315386443172097,0.017077272639352572,0.36562852968582804,0.01976451937183562,0.03344661211758476,0.0067685292690413046,-2.1657341987146728,0.6680934650094161,-0.07728397764265575,0.022851126687691566,0.004428535533135946,-0.05664036355799309,-1.0315386443172097,0.017077272639352572,0.36562852968582804,0.01976451937183562,0.03344661211758476,0.0067685292690413046,-2.1657341987146728,0.6680934650094161,-0.07728397764265575,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2166751,1.0,0.0,1.0,0.0,1.5188890270381192,1.3122137726498586,0.5467458010952325,0.09034634579273876,-0.023953909165564308,0.088886455528479,-0.9916465832448427,0.49711741510201496,-0.15087660606118466,-0.1201220601172355,-0.22723985833368898,0.3271266435599331,0.14485068901108003,0.027907153861061917,0.008360555029293108,-0.07323372227972719,-1.7074506857379848,0.4370668809180458,0.5446014601122777,0.026590306753981625,0.031277119056875365,0.021990750742356416,-2.547098203191003,0.6544991281886615,-0.4227039542694218,0.027907153861061917,0.008360555029293108,-0.07323372227972719,-1.7074506857379848,0.4370668809180458,0.5446014601122777,0.026590306753981625,0.031277119056875365,0.021990750742356416,-2.547098203191003,0.6544991281886615,-0.4227039542694218,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2333418,1.0,0.0,1.0,0.0,1.510353655056615,1.313593490813373,0.5451421685254204,0.09107475981501867,-0.02075600247037188,0.09063335568243995,-0.9914939088687469,0.4878183690338027,-0.1686534601943686,-0.14610281712955364,-0.03717695826643283,0.4711648496392794,0.08693641836461213,0.02991658866347666,0.008367124491504566,-0.07577020451009452,-2.230354569022441,0.4744000063534074,0.4711042972758572,0.0329968799206854,0.008646205178490166,0.05541978970056128,-2.841722538362086,0.5705447813784593,-0.5656204759240637,0.02991658866347666,0.008367124491504566,-0.07577020451009452,-2.230354569022441,0.4744000063534074,0.4711042972758572,0.0329968799206854,0.008646205178490166,0.05541978970056128,-2.841722538362086,0.5705447813784593,-0.5656204759240637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2500085,1.0,0.0,1.0,0.0,1.501637151092513,1.315508958238816,0.5433923599991546,0.09104861489046695,-0.016092758573962158,0.09024925446814956,-0.9916179934409979,0.48064405562240287,-0.18837455970618552,-0.15310983012095475,0.2509850582580098,0.5717749095833785,0.009338958607271942,0.029175856491922482,0.0024351548605261353,-0.06248925861938511,-2.3284098878591117,0.18928856242194794,0.4067501664929487,0.036239951429807626,-0.022657739461739105,0.09200443254458429,-2.9799008443397192,0.415108232922142,-0.6019161291840236,0.029175856491922482,0.0024351548605261353,-0.06248925861938511,-2.3284098878591117,0.18928856242194794,0.4067501664929487,0.036239951429807626,-0.022657739461739105,0.09200443254458429,-2.9799008443397192,0.415108232922142,-0.6019161291840236,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2666752,1.0,0.0,1.0,0.0,1.4932437275744648,1.3176252349032824,0.5415145978890264,0.0904242518181504,-0.010911143207822866,0.08735774312738623,-0.9920045495625086,0.4498309237722589,-0.17928648743570216,-0.15078405559291078,0.42394502112746957,0.5666511846631366,-0.03294271658005374,0.026617724803905448,-0.00428795744269526,-0.04482113454678423,-1.7791292663533405,0.29767822279126743,0.3116031781755492,0.03410557917964688,-0.039658613827869414,0.10640203174097063,-2.910924179725391,0.2607867543466182,-0.6198673627279255,0.026617724803905448,-0.00428795744269526,-0.04482113454678423,-1.7791292663533405,0.29767822279126743,0.3116031781755492,0.03410557917964688,-0.039658613827869414,0.10640203174097063,-2.910924179725391,0.2607867543466182,-0.6198673627279255,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.2833419,1.0,0.0,1.0,0.0,1.4856425635025863,1.319438832423189,0.5395794148060433,0.0897529972041134,-0.006133288953997958,0.08408858972078245,-0.992388981870645,0.387880195866377,-0.16161378875664678,-0.11099396813951203,0.46641548898389235,0.45737457127900527,-0.030485543427511877,0.0227331639983757,-0.011378877084333007,-0.024650795122730173,-0.9142425646028837,0.38693740616221634,-0.1813120829390345,0.027831681287940013,-0.04038561571834403,0.0973992054484822,-2.563499714173988,0.10625200203593065,-0.6302251289089286,0.0227331639983757,-0.011378877084333007,-0.024650795122730173,-0.9142425646028837,0.38693740616221634,-0.1813120829390345,0.027831681287940013,-0.04038561571834403,0.0973992054484822,-2.563499714173988,0.10625200203593065,-0.6302251289089286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3000086,1.0,0.0,1.0,0.0,1.4794686506309902,1.3211462382799055,0.5387346516534403,0.08932033550678971,-0.0026924549064327665,0.0803245216854369,-0.9927550551709808,0.29928496128874604,-0.16387166785364815,-0.059219106530196464,0.3887331178062886,0.16155954629468688,0.01685349779249461,0.013971970097719522,-0.022217173746425886,0.011024521237820833,-0.34549770198124025,0.21196195739440546,-0.6947680590544684,0.014243256121865073,-0.02509791084927795,0.055315104680769354,-1.8293156715006524,0.03490792890955302,-0.41627012912272626,0.013971970097719522,-0.022217173746425886,0.011024521237820833,-0.34549770198124025,0.21196195739440546,-0.6947680590544684,0.014243256121865073,-0.02509791084927795,0.055315104680769354,-1.8293156715006524,0.03490792890955302,-0.41627012912272626,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3166753,1.0,0.0,1.0,1.0,1.474820453204377,1.3232838999381054,0.538414921623044,0.08982494361912276,-0.0028618963747359606,0.07789711175171152,-0.992902477101202,0.18568440371975126,-0.16429423915814945,-0.05567413792804601,0.34377528408058367,-0.24165152712792565,0.11263846656462476,0.00655126230032834,-0.04435195267006197,0.06442633953810396,0.36422282451949706,0.09462334074873086,-1.2424467122116145,-0.00042465040880327416,-0.004486668108584525,0.003693070323857402,-0.685696819933984,0.03521015396533432,-0.1316411603429221,0.00655126230032834,-0.04435195267006197,0.06442633953810396,0.36422282451949706,0.09462334074873086,-1.2424467122116145,-0.00042465040880327416,-0.004486668108584525,0.003693070323857402,-0.685696819933984,0.03521015396533432,-0.1316411603429221,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.333342,1.0,1.0,1.0,1.0,1.472368196837922,1.3256471961234024,0.5376999194259025,0.09150648776194548,-0.006032737411543143,0.07427716081609244,-0.9930121208514511,0.0971305542416186,-0.15759388685108802,-0.09054155289644997,0.4190189287154652,-0.4611806153797045,0.11490907764450513,-0.0020631428048915415,-0.05598384231363546,0.10390954289033533,0.4427889452326289,0.08544063489906484,-0.7907105647488079,-0.011004512926806457,-0.006962354016955017,-0.016238201778234995,-0.03577421889587256,0.0011084738002410637,-0.09922910355501578,-0.0020631428048915415,-0.05598384231363546,0.10390954289033533,0.4427889452326289,0.08544063489906484,-0.7907105647488079,-0.011004512926806457,-0.006962354016955017,-0.016238201778234995,-0.03577421889587256,0.0011084738002410637,-0.09922910355501578,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3500087,1.0,1.0,1.0,1.0,1.4706100652108414,1.328241681999405,0.5362058877990785,0.0923389848539023,-0.009709455105721184,0.07026679202643472,-0.9931977730019408,0.09773548605908258,-0.13965558646450163,-0.13738176760651208,0.7085036716870325,-0.42139878899927125,0.07969031167762533,-0.00017187425471506336,-0.06765605170009605,0.12600017254805912,-0.020659569993128138,-0.051773530115319516,-0.014229203899551233,-0.00779019952902096,-0.03026679507169305,0.014791467920582651,-0.028277895267450687,-0.014384273486909864,-0.12543790852702438,-0.00017187425471506336,-0.06765605170009605,0.12600017254805912,-0.020659569993128138,-0.051773530115319516,-0.014229203899551233,-0.00779019952902096,-0.03026679507169305,0.014791467920582651,-0.028277895267450687,-0.014384273486909864,-0.12543790852702438,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3666754,1.0,1.0,1.0,1.0,1.4681712513894256,1.3302060009953092,0.5338452682392822,0.09345385442420151,-0.011821861947649535,0.061914173677786316,-0.9936263159614623,0.09240234411338324,-0.10602635481222163,-0.12357578645654867,1.185426076138041,-0.2929713254440787,0.10391425771574722,-0.13145687540250914,-0.22253288345357625,0.2553536009234616,-0.013520793845548551,-0.07066168466295743,-0.08322020291075213,0.007210520794792002,-0.056795738445509114,0.07578692829186462,-0.021562526508975232,-0.032883461257589515,-0.1592455249305028,-0.13145687540250914,-0.22253288345357625,0.2553536009234616,-0.013520793845548551,-0.07066168466295743,-0.08322020291075213,0.007210520794792002,-0.056795738445509114,0.07578692829186462,-0.021562526508975232,-0.032883461257589515,-0.1592455249305028,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.3833421,0.0,1.0,1.0,1.0,1.466789012760989,1.3316082618637024,0.5325987922165354,0.09461086365121699,-0.01260385117894577,0.050199610692425824,-0.9941679568870436,0.04446653865829363,-0.0841189203795186,-0.06426688250374553,1.2564145615933704,-0.14403537355222473,0.06520984877631689,-0.4276754192748405,-0.4276892422266157,0.41331219083273535,-0.0034243882491475286,-0.06482126686778797,-0.1111825117472144,0.013390613650013863,-0.06563660668661102,0.10137978004912189,-0.008141507530072688,-0.04304043242009818,-0.1482966174327861,-0.4276754192748405,-0.4276892422266157,0.41331219083273535,-0.0034243882491475286,-0.06482126686778797,-0.1111825117472144,0.013390613650013863,-0.06563660668661102,0.10137978004912189,-0.008141507530072688,-0.04304043242009818,-0.1482966174327861,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4000088,0.0,1.0,1.0,1.0,1.4661180726578833,1.332873647591579,0.5320241398933144,0.09493358533642421,-0.01216608806068723,0.04088500820451073,-0.9945692619323144,0.04162721590769939,-0.06592759946119249,-0.04672911244167402,1.047031925373761,0.06231247991443928,0.0030127356771116193,-0.6470969364382643,-0.6725124664157875,0.5620673170277914,0.00938579809922099,-0.04350707007761763,-0.1182924328981181,0.016987520182161403,-0.060187157167306896,0.10751585139402851,0.009641285785050937,-0.043512573851291425,-0.10108266151886514,-0.6470969364382643,-0.6725124664157875,0.5620673170277914,0.00938579809922099,-0.04350707007761763,-0.1182924328981181,0.016987520182161403,-0.060187157167306896,0.10751585139402851,0.009641285785050937,-0.043512573851291425,-0.10108266151886514,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4166755,0.0,1.0,1.0,1.0,1.4649642729560457,1.3336185685356463,0.5312534260820703,0.0948490248633549,-0.009909063895373145,0.03294430949663229,-0.9948970526677513,0.08722197467970724,-0.019508714553747766,-0.06647500818156411,0.9231593393744377,0.24275993514650385,0.06728082100018629,-0.5886751342642481,-0.928888910239758,0.6514917007678713,0.013082358652362935,-0.0469728383826207,-0.13214415575758948,0.029265935143232457,-0.04222926301136491,0.11916895176857155,0.01119198435020883,-0.03288824687816377,-0.0648929893410704,-0.5886751342642481,-0.928888910239758,0.6514917007678713,0.013082358652362935,-0.0469728383826207,-0.13214415575758948,0.029265935143232457,-0.04222926301136491,0.11916895176857155,0.01119198435020883,-0.03288824687816377,-0.0648929893410704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4333422,0.0,1.0,1.0,1.0,1.4630837081289236,1.3331013027795933,0.5298965529266109,0.09607878656701097,-0.0066549736734685914,0.02596953454700517,-0.9950126438255085,0.12402036846242481,0.028604136990528814,-0.0658047768255485,0.6732442703313215,0.31153683382904807,0.11673126835156375,-0.3671531761964364,-1.0763057815995682,0.5837603088351554,0.011862505060150245,-0.04414402073125809,-0.11668824252355246,0.0329778027833337,-0.01980961936158626,0.10451461945659214,0.007321128104551632,-0.017087118969608628,-0.029683788191313704,-0.3671531761964364,-1.0763057815995682,0.5837603088351554,0.011862505060150245,-0.04414402073125809,-0.11668824252355246,0.0329778027833337,-0.01980961936158626,0.10451461945659214,0.007321128104551632,-0.017087118969608628,-0.029683788191313704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4500089,0.0,1.0,1.0,1.0,1.4610489199166534,1.3320026892639871,0.529046706672215,0.09673567382926684,-0.0036143011225054315,0.022293473666612725,-0.9950538413915448,0.15735799438748166,0.06544038949735179,-0.042516509133150256,0.4790299073886757,0.3247110560595567,0.14171755977488285,-0.1435597557154534,-1.3359129663766256,0.5161400490055541,0.010124781836693983,-0.040159057684995406,-0.09841004628088501,0.032536181652504687,-0.004673568313870773,0.08775412078607907,0.0036327272418938726,-0.0059810339797417445,-0.007934329937865758,-0.1435597557154534,-1.3359129663766256,0.5161400490055541,0.010124781836693983,-0.040159057684995406,-0.09841004628088501,0.032536181652504687,-0.004673568313870773,0.08775412078607907,0.0036327272418938726,-0.0059810339797417445,-0.007934329937865758,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4666756,0.0,1.0,1.0,1.0,1.4583400199869876,1.3300141948843907,0.5283975796407148,0.09833737530906261,-0.0004483779317112557,0.018554413495774812,-0.994980046691582,0.20809889536349022,0.09209145678150324,-0.028766109451051847,0.24473649319289542,0.2574475533160032,0.19822072005090652,0.07115299109160571,-1.6867379279832422,0.5133152980764072,0.001243494771686575,-0.04022686131029402,-0.06458664543268441,0.030378739447787392,0.01612416360659132,0.05690464797176991,-0.00895954120945832,0.010319838278867254,0.00788964445231141,0.07115299109160571,-1.6867379279832422,0.5133152980764072,0.001243494771686575,-0.04022686131029402,-0.06458664543268441,0.030378739447787392,0.01612416360659132,0.05690464797176991,-0.00895954120945832,0.010319838278867254,0.00788964445231141,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.4833422999999994,0.0,1.0,1.0,1.0,1.4548427372156572,1.3276722412694162,0.5279557585758526,0.09995217734055012,0.0011111263608963255,0.018656005706175056,-0.9948167072854097,0.2417545610928768,0.1069155742969344,-0.0252186539886379,-0.03834738875191147,0.15446738816932892,0.1653496474218272,0.24808603849456468,-2.050496940681975,0.5285849974428175,-0.003994904958816166,-0.02330816060472766,-0.02014379120588247,0.019526142772457206,0.026335772455625676,0.0163182892584545,-0.012896014758240312,0.019481208392321103,0.023803148340778013,0.24808603849456468,-2.050496940681975,0.5285849974428175,-0.003994904958816166,-0.02330816060472766,-0.02014379120588247,0.019526142772457206,0.026335772455625676,0.0163182892584545,-0.012896014758240312,0.019481208392321103,0.023803148340778013,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5000089999999995,0.0,1.0,1.0,1.0,1.4511501637404924,1.3249531690610283,0.5273781807505827,0.10103284217809799,0.00209910079373774,0.019444414587006464,-0.9946908430857508,0.2585057956396905,0.13693419663669132,-0.020327789661955163,-0.08998476160825258,0.08490639243797246,0.22895416232003632,0.39545795243495785,-2.37879406167663,0.5458086982236748,-0.012153261622838356,-0.032643145553242485,-0.005025106006060527,0.019990732032958054,0.03780760221095159,0.0030710406814526223,-0.02485587149794916,0.02783051997643087,0.020652850286835233,0.39545795243495785,-2.37879406167663,0.5458086982236748,-0.012153261622838356,-0.032643145553242485,-0.005025106006060527,0.019990732032958054,0.03780760221095159,0.0030710406814526223,-0.02485587149794916,0.02783051997643087,0.020652850286835233,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5166756999999995,0.0,1.0,1.0,1.0,1.4473198202984863,1.321499666358904,0.527034214215791,0.10372374265735013,0.002442616495684332,0.020280401760490733,-0.9943963616879539,0.25975236422573067,0.17247102709302656,-0.00720230419191934,-0.04878635813910774,0.007499286658488476,0.3531023826827782,0.5335535694547304,-2.50534257136883,0.5528306505277167,-0.023745709747613666,-0.05657813016592476,0.0014257682420918078,0.025347119295641367,0.05287865701333771,-0.0017709014677802768,-0.04375256281841517,0.03789530832832112,0.0073363251061521135,0.5335535694547304,-2.50534257136883,0.5528306505277167,-0.023745709747613666,-0.05657813016592476,0.0014257682420918078,0.025347119295641367,0.05287865701333771,-0.0017709014677802768,-0.04375256281841517,0.03789530832832112,0.0073363251061521135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5333423999999996,0.0,1.0,1.0,1.0,1.4438648108686873,1.317557114274582,0.526830849257118,0.10688439926523098,0.0022611385166314145,0.02024995156951745,-0.9940626498907157,0.2544607328452261,0.20854040016204892,-0.0077502815029570635,0.03363213326447252,-0.030407951280814936,0.42899092475669526,0.6914890560565289,-2.404915591383226,0.421732517313833,-0.029360896003667182,-0.07385527357980701,-0.001821992004062407,0.02939066469299576,0.05921047222091386,0.001997447568263089,-0.05443232236940355,0.041188629211905615,-0.005478474434688997,0.6914890560565289,-2.404915591383226,0.421732517313833,-0.029360896003667182,-0.07385527357980701,-0.001821992004062407,0.02939066469299576,0.05921047222091386,0.001997447568263089,-0.05443232236940355,0.041188629211905615,-0.005478474434688997,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5500091,0.0,1.0,1.0,1.0,1.4405095087957602,1.3129217074068766,0.5264247400988853,0.11083991323558878,0.0021452910699372874,0.019653151776071638,-0.9936416179817646,0.2642336245775348,0.2508160938550163,-0.009967715871779548,0.10651489051948954,-0.020050343028962636,0.5449558298133298,0.7765075832979805,-2.1517851849362226,0.22483344996417623,-0.034870203921163516,-0.09674102742955656,-0.011458135086518204,0.038357213886466665,0.07222164055639646,0.011005146970161842,-0.0679276465266538,0.04893150228656641,-0.011221125352538072,0.7765075832979805,-2.1517851849362226,0.22483344996417623,-0.034870203921163516,-0.09674102742955656,-0.011458135086518204,0.038357213886466665,0.07222164055639646,0.011005146970161842,-0.0679276465266538,0.04893150228656641,-0.011221125352538072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5666758,0.0,1.0,1.0,1.0,1.437115758703724,1.307482226102543,0.5261003708445005,0.11591159315796168,0.0023061645646336795,0.018430590168276247,-0.9930858459985386,0.2763431812199454,0.2858843030710966,0.006274908862898446,0.08451851595137908,0.00195806293004051,0.615793573920887,0.7598307604134638,-1.874386020302522,0.010787275493423558,-0.037637976735281686,-0.1076162340082803,-0.012765744158430844,0.043350261664164655,0.08409465974115259,0.011835075867696825,-0.07649325877138549,0.056390431528842634,-0.006146592255424093,0.7598307604134638,-1.874386020302522,0.010787275493423558,-0.037637976735281686,-0.1076162340082803,-0.012765744158430844,0.043350261664164655,0.08409465974115259,0.011835075867696825,-0.07649325877138549,0.056390431528842634,-0.006146592255424093,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.5833425,0.0,1.0,1.0,1.0,1.4337402993439705,1.301527102386724,0.5262084650184299,0.12102859217826763,0.002524831527132327,0.018234662538254117,-0.9924783132054938,0.2959366229173528,0.3223143249896514,0.02677034176720122,-0.016999236223886757,0.007076513600474715,0.6588959910590589,0.7003947988208148,-1.6685487153479561,-0.2695407363837699,-0.040072109309831495,-0.11057181749834785,-0.003456426677451431,0.04433137420432705,0.09625655108882575,0.0027534015606963703,-0.08356416643318595,0.06439814202820207,0.004904642406086917,0.7003947988208148,-1.6685487153479561,-0.2695407363837699,-0.040072109309831495,-0.11057181749834785,-0.003456426677451431,0.04433137420432705,0.09625655108882575,0.0027534015606963703,-0.08356416643318595,0.06439814202820207,0.004904642406086917,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6000092,0.0,1.0,1.0,1.0,1.4301218181541673,1.2946585218026323,0.5265168268698572,0.12680878481170887,0.0025856361625546534,0.018697296820608347,-0.9917475775981581,0.3231865313757931,0.3510269747097964,0.039163290461012336,-0.13085774433191055,-0.03237361303390978,0.7293976888061787,0.6020281022785248,-1.5055336897442777,-0.47600879483458824,-0.0463934193233735,-0.11856557431851153,0.013446213949598714,0.04438932532468121,0.11274895823622787,-0.012830515660059752,-0.09676879729786395,0.0749835881981698,0.011881322427574666,0.6020281022785248,-1.5055336897442777,-0.47600879483458824,-0.0463934193233735,-0.11856557431851153,0.013446213949598714,0.04438932532468121,0.11274895823622787,-0.012830515660059752,-0.09676879729786395,0.0749835881981698,0.011881322427574666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6166759,0.0,1.0,1.0,1.0,1.4262577008055504,1.2874527943115042,0.5269803784816185,0.1331004039088552,0.0019340793084088896,0.020293496147830055,-0.9908928881723928,0.3552753582709879,0.3661824316979064,0.03627202693140768,-0.2640513020924422,-0.12392921913337387,0.806899346258823,0.5758769149433653,-1.4029092247347457,-0.5783312200135534,-0.055468355143984495,-0.1282280231310863,0.03983959673042193,0.04144719226524723,0.13103715660163678,-0.036531302355431595,-0.11405394832878094,0.0861648146343987,0.014755469929706388,0.5758769149433653,-1.4029092247347457,-0.5783312200135534,-0.055468355143984495,-0.1282280231310863,0.03983959673042193,0.04144719226524723,0.13103715660163678,-0.036531302355431595,-0.11405394832878094,0.0861648146343987,0.014755469929706388,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6333426,0.0,1.0,1.0,1.0,1.4219215082308143,1.279722848823068,0.5271309122316483,0.14018498477888242,0.000221937092418782,0.022750739893259868,-0.9898638919673658,0.3743538945653245,0.3904281990560361,0.023596422952214,-0.34584611673052706,-0.2079718964820606,0.929021156230661,0.6375858038623822,-1.2253611925770058,-0.7465786616725828,-0.06520806725379585,-0.14819720739599784,0.059432796102126983,0.04148628242464045,0.15343305546428646,-0.053776979229291984,-0.13650921106413214,0.09850671761553331,0.014090960293994913,0.6375858038623822,-1.2253611925770058,-0.7465786616725828,-0.06520806725379585,-0.14819720739599784,0.059432796102126983,0.04148628242464045,0.15343305546428646,-0.053776979229291984,-0.13650921106413214,0.09850671761553331,0.014090960293994913,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6500093,0.0,1.0,1.0,1.0,1.417886301000126,1.2714649963575158,0.5270956770846871,0.1485061301884326,-0.0019517893763660156,0.025508366826931403,-0.9885805192479312,0.34033726946675064,0.4185121456497291,0.027970523754211316,-0.4544359517118284,-0.24284538707419004,1.0270342896764062,0.5172482626240714,-0.7553985477953148,-0.9732338847438491,-0.07078849132132164,-0.1624606088184478,0.07459639391163816,0.040930916239541426,0.17440401852591422,-0.06744013537822066,-0.15423413926677026,0.10936455341238016,0.022566996848514334,0.5172482626240714,-0.7553985477953148,-0.9732338847438491,-0.07078849132132164,-0.1624606088184478,0.07459639391163816,0.040930916239541426,0.17440401852591422,-0.06744013537822066,-0.15423413926677026,0.10936455341238016,0.022566996848514334,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.666676,0.0,1.0,1.0,1.0,1.415182791630725,1.263027279595437,0.5273082078909238,0.1571915964309763,-0.004478088773117183,0.029668070389962515,-0.9871122298562396,0.302566442812399,0.45941400172310864,0.06075682817676812,-0.6767712968196078,-0.26421894968535076,1.110135489316617,0.23327062770970652,-0.16693521062668198,-1.1420958400402388,-0.07548078882018032,-0.16975423075285417,0.09904933810843078,0.03690463765324675,0.19996442367145087,-0.08977529854006192,-0.17138593601601856,0.12280491597936923,0.045237031860124254,0.23327062770970652,-0.16693521062668198,-1.1420958400402388,-0.07548078882018032,-0.16975423075285417,0.09904933810843078,0.03690463765324675,0.19996442367145087,-0.08977529854006192,-0.17138593601601856,0.12280491597936923,0.045237031860124254,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.6833427,0.0,1.0,1.0,1.0,1.4130846389223537,1.2536865900618084,0.5281938444727909,0.16684288870182096,-0.007537845715609259,0.03603012358579214,-0.9852961288698906,0.36711996605416,0.5317285406044465,0.07422392070272531,-0.8973570952746914,-0.283750325045995,1.2812282196500786,0.06776316736820207,0.21436692728477977,-0.9937990203252217,-0.08288144868018926,-0.19350541056797124,0.1213456589959318,0.036014800493474795,0.23938360773093123,-0.1096433585966216,-0.2007660537579859,0.14205007709762885,0.07009664607812753,0.06776316736820207,0.21436692728477977,-0.9937990203252217,-0.08288144868018926,-0.19350541056797124,0.1213456589959318,0.036014800493474795,0.23938360773093123,-0.1096433585966216,-0.2007660537579859,0.14205007709762885,0.07009664607812753,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7000094,1.0,1.0,1.0,1.0,1.4095123760782227,1.2421362667538598,0.5285072657547037,0.17828084816609524,-0.010865129230502703,0.04377756664534957,-0.9829452745715777,0.4757312481437623,0.5880400030204092,0.048165607823809284,-1.0332015216494257,-0.27582298979900344,1.4872042510594627,0.11766314611643969,0.104745583034222,-0.42951570324299315,-0.08744438152136479,-0.2273738760464246,0.12947571849478087,0.03736098804892813,0.2804524882547736,-0.11618841171963092,-0.23314703406481307,0.15836477768153723,0.09131732271051161,0.11766314611643969,0.104745583034222,-0.42951570324299315,-0.08744438152136479,-0.2273738760464246,0.12947571849478087,0.03736098804892813,0.2804524882547736,-0.11618841171963092,-0.23314703406481307,0.15836477768153723,0.09131732271051161,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7166761,1.0,1.0,1.0,1.0,1.4051492991914123,1.229701500286719,0.5281211520562996,0.19121129549529917,-0.014039206849458292,0.052411411162422795,-0.9800480524576389,0.5213949364013393,0.5741197280899989,0.061800561917957075,-1.2545496546248918,-0.17968830310661416,1.568859577786282,0.19516231835427203,-0.09143446649335564,-0.11720874049135188,-0.08322059479570555,-0.23444920465799568,0.13444235778456995,0.03274396441385677,0.30888208707480114,-0.11981437786019235,-0.30788205767257926,0.1464652238993801,0.2886598292335299,0.19516231835427203,-0.09143446649335564,-0.11720874049135188,-0.08322059479570555,-0.23444920465799568,0.13444235778456995,0.03274396441385677,0.30888208707480114,-0.11981437786019235,-0.30788205767257926,0.1464652238993801,0.2886598292335299,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7333428,1.0,1.0,1.0,0.0,1.400652593112338,1.2177634451231074,0.5286163166212144,0.20374843074136606,-0.0164702842471517,0.06407052221953448,-0.9767856852399941,0.5232115626520157,0.5398975799493311,0.14138963085288908,-1.2696012832336812,-0.017736595842183234,1.5820403468974653,0.20506355694251804,-0.07805543046556893,-0.14702527588527406,-0.07026169021309066,-0.23424905338572244,0.10661262771306282,0.03327518583073252,0.31569521481707696,-0.09461009908412556,-0.41343015628671254,0.08859508675244779,0.5008073524594893,0.20506355694251804,-0.07805543046556893,-0.14702527588527406,-0.07026169021309066,-0.23424905338572244,0.10661262771306282,0.03327518583073252,0.31569521481707696,-0.09461009908412556,-0.41343015628671254,0.08859508675244779,0.5008073524594893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7500095,1.0,1.0,1.0,0.0,1.396566399409987,1.2058098148961771,0.5305253579203949,0.21662269472111745,-0.016916878320493083,0.07348118774492474,-0.9733390685713004,0.5336360094557191,0.49277400804598726,0.21963731388427166,-1.1492322968758386,0.06633979228176301,1.5799770317643602,0.2123378722002846,-0.07365440207237385,-0.15017061274732818,-0.05890030149135102,-0.2388445054316965,0.07737747241706908,0.03228670860823397,0.31143716667133436,-0.06728526563616066,-0.49162952988413555,0.03887375849208652,0.5742866896647835,0.2123378722002846,-0.07365440207237385,-0.15017061274732818,-0.05890030149135102,-0.2388445054316965,0.07737747241706908,0.03228670860823397,0.31143716667133436,-0.06728526563616066,-0.49162952988413555,0.03887375849208652,0.5742866896647835,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7666762,1.0,1.0,1.0,0.0,1.3919043061401488,1.1945176794612744,0.5334038159737433,0.2289753650607157,-0.017619617596287045,0.08339428350108176,-0.9696933663537222,0.5690127678851444,0.4541003845219789,0.23342007874871268,-0.9159637746938973,-0.01469945607246581,1.6167116079293335,0.22421374962060125,-0.0862234728040201,-0.12097386359994376,-0.27566124933170244,-0.477673775804513,0.21611049977653118,0.028056223855768316,0.30457426484862243,-0.04943990375390189,-0.6199345946146687,-0.06966989245374902,0.6325176103733208,0.22421374962060125,-0.0862234728040201,-0.12097386359994376,-0.27566124933170244,-0.477673775804513,0.21611049977653118,0.028056223855768316,0.30457426484862243,-0.04943990375390189,-0.6199345946146687,-0.06966989245374902,0.6325176103733208,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.7833429,1.0,0.0,1.0,0.0,1.3868402549945118,1.1827967468952025,0.5355465015116779,0.24250976975235622,-0.018332341074931684,0.08870502443113137,-0.9659111529980612,0.6159691791059745,0.4426913618035765,0.16521839525292417,-0.49585671977348467,-0.13116585205010534,1.6959659095457806,0.2478399692724017,-0.11619078434039506,-0.06949408040069012,-0.7243352966802642,-1.0721617372614365,0.29140468457922836,0.02876498062988462,0.29221214248138017,-0.02105462552960738,-0.7576349588765059,-0.2669623587588202,0.6601113890469115,0.2478399692724017,-0.11619078434039506,-0.06949408040069012,-0.7243352966802642,-1.0721617372614365,0.29140468457922836,0.02876498062988462,0.29221214248138017,-0.02105462552960738,-0.7576349588765059,-0.2669623587588202,0.6601113890469115,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8000096,1.0,0.0,1.0,0.0,1.3810979733516247,1.1711485082949804,0.5360046085702919,0.25632376247592403,-0.019189436147602774,0.09136335778825604,-0.9620720509318303,0.6670558172921617,0.42690085412096335,0.08457192540461042,-0.24484321670513748,-0.188439469874354,1.6513704684624968,0.2501195660922641,-0.12338003437425002,-0.03835294757796296,-1.0111376693803094,-1.862518123206067,0.14118212031336255,0.024681562657484165,0.2707117704832546,-0.005163031329306746,-0.9253176327169329,-0.6040248783947412,0.5676450359537878,0.2501195660922641,-0.12338003437425002,-0.03835294757796296,-1.0111376693803094,-1.862518123206067,0.14118212031336255,0.024681562657484165,0.2707117704832546,-0.005163031329306746,-0.9253176327169329,-0.6040248783947412,0.5676450359537878,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8166763,1.0,0.0,1.0,0.0,1.3747477345921943,1.1591618157315215,0.5354544150221124,0.2692017325287604,-0.01986439544786053,0.09235724095790204,-0.9584393423893078,0.7115422352832995,0.4105004422226348,0.0487985494324978,-0.029893549540593752,-0.16296489112742885,1.4763007584263865,0.233120289071306,-0.11531341378352329,-0.01855974237483289,-0.821716348935002,-2.572208663129351,0.10031258777669119,0.022732673139960954,0.23136808594632158,0.013503447347849388,-1.069746426652985,-1.0111382413002128,0.40207774182752143,0.233120289071306,-0.11531341378352329,-0.01855974237483289,-0.821716348935002,-2.572208663129351,0.10031258777669119,0.022732673139960954,0.23136808594632158,0.013503447347849388,-1.069746426652985,-1.0111382413002128,0.40207774182752143,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.833343,1.0,0.0,1.0,0.0,1.3679898606418623,1.1470850274195437,0.5347571154242443,0.2801534750379193,-0.01963357281660009,0.0916114961943198,-0.955372119651642,0.733919508585265,0.402739651435013,0.06351561751776758,0.35451694628193375,-0.07195899942958076,1.3452216509650357,0.23111144809238637,-0.11808545090618564,0.0064893456500688005,-0.5176816226301783,-3.0294433558212495,0.21340008174125963,0.03349820048306497,0.18969895047596155,0.055714696214308974,-1.1562604380185426,-1.2486926080876073,0.2163318256517574,0.23111144809238637,-0.11808545090618564,0.0064893456500688005,-0.5176816226301783,-3.0294433558212495,0.21340008174125963,0.03349820048306497,0.18969895047596155,0.055714696214308974,-1.1562604380185426,-1.2486926080876073,0.2163318256517574,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8500097,1.0,0.0,1.0,0.0,1.3614687931396303,1.1345388128872007,0.5346988244349465,0.2908444783561188,-0.01725463543778311,0.08684017761704334,-0.9526649728614497,0.7346861754196243,0.36389902685323294,0.09712942095814447,0.6248292023434131,0.04549198437987009,1.1369310378277457,0.21207323557360228,-0.10942926318378836,0.020994729534043532,-0.47133838837868913,-3.34664494822449,0.42688683654653203,0.04226671506759051,0.14325512544628458,0.088500293239877,-1.3014516695022433,-1.3830193984142503,-0.047167650043223916,0.21207323557360228,-0.10942926318378836,0.020994729534043532,-0.47133838837868913,-3.34664494822449,0.42688683654653203,0.04226671506759051,0.14325512544628458,0.088500293239877,-1.3014516695022433,-1.3830193984142503,-0.047167650043223916,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8666764,1.0,0.0,1.0,0.0,1.3546135562017383,1.1230425355686569,0.535383292192059,0.29833078141250596,-0.014223811632078743,0.08225587154619558,-0.9508051323171507,0.7522187441677948,0.3099913668053076,0.10157758108984767,0.6666191114528205,0.09247503903033419,0.9102656826505847,0.17885984048207473,-0.0909693486293119,0.026076807619652774,-0.6035039655936194,-3.6296649718746243,0.5195846754362851,0.0400733587587749,0.10688691440222536,0.09226201516404926,-1.4637385340913938,-1.5343242454668449,-0.21900875702642808,0.17885984048207473,-0.0909693486293119,0.026076807619652774,-0.6035039655936194,-3.6296649718746243,0.5195846754362851,0.0400733587587749,0.10688691440222536,0.09226201516404926,-1.4637385340913938,-1.5343242454668449,-0.21900875702642808,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.8833431,1.0,0.0,1.0,0.0,1.34696378864889,1.1114006196092963,0.5357811837092857,0.30529827306156737,-0.011218878424026933,0.07695360582012502,-0.9490759947358338,0.7988163166513211,0.2834420015389538,0.07884843647292206,0.6797024662059861,0.04415980046773629,0.8263947154804971,0.16469970769980816,-0.08632590676292339,0.03845304903102485,-0.8312997332053657,-3.8876757624418534,0.3924501470392112,0.03498738178214797,0.09346617567449747,0.08516013757228764,-1.5782704134832866,-1.6654055305853146,-0.3539233706402333,0.16469970769980816,-0.08632590676292339,0.03845304903102485,-0.8312997332053657,-3.8876757624418534,0.3924501470392112,0.03498738178214797,0.09346617567449747,0.08516013757228764,-1.5782704134832866,-1.6654055305853146,-0.3539233706402333,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9000098,1.0,0.0,1.0,0.0,1.338595034208458,1.099625154947089,0.5358508683957133,0.31147235359983017,-0.009004465445164717,0.07188113313677201,-0.9474898391244114,0.8147798360913225,0.2709105457178037,0.0657723310762071,0.7920344307009121,-0.039449040404863925,0.7335695762356409,0.15116118867882422,-0.08832671381204564,0.06491450223676172,-0.9760136101115066,-4.093615799348346,0.32960301279465226,0.032372850693243777,0.07287403497071498,0.0828477058942218,-1.6315525983047048,-1.7694575243480983,-0.4738583905539007,0.15116118867882422,-0.08832671381204564,0.06491450223676172,-0.9760136101115066,-4.093615799348346,0.32960301279465226,0.032372850693243777,0.07287403497071498,0.0828477058942218,-1.6315525983047048,-1.7694575243480983,-0.4738583905539007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9166764999999995,1.0,0.0,1.0,0.0,1.3305324680981152,1.0878638501724298,0.5359171634840398,0.3170395369071768,-0.0068323011785594405,0.06435204686995724,-0.9462019159576539,0.8053629829700022,0.2580068801024444,0.06466007996919815,0.9660151200906187,-0.13005991204123096,0.6242068139130805,0.1362504868507611,-0.09303639242250428,0.09851346358668227,-1.1173917137255238,-4.150366778670858,0.3179852635680077,0.03218050762228713,0.04623655948563196,0.08502616715367574,-1.6200488326038138,-1.8815542432482608,-0.5137376096455699,0.1362504868507611,-0.09303639242250428,0.09851346358668227,-1.1173917137255238,-4.150366778670858,0.3179852635680077,0.03218050762228713,0.04623655948563196,0.08502616715367574,-1.6200488326038138,-1.8815542432482608,-0.5137376096455699,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9333431999999995,1.0,0.0,1.0,0.0,1.3224168668083496,1.076441882335958,0.5361552465339252,0.3215596911841836,-0.005268966426210196,0.05603003403892642,-0.945215445432378,0.8088523143264863,0.24563418960406402,0.05116970922281805,1.037618076665228,-0.18823036528154183,0.533857404226619,0.12148425891363639,-0.09149334325370502,0.1176750595759676,-1.300841363600059,-3.9822113444401888,0.2777871723564758,0.030389655579303048,0.028824163933787637,0.08252840482190574,-1.5680363614155577,-1.9507693769708827,-0.5191366806423796,0.12148425891363639,-0.09149334325370502,0.1176750595759676,-1.300841363600059,-3.9822113444401888,0.2777871723564758,0.030389655579303048,0.028824163933787637,0.08252840482190574,-1.5680363614155577,-1.9507693769708827,-0.5191366806423796,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9500098999999995,1.0,0.0,1.0,0.0,1.3141987840222167,1.0648401746030354,0.5360140278246038,0.32571399080414065,-0.0037320755132738068,0.04704439676826982,-0.9442898350292209,0.8222090039001747,0.2236196255550648,0.03480005248127464,0.954303058386157,-0.22652750415588815,0.4098936764725326,0.09573970097595125,-0.0796443120105344,0.11905464050914877,-1.4167529384463915,-3.6126180738360323,0.054060519079777235,0.02459359948027575,0.013645486714446927,0.06796964959677416,-1.4874482485481342,-1.976245870439923,-0.48781243965255455,0.09573970097595125,-0.0796443120105344,0.11905464050914877,-1.4167529384463915,-3.6126180738360323,0.054060519079777235,0.02459359948027575,0.013645486714446927,0.06796964959677416,-1.4874482485481342,-1.976245870439923,-0.48781243965255455,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9666765999999996,1.0,0.0,1.0,0.0,1.305452148318163,1.0536335234211494,0.5359829521895091,0.3282473622033275,-0.0033248209739089214,0.03980577484980405,-0.9437468490334978,0.8169740855723864,0.24739148786762408,0.030935437584709204,0.9476763294784134,-0.30259166597448495,0.4750409400883129,0.10373075673049022,-0.08330378761510022,0.1314258090794341,-1.381300599600381,-3.0197840939918397,-0.35332180356758264,0.02024110593545363,0.024010315512158268,0.05812242742823437,-1.3877746444152554,-1.9315789245840764,-0.4484159278988794,0.10373075673049022,-0.08330378761510022,0.1314258090794341,-1.381300599600381,-3.0197840939918397,-0.35332180356758264,0.02024110593545363,0.024010315512158268,0.05812242742823437,-1.3877746444152554,-1.9315789245840764,-0.4484159278988794,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +4.9833433,1.0,0.0,1.0,0.0,1.2979756858999312,1.0414421990023666,0.5358635947934876,0.3334284640692103,-0.0030068277671470305,0.03050690505828443,-0.9422768951210632,0.7959502181892714,0.26929106071768627,0.01629375433538171,0.9838507319710091,-0.3001374686719568,0.5397116866676867,0.11610672397794282,-0.08579817815382611,0.13547335865240648,-1.1619816621462873,-2.524869786735277,-0.6383101871236265,0.021217950207693615,0.03382052192109301,0.06269585741059011,-1.2207404842390335,-1.7783702297413777,-0.4016713623496869,0.11610672397794282,-0.08579817815382611,0.13547335865240648,-1.1619816621462873,-2.524869786735277,-0.6383101871236265,0.021217950207693615,0.03382052192109301,0.06269585741059011,-1.2207404842390335,-1.7783702297413777,-0.4016713623496869,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.00001,1.0,0.0,1.0,0.0,1.2904731233579843,1.029963153638342,0.5356015775419999,0.3369358882990083,-0.0022886950396996345,0.022717479009999406,-0.9412507026284782,0.7930510713571932,0.24173287437262891,0.003857173546483228,0.8039123930181927,-0.22112743483934683,0.4389630324741039,0.09519117645623884,-0.06666043915017399,0.10889418387374632,-0.8948385380104268,-2.249658758056479,-0.41835893505974653,0.01771713433907713,0.028721696989336083,0.0537157989807947,-0.9558906894658713,-1.5405614740824534,-0.370931196401356,0.09519117645623884,-0.06666043915017399,0.10889418387374632,-0.8948385380104268,-2.249658758056479,-0.41835893505974653,0.01771713433907713,0.028721696989336083,0.0537157989807947,-0.9558906894658713,-1.5405614740824534,-0.370931196401356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0166767,1.0,0.0,1.0,0.0,1.282655593568828,1.018446911347427,0.5353442184450607,0.3404326019742088,-0.0018017138803794039,0.016670034197730135,-0.940119411192009,0.7956178085336296,0.25673830857074276,0.01775351701887872,0.9364944119402259,-0.2104696098200565,0.5433432482590862,0.11797009722002111,-0.07451323270606179,0.12161006797419635,-0.5498788470247116,-2.0520777478531094,-0.17666148938727355,0.02168887836065081,0.04127220115091047,0.06839740762263093,-0.6822448034085838,-1.2342473206606293,-0.31949754147867215,0.11797009722002111,-0.07451323270606179,0.12161006797419635,-0.5498788470247116,-2.0520777478531094,-0.17666148938727355,0.02168887836065081,0.04127220115091047,0.06839740762263093,-0.6822448034085838,-1.2342473206606293,-0.31949754147867215,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0333434,1.0,0.0,1.0,1.0,1.2755859473238862,1.0063984495588079,0.5357031261024214,0.34552769495589897,-0.0001184855057967762,0.006869148717332074,-0.9383834039322879,0.7902434203834318,0.2785634288294048,0.029564243583266245,1.1478255840015623,-0.2050512798278583,0.6961903650475113,0.15142215851392898,-0.08750556372400334,0.14368496700428607,-0.5179813742164778,-1.4375262391670651,-0.5952106848192104,0.027330236441019885,0.05831800016947771,0.08974450817755393,-0.31470426996932677,-0.5472807096907472,-0.20352728445132867,0.15142215851392898,-0.08750556372400334,0.14368496700428607,-0.5179813742164778,-1.4375262391670651,-0.5952106848192104,0.027330236441019885,0.05831800016947771,0.08974450817755393,-0.31470426996932677,-0.5472807096907472,-0.20352728445132867,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0500101,1.0,0.0,1.0,1.0,1.2686301593086673,0.9942850250913857,0.5360899510414252,0.35134792723773584,0.0016704857094227276,-0.0024615623768008215,-0.9362402385146167,0.7647972164871226,0.279163915799171,0.028590557793809968,1.2516050181598892,-0.19462491978000446,0.8087672031079134,0.17435067127523043,-0.09174237063809211,0.15574084905395758,-0.5882725444836758,-0.6646557974148319,-0.9496962159286336,0.028720893564410963,0.07471695998289979,0.10079397101211961,-0.09146571256464052,-0.033135416321155645,-0.14967681835943286,0.17435067127523043,-0.09174237063809211,0.15574084905395758,-0.5882725444836758,-0.6646557974148319,-0.9496962159286336,0.028720893564410963,0.07471695998289979,0.10079397101211961,-0.09146571256464052,-0.033135416321155645,-0.14967681835943286,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0666768,1.0,0.0,1.0,1.0,1.262504153200054,0.9826217455884438,0.5366742987119655,0.3580967640602608,0.004143143747985119,-0.013820157594817197,-0.9335729993811452,0.7717121062156043,0.2547904261363572,0.007127158819306348,1.1011328520414634,-0.1562603239464705,0.825265806079806,0.17342837814764236,-0.081509568575494,0.13807041116190866,-0.19205384313043244,-0.5127734271443161,-0.6905103680857205,-0.46392874235798803,-0.09953698292034999,0.2221800124453327,-0.09639144879386091,-0.028656740329815435,-0.13079694526869237,0.17342837814764236,-0.081509568575494,0.13807041116190866,-0.19205384313043244,-0.5127734271443161,-0.6905103680857205,-0.46392874235798803,-0.09953698292034999,0.2221800124453327,-0.09639144879386091,-0.028656740329815435,-0.13079694526869237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.0833435,1.0,0.0,0.0,1.0,1.2551779858730199,0.9707764844036463,0.5366273983941191,0.36409374189433086,0.005596582053518102,-0.02059000492410706,-0.9311178642255382,0.8450938168926997,0.23286036384277892,-0.042838720364340284,0.6969872671613916,-0.09311892109823727,0.8069965716947946,0.15973068296883083,-0.06057595090546156,0.08981178328807515,0.2100938649148424,-0.4505962407429412,-0.42110416593196986,-1.00981844195198,-0.32453919200150544,0.3856360859581274,-0.10472102123580641,-0.013277119351951076,-0.08366558125115751,0.15973068296883083,-0.06057595090546156,0.08981178328807515,0.2100938649148424,-0.4505962407429412,-0.42110416593196986,-1.00981844195198,-0.32453919200150544,0.3856360859581274,-0.10472102123580641,-0.013277119351951076,-0.08366558125115751,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1000102,1.0,0.0,0.0,1.0,1.247102076399444,0.9577688506699826,0.5357056654850294,0.37052669479351014,0.006633901455209468,-0.02528023906674512,-0.9284540211069193,0.8890258899221669,0.2507566287978993,-0.06920821029806944,0.39470238287094817,-0.03922024351163879,0.8646446436563464,0.1626969914336862,-0.048379955159709484,0.05245869805751179,0.3338227729353457,-0.24793955367213005,-0.24437732384500774,-1.0662584640313217,-0.4542878010067558,0.4869815325995924,-0.12301122139753058,0.00040265251130402476,-0.0483287441210638,0.1626969914336862,-0.048379955159709484,0.05245869805751179,0.3338227729353457,-0.24793955367213005,-0.24437732384500774,-1.0662584640313217,-0.4542878010067558,0.4869815325995924,-0.12301122139753058,0.00040265251130402476,-0.0483287441210638,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1166769,1.0,1.0,0.0,1.0,1.2395031283677629,0.9442274250091467,0.5349471910430358,0.3774156518068748,0.007040191106361487,-0.027040525675395805,-0.9256223157700856,0.9043627731314493,0.26164167799579885,-0.04878069207372304,-0.11259684380618984,0.01559185185091783,0.8724950764762481,0.15028781663910307,-0.02825302969867093,-0.007275207322558048,0.17015055651213623,-0.1573001105683339,-0.019198316381416114,-1.1270679192706363,-0.6781189437288061,0.5124929082711873,-0.14215378215607352,0.021505817069160778,0.007520110361435308,0.15028781663910307,-0.02825302969867093,-0.007275207322558048,0.17015055651213623,-0.1573001105683339,-0.019198316381416114,-1.1270679192706363,-0.6781189437288061,0.5124929082711873,-0.14215378215607352,0.021505817069160778,0.007520110361435308,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1333436,1.0,1.0,0.0,1.0,1.2316921886720316,0.9303982534629515,0.5347875177553909,0.38400505920387845,0.005734545082477541,-0.023560046918601644,-0.9230125425408455,0.9569965814570642,0.2559876379365765,-0.04573536836911152,-0.653544285583704,0.04104809344091137,0.8650286490165994,0.1322411242909269,-0.007403407872729224,-0.06739201276294357,0.0068613742249346455,-0.12534608896771957,0.0644763315911138,-1.316327147390066,-0.9689680696419546,0.43567890453397445,-0.16138550104729427,0.041841107409896446,0.06439956708532366,0.1322411242909269,-0.007403407872729224,-0.06739201276294357,0.0068613742249346455,-0.12534608896771957,0.0644763315911138,-1.316327147390066,-0.9689680696419546,0.43567890453397445,-0.16138550104729427,0.041841107409896446,0.06439956708532366,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1500103,1.0,1.0,0.0,1.0,1.2231034752766274,0.9155389501007698,0.534072679874365,0.3907935361580767,0.0031268079139656567,-0.01681525407793225,-0.9203194458445556,1.0035680118489316,0.24231937189674238,-0.05817320005709016,-0.9661333005103023,0.03402412033625647,0.8164486611629497,0.016195467590513244,-0.19854807085287401,-0.029996746702813482,-0.0050180732967739375,-0.10552456276571574,0.09472180971241333,-1.6085163127821858,-1.3537885487768915,0.32203278162843557,-0.16588798675096536,0.05012375220238597,0.09629031382888499,0.016195467590513244,-0.19854807085287401,-0.029996746702813482,-0.0050180732967739375,-0.10552456276571574,0.09472180971241333,-1.6085163127821858,-1.3537885487768915,0.32203278162843557,-0.16588798675096536,0.05012375220238597,0.09629031382888499,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.166677,0.0,1.0,0.0,1.0,1.2143040593316596,0.9006712384105238,0.5333664026525595,0.39658675565833124,-0.0002829429161014651,-0.00857051508188249,-0.9179571947813996,0.9953239173459464,0.23594132737166135,-0.0488148047418505,-1.0170432347240908,0.034133231836363534,0.6964862337114913,-0.1733687062475205,-0.5937382654408847,-0.0018237206609349737,-0.00937659889885931,-0.08353154246307071,0.0979861543593965,-1.8821420697824558,-1.7140914897646267,0.2875308737389678,-0.14816614596565592,0.0474390740815916,0.10410516163272782,-0.1733687062475205,-0.5937382654408847,-0.0018237206609349737,-0.00937659889885931,-0.08353154246307071,0.0979861543593965,-1.8821420697824558,-1.7140914897646267,0.2875308737389678,-0.14816614596565592,0.0474390740815916,0.10410516163272782,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.1833437,0.0,1.0,0.0,1.0,1.2060989006435263,0.8859669790000091,0.5328105121890385,0.4014525226363069,-0.0031763419222100597,-0.0010267275591415155,-0.9158737515353621,0.9704519978240034,0.24213306684637936,-0.0397659802305786,-0.9113378693922447,0.05275481213026389,0.6244074618678256,-0.4503190361599459,-1.1147608027713747,0.051151150386672145,-0.0057624307700005735,-0.07515154737814356,0.08359092391540977,-1.983134119622191,-1.9299608161972814,0.28718907785092884,-0.13140655108493182,0.040816517965853685,0.09809585247902779,-0.4503190361599459,-1.1147608027713747,0.051151150386672145,-0.0057624307700005735,-0.07515154737814356,0.08359092391540977,-1.983134119622191,-1.9299608161972814,0.28718907785092884,-0.13140655108493182,0.040816517965853685,0.09809585247902779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2000104,0.0,1.0,0.0,1.0,1.1983116795182522,0.8714082682839472,0.5322503710802255,0.40607260268734297,-0.005583526480318113,0.005728409550258491,-0.9138058059034181,0.9514786795519918,0.23094002275911368,-0.022399590984460954,-0.8097293245608784,0.09698592614650543,0.5766480226259209,-0.874617944347876,-1.9775760023259794,0.14679782997863772,-0.0012175267196455316,-0.06941916058481346,0.06611944530486726,-2.072219829990927,-2.1375825386765923,0.08952487472016937,-0.11788342677252844,0.03623388691641489,0.09492273299573975,-0.874617944347876,-1.9775760023259794,0.14679782997863772,-0.0012175267196455316,-0.06941916058481346,0.06611944530486726,-2.072219829990927,-2.1375825386765923,0.08952487472016937,-0.11788342677252844,0.03623388691641489,0.09492273299573975,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2166771,0.0,1.0,0.0,1.0,1.190545925674606,0.8572727765445834,0.5321245468693682,0.41014893218968324,-0.0071258127895355815,0.012018508114885088,-0.9119115262340112,0.9183212740126002,0.2173332604962949,0.011353927843067567,-0.7530888276613289,0.15725369930617303,0.5377389449533914,-1.1181010361678334,-2.6283792396618604,0.07704503190799261,0.002130829039058317,-0.06276999826849447,0.05074971776863445,-2.3073552224418092,-2.373573648949045,-0.2360693078535428,-0.10697913421953409,0.034170797905165216,0.09787552972957782,-1.1181010361678334,-2.6283792396618604,0.07704503190799261,0.002130829039058317,-0.06276999826849447,0.05074971776863445,-2.3073552224418092,-2.373573648949045,-0.2360693078535428,-0.10697913421953409,0.034170797905165216,0.09787552972957782,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2333438,0.0,1.0,0.0,1.0,1.1834293823335758,0.8436938815642374,0.5325235867890716,0.41412230683668694,-0.008234325789708561,0.01831479239931537,-0.9099997138672187,0.8699638169762466,0.21763614465543546,0.019349472335210283,-0.6608770666364027,0.15972191141151623,0.5336121218104185,-1.34118607153923,-2.9493297487534575,0.09814876236324561,0.0062446638897657595,-0.06530384545451337,0.04025247957869647,-2.4129613156530185,-2.606464134113523,-0.4426182452275277,-0.10259151040981826,0.029517026891820425,0.08983979033349576,-1.34118607153923,-2.9493297487534575,0.09814876236324561,0.0062446638897657595,-0.06530384545451337,0.04025247957869647,-2.4129613156530185,-2.606464134113523,-0.4426182452275277,-0.10259151040981826,0.029517026891820425,0.08983979033349576,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2500105,0.0,1.0,0.0,1.0,1.1769824902239394,0.8306290127063354,0.5324724218077945,0.4181058340568103,-0.0090956551951646,0.023218627931501166,-0.9080559872063001,0.8202108974836376,0.21546942869747557,0.022677095417586397,-0.545915202455597,0.09868842591554793,0.5396572576443387,-1.6805480857500632,-3.461204767800306,0.20945136470885892,0.009734078067742243,-0.07282697398009447,0.03697838771065804,-2.460002165325641,-2.756844142201364,-0.5048868613864068,-0.10154453578280775,0.0222832950945342,0.07135152614508686,-1.6805480857500632,-3.461204767800306,0.20945136470885892,0.009734078067742243,-0.07282697398009447,0.03697838771065804,-2.460002165325641,-2.756844142201364,-0.5048868613864068,-0.10154453578280775,0.0222832950945342,0.07135152614508686,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2666772,0.0,1.0,0.0,1.0,1.1711302466853204,0.8182324272567781,0.532841857519428,0.42217205643933386,-0.01033215021605938,0.027344773887169216,-0.9060442951504943,0.797902767931246,0.20866013088520965,0.018554201966659717,-0.4473580552255317,-0.012732146667277865,0.550357078913639,-1.849447705759217,-4.032827296461905,0.272654948839542,0.011634851268044494,-0.08270724861017252,0.04281913379811208,-2.5588361719346597,-2.780264174159028,-0.5164577765026797,-0.10387137833389704,0.01430068462057269,0.0481420819584017,-1.849447705759217,-4.032827296461905,0.272654948839542,0.011634851268044494,-0.08270724861017252,0.04281913379811208,-2.5588361719346597,-2.780264174159028,-0.5164577765026797,-0.10387137833389704,0.01430068462057269,0.0481420819584017,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.2833439,0.0,1.0,0.0,1.0,1.1652148807079588,0.8057761658738307,0.5325684042991797,0.42635087884696604,-0.012177536237456326,0.02997671598750386,-0.9039789998756662,0.7884934626102512,0.19759283559329327,-0.0001936082548592219,-0.380717853026957,-0.14335325095468504,0.6017184448310565,-1.8546287548399036,-4.268522476254706,0.39183125534802277,0.014356252506090988,-0.09946884347102497,0.05456469450813446,-2.557207427335896,-2.7258716654734663,-0.521036955825363,-0.11461575980005717,0.006787027854453014,0.026110668395969892,-1.8546287548399036,-4.268522476254706,0.39183125534802277,0.014356252506090988,-0.09946884347102497,0.05456469450813446,-2.557207427335896,-2.7258716654734663,-0.521036955825363,-0.11461575980005717,0.006787027854453014,0.026110668395969892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3000106,0.0,1.0,0.0,1.0,1.1594819976691073,0.7937737094616464,0.5323168954993327,0.4312327702279206,-0.014892497665551748,0.032181512834544644,-0.9015435994041082,0.7660985817554159,0.18581075486936668,0.007991248646414675,-0.31944491948000975,-0.27192342131301345,0.6421343349131093,-1.6395959436534453,-4.127341754218783,0.527713530911047,0.016899578180275435,-0.11400792862964254,0.06671920582547597,-2.4702955286246255,-2.6064840479194844,-0.5182893230667475,-0.12388062815882303,-0.0005293907001752096,0.0048894173440652815,-1.6395959436534453,-4.127341754218783,0.527713530911047,0.016899578180275435,-0.11400792862964254,0.06671920582547597,-2.4702955286246255,-2.6064840479194844,-0.5182893230667475,-0.12388062815882303,-0.0005293907001752096,0.0048894173440652815,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3166773,0.0,1.0,0.0,1.0,1.1540117489102588,0.7820063158699584,0.5323721010150332,0.4360709065061377,-0.018207295079512655,0.03297822792263971,-0.8991235150900488,0.7376424531581824,0.17817736847192236,0.03427348386192778,-0.2246919283271831,-0.4187214560957708,0.567518978680299,-1.3050455263993004,-3.726130055279282,0.5538009076651174,0.01429174983882875,-0.11044745156496373,0.07967352650723546,-2.3424680172602863,-2.423986390485963,-0.5289829848906104,-0.11451978349303482,-0.009400455555757798,-0.02306987157662753,-1.3050455263993004,-3.726130055279282,0.5538009076651174,0.01429174983882875,-0.11044745156496373,0.07967352650723546,-2.3424680172602863,-2.423986390485963,-0.5289829848906104,-0.11451978349303482,-0.009400455555757798,-0.02306987157662753,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.333344,0.0,1.0,0.0,1.0,1.148981899399333,0.7707459185103398,0.533107426539758,0.4399042157883098,-0.022483215931931987,0.03266881859844768,-0.897168620842488,0.6847937438878839,0.1664289257692907,0.06893697029392497,-0.14316525226580243,-0.48358739087648706,0.4655094568084705,-0.9680979041724711,-3.1371783339331047,0.32941806891171105,0.01135997111371615,-0.09784754763916532,0.0823106158948593,-2.1358076346195856,-2.1502526740184584,-0.37248359550355464,-0.0981831236696266,-0.014743770096256043,-0.03975779380532491,-0.9680979041724711,-3.1371783339331047,0.32941806891171105,0.01135997111371615,-0.09784754763916532,0.0823106158948593,-2.1358076346195856,-2.1502526740184584,-0.37248359550355464,-0.0981831236696266,-0.014743770096256043,-0.03975779380532491,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3500106999999995,0.0,1.0,1.0,1.0,1.1445724541233813,0.7604770562101804,0.534492633871265,0.4432454694705318,-0.02623173893571809,0.03174791014279819,-0.8954537508257034,0.6220755203063061,0.14018269041236256,0.06648544903109024,-0.11452494460574478,-0.4723480415121836,0.34591563128848113,-0.722646410095343,-2.4766897450943204,-0.07018605753950466,0.006841915664566561,-0.07729838405877659,0.07923389689141314,-1.0166729378681665,-0.9782119803606725,-0.135058015619805,-0.07785740644889942,-0.01551500904898574,-0.04216501231978364,-0.722646410095343,-2.4766897450943204,-0.07018605753950466,0.006841915664566561,-0.07729838405877659,0.07923389689141314,-1.0166729378681665,-0.9782119803606725,-0.135058015619805,-0.07785740644889942,-0.01551500904898574,-0.04216501231978364,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3666773999999995,0.0,1.0,1.0,1.0,1.1402903613972073,0.7513492551077454,0.5353322993679822,0.4452674685504059,-0.030195185103884727,0.03103367854213545,-0.894350067391622,0.5793734531589512,0.1403556524666914,0.04395924578022285,-0.2418636759663132,-0.47519605145926125,0.2035059614232167,-0.5743052526522833,-1.788694362572746,-0.49551290126420455,-0.004704192388956101,-0.049244433191989026,0.09461926987247636,-0.03919757189739129,0.021820713288174816,-0.07969027916122738,-0.05959788333961704,-0.011945144475629907,-0.030522778345060373,-0.5743052526522833,-1.788694362572746,-0.49551290126420455,-0.004704192388956101,-0.049244433191989026,0.09461926987247636,-0.03919757189739129,0.021820713288174816,-0.07969027916122738,-0.05959788333961704,-0.011945144475629907,-0.030522778345060373,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.3833440999999995,0.0,1.0,1.0,1.0,1.1367901768109847,0.7422031356367392,0.5360762794391586,0.44639580039298804,-0.03500751844046414,0.03192322828368027,-0.893580533886058,0.5652966435414154,0.17181395465531776,0.03941214094961837,-0.5191907186133331,-0.45419482948054213,0.12410779616895976,-0.2763904088196924,-1.2273814722564698,-0.9555512947572581,-0.016681509424792018,-0.026826203449784654,0.1213175095945841,-0.0499441280600481,0.019277328540315993,-0.10373805603029453,-0.05498453391304217,-0.0032224115383743686,0.00040691513901608704,-0.2763904088196924,-1.2273814722564698,-0.9555512947572581,-0.016681509424792018,-0.026826203449784654,0.1213175095945841,-0.0499441280600481,0.019277328540315993,-0.10373805603029453,-0.05498453391304217,-0.0032224115383743686,0.00040691513901608704,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4000107999999996,0.0,1.0,1.0,1.0,1.133678892878469,0.7328074657018387,0.5367762623911994,0.44703926881566913,-0.04075982376340176,0.03545535191959992,-0.8928815413725304,0.5888023306906417,0.17632486700809225,0.028734395015839773,-0.8351633264514353,-0.34898049953114996,0.02367933225807442,0.36111032469724524,-0.8519461102779564,-1.115958630255106,-0.02904414174566286,0.0035665909829128667,0.1398634294153329,-0.058925867865508436,0.01832839444207962,-0.12095594408805045,-0.04388413584659119,0.009943347630646889,0.04515334408417289,0.36111032469724524,-0.8519461102779564,-1.115958630255106,-0.02904414174566286,0.0035665909829128667,0.1398634294153329,-0.058925867865508436,0.01832839444207962,-0.12095594408805045,-0.04388413584659119,0.009943347630646889,0.04515334408417289,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4166775,0.0,1.0,1.0,1.0,1.1298483440917513,0.7229389260456569,0.5372485952024422,0.4463667095237821,-0.04641614645838803,0.04175905937541713,-0.8926693021141399,0.6277247300372765,0.16788210435785794,0.02752804281201836,-0.9625442284629236,-0.18559005217236502,-0.047363015754072,0.12082084774960648,-0.1912608946926518,-0.47626367767431566,-0.0328535766980561,0.025882794353242256,0.12978872944451778,-0.0570732175141026,0.018411453470547075,-0.11275091610594867,-0.028347947798809274,0.01965136809472455,0.07782863006171177,0.12082084774960648,-0.1912608946926518,-0.47626367767431566,-0.0328535766980561,0.025882794353242256,0.12978872944451778,-0.0570732175141026,0.018411453470547075,-0.11275091610594867,-0.028347947798809274,0.01965136809472455,0.07782863006171177,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4333442,0.0,1.0,1.0,1.0,1.1257310244850014,0.7126745381088004,0.5379915245070075,0.44571218596588646,-0.05071456222389586,0.0483581502868645,-0.8924293640175578,0.6369791086500187,0.18250029569363654,0.05710073716748582,-0.8066825922477219,-0.06994703518215664,0.08920160325336803,-0.38087627500168914,0.28214587135573405,-0.09353489579643022,-0.017617266015292826,0.0031349316780084294,0.09419399049970945,-0.049977191751312704,0.03914410245969158,-0.08176713971116803,-0.03935056533856223,0.01840082842250944,0.07889944936663196,-0.38087627500168914,0.28214587135573405,-0.09353489579643022,-0.017617266015292826,0.0031349316780084294,0.09419399049970945,-0.049977191751312704,0.03914410245969158,-0.08176713971116803,-0.03935056533856223,0.01840082842250944,0.07889944936663196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4500109,1.0,1.0,1.0,1.0,1.122225036678651,0.7022273693419063,0.5393398332467192,0.44707087786622846,-0.053364055844382925,0.053322586226692156,-0.8913117353125418,0.6446069902869406,0.20097775864094214,0.08856366485120688,-0.6153133700489078,-0.03465216964956546,0.2546407838893665,-0.09584810007096978,0.1243240719730463,-0.15502609040038287,-0.0014754436637609406,-0.02888768669292995,0.06623065667635843,-0.04525699995364313,0.05965360373622384,-0.057188920301576227,-0.05803387348390654,0.012997198932016445,0.06690350456081319,-0.09584810007096978,0.1243240719730463,-0.15502609040038287,-0.0014754436637609406,-0.02888768669292995,0.06623065667635843,-0.04525699995364313,0.05965360373622384,-0.057188920301576227,-0.05803387348390654,0.012997198932016445,0.06690350456081319,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4666776,1.0,1.0,1.0,1.0,1.1186782530522974,0.6913051141350999,0.5409731590101156,0.4489801319828996,-0.05558363706440077,0.057469522462111663,-0.8899576138015158,0.6622071148454465,0.1953767936391706,0.09820944893124564,-0.3959232349541706,-0.021335674152267396,0.28093180040713345,0.02780721137362084,0.010792061428652154,-0.04058640791516119,0.006357448189746018,-0.03849258939583822,0.04027786079297375,-0.03404938808672697,0.05651108485594549,-0.03466314114959143,-0.17021678982370228,-0.07780169635218628,0.2211329857046831,0.02780721137362084,0.010792061428652154,-0.04058640791516119,0.006357448189746018,-0.03849258939583822,0.04027786079297375,-0.03404938808672697,0.05651108485594549,-0.03466314114959143,-0.17021678982370228,-0.07780169635218628,0.2211329857046831,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.4833443,1.0,1.0,1.0,0.0,1.114842862209974,0.680430918692916,0.5426251221644907,0.45089500911358654,-0.05636965483387961,0.05929942026634465,-0.8888192907033711,0.6698785020820432,0.1772646057561973,0.09855343413387452,-0.05225355051655817,-0.009830554470588459,0.31230948972020567,0.05251545557687535,-0.0007193917526654751,-0.012039493788551075,0.017459289567725026,-0.051782521680707586,0.0011899917066082925,-0.015926117205588893,0.04954165753035294,-0.001317845010474473,-0.2919716795767225,-0.21954014832260108,0.3769944748542291,0.05251545557687535,-0.0007193917526654751,-0.012039493788551075,0.017459289567725026,-0.051782521680707586,0.0011899917066082925,-0.015926117205588893,0.04954165753035294,-0.001317845010474473,-0.2919716795767225,-0.21954014832260108,0.3769944748542291,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.500011,1.0,1.0,1.0,0.0,1.1107716688526126,0.6696142741648036,0.5443344973326509,0.453566774449248,-0.055805985125398076,0.058466703181976276,-0.8875497269217762,0.6607599908540887,0.16823195637879773,0.09305078696491756,0.17194013053255564,-0.03377642258585148,0.3913873855016299,0.07896361309292899,-0.009933421415360473,0.009859174574347623,0.028209492988743486,-0.07168745048361501,-0.020483829255784822,-0.00809222813992177,0.05285407357248426,0.017252014227497406,-0.3321096189779732,-0.3116130809370587,0.38653439864716477,0.07896361309292899,-0.009933421415360473,0.009859174574347623,0.028209492988743486,-0.07168745048361501,-0.020483829255784822,-0.00809222813992177,0.05285407357248426,0.017252014227497406,-0.3321096189779732,-0.3116130809370587,0.38653439864716477,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5166777,1.0,1.0,1.0,0.0,1.1069670278868509,0.6591269718206637,0.5458341152767561,0.45687565430974103,-0.05518625965242782,0.05686428024578525,-0.8859941122133655,0.6417646502458201,0.1640973274159094,0.07323268265877586,0.18320458121940741,-0.04001339450127577,0.4687917781776927,0.09335698128345177,-0.01042006554452932,0.009935857666318378,0.03386000358617712,-0.08508755516768696,-0.02194880392386348,-0.011494053272050206,0.06404643713084228,0.018501188925121294,-0.3909916548949982,-0.3819601294974398,0.3897159037090181,0.09335698128345177,-0.01042006554452932,0.009935857666318378,0.03386000358617712,-0.08508755516768696,-0.02194880392386348,-0.011494053272050206,0.06404643713084228,0.018501188925121294,-0.3909916548949982,-0.3819601294974398,0.3897159037090181,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5333444,1.0,1.0,1.0,0.0,1.103199939551581,0.6488874618097402,0.5468983377860782,0.4606952043880873,-0.05456069565371117,0.055887441931027446,-0.8841151808322305,0.6191696490865053,0.14336222938192544,0.053463888692467265,0.11616911631940414,-0.011931963690519326,0.44663920397541607,0.08589881396493457,-0.006014949169448741,0.0003842722157551181,-0.10118190946889048,-0.24509552075129795,0.06413040811036072,-0.013428988448488445,0.06389227792388417,0.015422957528293467,-0.4558139041026161,-0.4781557728049667,0.32741478799205875,0.08589881396493457,-0.006014949169448741,0.0003842722157551181,-0.10118190946889048,-0.24509552075129795,0.06413040811036072,-0.013428988448488445,0.06389227792388417,0.015422957528293467,-0.4558139041026161,-0.4781557728049667,0.32741478799205875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5500111,1.0,0.0,1.0,0.0,1.0993391379965485,0.639381299444157,0.5478104036291618,0.4635759000385029,-0.054055680057701054,0.05546739909374478,-0.8826656988887507,0.5949769821937823,0.11965363494993946,0.017738145832467304,0.0591664038196202,0.01846309414154578,0.38897811319990927,0.0726797251072329,-0.0018393885777063966,-0.007699522555536781,-0.27932503978657536,-0.5162882361355513,0.17214667399504308,-0.013139247567179681,0.05801275922313573,0.013069946660818883,-0.5313383550006223,-0.6169635091244264,0.29761794193875263,0.0726797251072329,-0.0018393885777063966,-0.007699522555536781,-0.27932503978657536,-0.5162882361355513,0.17214667399504308,-0.013139247567179681,0.05801275922313573,0.013069946660818883,-0.5313383550006223,-0.6169635091244264,0.29761794193875263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5666778,1.0,0.0,1.0,0.0,1.0953343250190186,0.6302602987643242,0.5477647046876637,0.4664539293321925,-0.05347385457194996,0.055510365523932355,-0.8811809564483197,0.5748224314716535,0.10574990997641667,-0.025503834206027035,0.012389777834788522,0.06428104546960928,0.34036053247761083,0.06171457189634389,0.002458079835029912,-0.017485457404739745,-0.38236961625043697,-0.727156527327971,0.23112677829271397,-0.011761855925316329,0.05375859153103778,0.013684166724751408,-0.607827141739155,-0.840329842887363,0.31281056497694576,0.06171457189634389,0.002458079835029912,-0.017485457404739745,-0.38236961625043697,-0.727156527327971,0.23112677829271397,-0.011761855925316329,0.05375859153103778,0.013684166724751408,-0.607827141739155,-0.840329842887363,0.31281056497694576,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.5833445,1.0,0.0,1.0,0.0,1.0913786091725024,0.621587632826579,0.5472631336465672,0.4685273516115331,-0.052702303198613576,0.056089766180431,-0.8800900670722678,0.5414488005400332,0.09048320604237513,-0.04943287965881096,0.014298954919595415,0.11315183117312913,0.2614008282593845,0.04810262678334307,0.0051770946340050795,-0.022503976768006247,-0.5838676284017047,-0.9315452962849861,0.27094436660419063,-0.00600690961666221,0.043382475265592274,0.018728711207855214,-0.6623239507228372,-1.059801052203549,0.3065410032570629,0.04810262678334307,0.0051770946340050795,-0.022503976768006247,-0.5838676284017047,-0.9315452962849861,0.27094436660419063,-0.00600690961666221,0.043382475265592274,0.018728711207855214,-0.6623239507228372,-1.059801052203549,0.3065410032570629,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6000112,1.0,0.0,1.0,0.0,1.0875401902731414,0.6136776245199643,0.5464153922756411,0.47019484103805614,-0.051457811546635285,0.05641532555037636,-0.8792532150268619,0.5117706033831758,0.06375778422293334,-0.0664873923636313,0.06786291370303776,0.1378382769178198,0.17091373211820127,0.0351970942070799,0.004763273052211917,-0.018888561037326192,-0.7731356998574003,-1.1449254444749268,0.2539055073337573,0.0022064132867196415,0.028700034746865426,0.025354422681845384,-0.6733764753815736,-1.1888834821941108,0.29635648454209756,0.0351970942070799,0.004763273052211917,-0.018888561037326192,-0.7731356998574003,-1.1449254444749268,0.2539055073337573,0.0022064132867196415,0.028700034746865426,0.025354422681845384,-0.6733764753815736,-1.1888834821941108,0.29635648454209756,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6166779,1.0,0.0,1.0,0.0,1.0833796283374213,0.6063240743832559,0.545397675471615,0.4709605391255233,-0.04998948504302623,0.05632382561738314,-0.8789339273458228,0.487649258812687,0.04003119383420718,-0.08005654101639027,0.22780643136980422,0.17959500462380254,0.08607611721747511,0.029386822770465636,0.0015524649294255221,-0.0082299910542351,-0.8426213590004569,-1.3988144438857777,0.23455620046358505,0.016892417570013373,0.0119687623239668,0.04387917574943965,-0.671221036673961,-1.2654401638299095,0.259906583412723,0.029386822770465636,0.0015524649294255221,-0.0082299910542351,-0.8426213590004569,-1.3988144438857777,0.23455620046358505,0.016892417570013373,0.0119687623239668,0.04387917574943965,-0.671221036673961,-1.2654401638299095,0.259906583412723,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6333446,1.0,0.0,1.0,0.0,1.079298393669366,0.5995333807013004,0.5441481940290535,0.47147262592684247,-0.04695634357642808,0.054561204860963,-0.8789378474748373,0.46498712794166464,0.03530902779886909,-0.0696613696264779,0.45756832817604165,0.2188605933732826,0.023472222399166395,0.03131935854431657,-0.004161413264533242,0.008669449207213367,-0.8588404996243597,-1.644957019648118,0.23653629339324733,0.034065017520823374,-0.0037241435792515994,0.06898186751970721,-0.7259997773006537,-1.3422875783324184,0.13556743350256784,0.03131935854431657,-0.004161413264533242,0.008669449207213367,-0.8588404996243597,-1.644957019648118,0.23653629339324733,0.034065017520823374,-0.0037241435792515994,0.06898186751970721,-0.7259997773006537,-1.3422875783324184,0.13556743350256784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6500113,1.0,0.0,1.0,0.0,1.0754973741933274,0.5928719198203432,0.5434166547567093,0.4714578912190074,-0.043164467029656366,0.051361060511788216,-0.8793328875098877,0.44734133121450853,0.026125734417904695,-0.041588081590272434,0.4907587762731577,0.24858260404044102,0.008136982670090019,0.03077025555804071,-0.0038078518150907945,0.007963543091250714,-0.9541848197425447,-1.7961455272557065,0.290427243988136,0.03732334636345646,-0.005950780352021045,0.07568424470573876,-0.8184942756147942,-1.4113092483627776,-0.030531900234817215,0.03077025555804071,-0.0038078518150907945,0.007963543091250714,-0.9541848197425447,-1.7961455272557065,0.290427243988136,0.03732334636345646,-0.005950780352021045,0.07568424470573876,-0.8184942756147942,-1.4113092483627776,-0.030531900234817215,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.666678,1.0,0.0,1.0,0.0,1.0716171740082818,0.5866933339229279,0.5430701009744171,0.47173743272204144,-0.03945120288938092,0.04932674789599339,-0.8794738592484733,0.43658676897151394,0.004844172374578251,-0.0034909259482720865,0.48420181551806657,0.24669717298414906,0.038905218011762985,0.03564599763626367,-0.0036247882925998435,0.007283720860342101,-1.1198091387191134,-1.8511442367726156,0.33500637101467884,0.034748271352408586,-0.0011189621658235925,0.07561950097064168,-0.9187617986691081,-1.3878761479367008,-0.1789175352140049,0.03564599763626367,-0.0036247882925998435,0.007283720860342101,-1.1198091387191134,-1.8511442367726156,0.33500637101467884,0.034748271352408586,-0.0011189621658235925,0.07561950097064168,-0.9187617986691081,-1.3878761479367008,-0.1789175352140049,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.6833447,1.0,0.0,1.0,0.0,1.0675867220036153,0.5806567712586606,0.543613791992722,0.47213893502344256,-0.03570943720592653,0.04622828839849405,-0.8795866116995592,0.41670042643036287,-0.006097338913112149,0.020605146547304325,0.5716456149340753,0.15046847044701067,0.016161102363376048,0.03491788297623987,-0.01125980952109797,0.03056745333924961,-1.205194057904323,-1.745463931176604,0.3325242891196136,0.03582296389552127,-0.010847124568155769,0.07206087972029382,-0.9912535400043673,-1.3484135098321623,-0.3796320475007719,0.03491788297623987,-0.01125980952109797,0.03056745333924961,-1.205194057904323,-1.745463931176604,0.3325242891196136,0.03582296389552127,-0.010847124568155769,0.07206087972029382,-0.9912535400043673,-1.3484135098321623,-0.3796320475007719,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7000114,1.0,0.0,1.0,0.0,1.0638601481765888,0.5751898320852179,0.5440418620004861,0.47219283672765955,-0.0327331149785704,0.04214140847649547,-0.8798787244947469,0.3834321905723415,-0.00792978836636702,0.029102992888094988,0.47413068367505307,0.035340958485992405,-0.03534054133192094,0.018907218712952135,-0.01372376390580276,0.039834643621752854,-1.1687716097616725,-1.3368502493515766,0.1993702354839202,0.027960452687607915,-0.019527717532037903,0.04848242320451531,-1.0019165332298738,-1.2820124155557036,-0.5734552574720858,0.018907218712952135,-0.01372376390580276,0.039834643621752854,-1.1687716097616725,-1.3368502493515766,0.1993702354839202,0.027960452687607915,-0.019527717532037903,0.04848242320451531,-1.0019165332298738,-1.2820124155557036,-0.5734552574720858,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7166781,1.0,0.0,1.0,0.0,1.0604080912051805,0.5701046852286951,0.5448337047742555,0.47185621077006284,-0.03148328149916448,0.03953580475478376,-0.8802257889235887,0.3547160696270928,-0.021175555743867806,0.042610375083303655,0.23489727776029518,-0.05017399769673305,-0.11949997102629761,-0.0099829207519572,-0.010085900632484011,0.031629867948583135,-0.9808913509793292,-0.737955227168013,-0.09540640005493863,0.015867666517980432,-0.027651555536661782,0.01476730513777062,-1.0016110536233844,-1.1147088917799777,-0.6814649591499057,-0.0099829207519572,-0.010085900632484011,0.031629867948583135,-0.9808913509793292,-0.737955227168013,-0.09540640005493863,0.015867666517980432,-0.027651555536661782,0.01476730513777062,-1.0016110536233844,-1.1147088917799777,-0.6814649591499057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7333448,1.0,0.0,1.0,0.0,1.0568719692817938,0.5656712013568572,0.5457392367513763,0.4705952429587932,-0.031697516043625786,0.038240085892116346,-0.8809501010909654,0.3148829000241128,-0.030584739920666185,0.05985586578608105,0.1549499664126799,-0.16181302764523053,-0.1415010428638936,-0.019766130511249314,-0.012774022527099763,0.041261461547541914,-0.6718335309862212,-0.41216569312774975,-0.3813686838538066,0.008230391640933764,-0.0326419398587349,-0.00664188840688533,-0.861480359100664,-0.9416220378464563,-0.7353191159043615,-0.019766130511249314,-0.012774022527099763,0.041261461547541914,-0.6718335309862212,-0.41216569312774975,-0.3813686838538066,0.008230391640933764,-0.0326419398587349,-0.00664188840688533,-0.861480359100664,-0.9416220378464563,-0.7353191159043615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7500115,1.0,0.0,1.0,0.0,1.0539224072219353,0.5618665243333179,0.547126581155284,0.46996204538698505,-0.032736330924751963,0.03591813868824423,-0.8813477723614207,0.26496480464534516,-0.03874002899586726,0.07997319652590831,0.06361223001078331,-0.2857905452100432,-0.12892546136673813,-0.02406151709770457,-0.015554259921485099,0.0510666990481343,-0.4005412785092232,-0.4321463130199369,-0.5351595585934749,-0.0020819297041506247,-0.032704846342593276,-0.030159497532424598,-0.5406032267744628,-0.7879241521780376,-0.6572031938910615,-0.02406151709770457,-0.015554259921485099,0.0510666990481343,-0.4005412785092232,-0.4321463130199369,-0.5351595585934749,-0.0020819297041506247,-0.032704846342593276,-0.030159497532424598,-0.5406032267744628,-0.7879241521780376,-0.6572031938910615,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.766678199999999,1.0,0.0,1.0,0.0,1.0511372651718502,0.5589646867848129,0.5487253918566257,0.46890185009100765,-0.03547238608176782,0.03499759880305835,-0.8818434854807946,0.19082676828473516,-0.04784728188975901,0.06947778865878076,-0.06055290627942036,-0.3528587909311799,-0.16403882234868616,-0.03754842008249795,-0.01448645329958945,0.05016467931045885,-0.24112939311551562,-0.06378224976589018,-0.8079248867027677,-0.009744381084346268,-0.036826230904245624,-0.05027657619994359,-0.151984925184846,-0.2930988753437732,-0.2999646205825247,-0.03754842008249795,-0.01448645329958945,0.05016467931045885,-0.24112939311551562,-0.06378224976589018,-0.8079248867027677,-0.009744381084346268,-0.036826230904245624,-0.05027657619994359,-0.151984925184846,-0.2930988753437732,-0.2999646205825247,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.7833448999999995,1.0,0.0,1.0,0.0,1.0492805150201259,0.5574140411093069,0.5497716944809092,0.4677206771393143,-0.0384913285244056,0.033953466882835105,-0.8823848071512812,0.11004550880153786,-0.053468418366489384,0.02201491323980525,0.1174135788118891,-0.3412836018741415,-0.18760512706863552,-0.03214934309484071,-0.019089075484297842,0.0659084170178049,-0.21340340008221134,0.5276116783080352,-0.8706778297330117,0.0008197457582773942,-0.045602781760057526,-0.032002082691352435,0.14429808933723304,0.24401229423386966,-0.016716779596841543,-0.03214934309484071,-0.019089075484297842,0.0659084170178049,-0.21340340008221134,0.5276116783080352,-0.8706778297330117,0.0008197457582773942,-0.045602781760057526,-0.032002082691352435,0.14429808933723304,0.24401229423386966,-0.016716779596841543,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8000115999999995,1.0,0.0,1.0,0.0,1.0476915523759203,0.5569081352125638,0.5497589923876549,0.46641855544501387,-0.03968518706990687,0.030487015297404878,-0.8831474163253091,0.08669774665398015,-0.07606670959089935,-0.033234435568007266,0.3368861313146422,-0.25429297899345915,-0.20755603273456913,-0.023229051734387503,-0.021380358397194273,0.07402824276460539,-0.014755172640698032,0.2327351401077764,-0.34588258521796783,0.016568993269817905,-0.05211766546790951,-0.00042833892626680084,0.20308149864441,0.295660668265648,-0.06920446637143297,-0.023229051734387503,-0.021380358397194273,0.07402824276460539,-0.014755172640698032,0.2327351401077764,-0.34588258521796783,0.016568993269817905,-0.05211766546790951,-0.00042833892626680084,0.20308149864441,0.295660668265648,-0.06920446637143297,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8166782999999995,1.0,0.0,1.0,1.0,1.0454651720760397,0.5564725170600773,0.5490202140645964,0.46502140758169613,-0.03972070795255195,0.026878841177171302,-0.8839993686352149,0.09473904758341128,-0.09870586953386444,-0.03178267203356097,0.46178183071566764,-0.14165251573924187,-0.22225188776857985,-0.018099318575741923,-0.019583316207700006,0.06922302661187403,0.2206311190546448,-0.0665589983128978,-0.024731512208002553,0.028048521764260242,-0.0535462481785894,0.025486630149870494,0.11550242986303023,0.10036610466924763,-0.10848558896871116,-0.018099318575741923,-0.019583316207700006,0.06922302661187403,0.2206311190546448,-0.0665589983128978,-0.024731512208002553,0.028048521764260242,-0.0535462481785894,0.025486630149870494,0.11550242986303023,0.10036610466924763,-0.10848558896871116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.833345,1.0,1.0,1.0,1.0,1.043110413126121,0.5561787178907962,0.5491251722561378,0.4635157651045527,-0.03829341770188157,0.022435932924499326,-0.8849764847576786,0.10616601378632942,-0.10223703980456263,-0.008124100925647235,0.5682618645341732,-0.040271188560197,-0.24719026265580932,-0.01604429709498127,-0.01781726366446601,0.06443687880679799,0.11166148093059651,0.06471227510490761,-0.05109430033615938,0.03830866674866216,-0.05625574996292479,0.048408684524811695,0.05633357591083788,-0.015166920259687609,-0.06712249461814068,-0.01604429709498127,-0.01781726366446601,0.06443687880679799,0.11166148093059651,0.06471227510490761,-0.05109430033615938,0.03830866674866216,-0.05625574996292479,0.048408684524811695,0.05633357591083788,-0.015166920259687609,-0.06712249461814068,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8500117,1.0,1.0,1.0,1.0,1.0406433260027292,0.5555044008632304,0.5491730367395838,0.46175569890193213,-0.03601573805735092,0.018027205934510983,-0.8860922982342003,0.11156194582721449,-0.0926106003799658,0.005750736412404633,0.5980925598910527,0.048062073653841186,-0.2581562415905579,-0.015583252670249995,-0.014526779575764056,0.05408046723416734,0.004280654487718769,0.02762707979378331,-0.06758512658906383,0.043153067246121085,-0.054958484697151276,0.06258490134936416,0.06301697440405654,-0.012804625327585594,-0.05908069247387033,-0.015583252670249995,-0.014526779575764056,0.05408046723416734,0.004280654487718769,0.02762707979378331,-0.06758512658906383,0.043153067246121085,-0.054958484697151276,0.06258490134936416,0.06301697440405654,-0.012804625327585594,-0.05908069247387033,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8666784,1.0,1.0,1.0,1.0,1.038480399131101,0.5548996345658332,0.5496929856846672,0.46005055148761514,-0.033058182562323304,0.013816548875192614,-0.8871695157177103,0.09716004551578719,-0.07749353565624875,0.018449526680960334,0.5905094107255425,0.06671424870122793,-0.21314805892753433,-0.0081453918652613,-0.013394726025111322,0.04991086291617214,0.007865704683595185,0.020775987419742535,-0.06984944583137277,0.04083175500612474,-0.04693369521805999,0.06481862683744792,0.0568428515549679,-0.012762981773194479,-0.054941681910092,-0.0081453918652613,-0.013394726025111322,0.04991086291617214,0.007865704683595185,0.020775987419742535,-0.06984944583137277,0.04083175500612474,-0.04693369521805999,0.06481862683744792,0.0568428515549679,-0.012762981773194479,-0.054941681910092,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.8833451,1.0,1.0,1.0,1.0,1.036720322801027,0.5543501069548213,0.5500771366590744,0.4589137880804628,-0.030553364633108936,0.009688941273478455,-0.887902444774332,0.0775635219235012,-0.08104685376964516,0.011824638020890564,0.41275918801302103,0.03221987059232824,-0.21272577747444196,-0.017630834755574993,-0.00942357820581683,0.03764845955627886,0.0015329594614252166,0.024476912207091386,-0.04664881936061716,0.030377575999565053,-0.043083053703113675,0.04389322572607434,0.04954137021653862,-0.009182563290190465,-0.040404053190820015,-0.017630834755574993,-0.00942357820581683,0.03764845955627886,0.0015329594614252166,0.024476912207091386,-0.04664881936061716,0.030377575999565053,-0.043083053703113675,0.04389322572607434,0.04954137021653862,-0.009182563290190465,-0.040404053190820015,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9000118,1.0,1.0,1.0,1.0,1.0348136454128571,0.554358530178668,0.5503258594585592,0.45711129285602065,-0.029452972466940626,0.007850246655525967,-0.8888870355584034,0.06285051714878863,-0.09161712965422154,0.011046377519748553,0.29927462772192204,0.02929820242244595,-0.24346226774516855,-0.02889578481977984,-0.005970057735546578,0.02741191374013707,-0.004163934351539525,0.032825005932218494,-0.03453416479191654,0.025739747504448622,-0.04466383720639429,0.03268454097500748,0.05047159797265896,-0.005868773538629214,-0.02926153755705446,-0.02889578481977984,-0.005970057735546578,0.02741191374013707,-0.004163934351539525,0.032825005932218494,-0.03453416479191654,0.025739747504448622,-0.04466383720639429,0.03268454097500748,0.05047159797265896,-0.005868773538629214,-0.02926153755705446,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9166785,1.0,1.0,1.0,1.0,1.0330460518022275,0.5544287150082821,0.5506641785212225,0.4554493453963133,-0.027872713799617886,0.005357780629391827,-0.8898091367199157,0.04672890682069368,-0.08627302474096464,0.01782844407895327,0.3310079360187858,0.02310658195047051,-0.22125031194597047,-0.02369605983346624,-0.007063187359067987,0.031103860525332906,-0.001503636530048295,0.027781637202004685,-0.03696954188646237,0.02577556484320488,-0.04241996311461157,0.03528396238351168,0.0479679881466095,-0.0075751385535389,-0.03278944002828193,-0.02369605983346624,-0.007063187359067987,0.031103860525332906,-0.001503636530048295,0.027781637202004685,-0.03696954188646237,0.02577556484320488,-0.04241996311461157,0.03528396238351168,0.0479679881466095,-0.0075751385535389,-0.03278944002828193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9333452,1.0,1.0,1.0,1.0,1.0316069932502323,0.5547875259084567,0.5510892792800246,0.45398186491497666,-0.02661775486078625,0.0030142278970204392,-0.8906081494600618,0.029615171933449088,-0.09146277935761762,0.020169603615322367,0.2702841812382573,0.014884323697382632,-0.22735294198587025,-0.027927308698838728,-0.005440228326826661,0.026317985364275175,-0.003996287442150133,0.03033270942220163,-0.02969051949757271,0.02260846370494786,-0.041980250831088695,0.028575441640482282,0.046539484961619804,-0.006207313082050411,-0.027433063221362276,-0.027927308698838728,-0.005440228326826661,0.026317985364275175,-0.003996287442150133,0.03033270942220163,-0.02969051949757271,0.02260846370494786,-0.041980250831088695,0.028575441640482282,0.046539484961619804,-0.006207313082050411,-0.027433063221362276,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9500119,1.0,1.0,1.0,1.0,1.0300360405978874,0.5554349387182602,0.5514696884904369,0.45219451847789216,-0.025616188976262895,0.001358449793479372,-0.8915503816022056,0.021840832292308064,-0.10544612008832972,0.013566582341669995,0.20132597331442695,-0.0044972073762289885,-0.2642830548832526,-0.03831697472956281,-0.0037650092665556167,0.022697920652323903,-0.009035882569543631,0.03802317095552075,-0.0198636421555292,0.01999601183661761,-0.04660617568754335,0.019631277892785046,0.04927710399664012,-0.0048179954654536585,-0.022930284915064728,-0.03831697472956281,-0.0037650092665556167,0.022697920652323903,-0.009035882569543631,0.03802317095552075,-0.0198636421555292,0.01999601183661761,-0.04660617568754335,0.019631277892785046,0.04927710399664012,-0.0048179954654536585,-0.022930284915064728,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9666786,1.0,1.0,1.0,1.0,1.0283650347017064,0.5562872615527632,0.5516632067467636,0.4501402546862211,-0.02517242558374128,-0.00012262129828820474,-0.8926029828906423,0.004047355732183398,-0.10757306818724005,0.004505937119573956,0.16780002756102472,-0.03484537277986903,-0.2722653949373509,-0.04206019644919177,-0.0036981138676731645,0.023995700936279653,-0.011257798042465485,0.039300170384512965,-0.011973317641192308,0.017451207430063106,-0.04826525274416215,0.012781922293969914,0.04825360583679605,-0.005266968491966023,-0.023187096283500384,-0.04206019644919177,-0.0036981138676731645,0.023995700936279653,-0.011257798042465485,0.039300170384512965,-0.011973317641192308,0.017451207430063106,-0.04826525274416215,0.012781922293969914,0.04825360583679605,-0.005266968491966023,-0.023187096283500384,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +5.9833453,1.0,1.0,1.0,1.0,1.0270811789791283,0.5574625930857914,0.5517062507055203,0.44821450278400277,-0.0248751498203313,-0.001513241769693422,-0.8935785900047358,-0.020604168011645226,-0.09859113229848131,-0.004880193862188645,0.1834556258189037,-0.04358393627349082,-0.2764960794749087,-0.0423893910967972,-0.004171260138994556,0.02682925976923798,-0.010939412731733,0.03918417512309969,-0.012351770117217754,0.01776063404854261,-0.04979045046677492,0.013433786297463186,0.049210612413596824,-0.006435015204669013,-0.025747243588997545,-0.0423893910967972,-0.004171260138994556,0.02682925976923798,-0.010939412731733,0.03918417512309969,-0.012351770117217754,0.01776063404854261,-0.04979045046677492,0.013433786297463186,0.049210612413596824,-0.006435015204669013,-0.025747243588997545,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.000012,1.0,1.0,1.0,1.0,1.0261352929975267,0.5587992160883964,0.5515336657495769,0.44609690093212906,-0.02444460965686749,-0.0032952601256003755,-0.8946447100934417,-0.031122409371824644,-0.08896058425025748,-0.0023667425451388705,0.22047253852172494,-0.02320440940526929,-0.29841459843241286,-0.04422272026864004,-0.00397984337280671,0.02746409878866093,-0.01015073744646605,0.042415677680923046,-0.01936326300456079,0.02075109169688723,-0.0533536238971807,0.01982453664982581,0.05482307451903791,-0.006958102843447612,-0.027002825143399245,-0.04422272026864004,-0.00397984337280671,0.02746409878866093,-0.01015073744646605,0.042415677680923046,-0.01936326300456079,0.02075109169688723,-0.0533536238971807,0.01982453664982581,0.05482307451903791,-0.006958102843447612,-0.027002825143399245,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0166787,1.0,1.0,1.0,1.0,1.025333823130767,0.5600733688456725,0.5516262183366303,0.4438538752081392,-0.02356532987774333,-0.00509575465965156,-0.8957747741340563,-0.021508985521236125,-0.08924336532411052,0.0069339788150597804,0.2853813831797343,-0.0011976520993514164,-0.32121398277528973,-0.04501528619209777,-0.004436546270984717,0.030585308945291892,-0.00825670523150097,0.04487808503242617,-0.029427722414111093,0.0249471802755644,-0.05777667864306295,0.029239868377498444,0.061705761236144546,-0.008462047339645397,-0.030773162981902875,-0.04501528619209777,-0.004436546270984717,0.030585308945291892,-0.00825670523150097,0.04487808503242617,-0.029427722414111093,0.0249471802755644,-0.05777667864306295,0.029239868377498444,0.061705761236144546,-0.008462047339645397,-0.030773162981902875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0333454,1.0,1.0,1.0,1.0,1.024211460348845,0.5611786396791341,0.5517660898334396,0.4414120322486825,-0.022325624751240926,-0.007691600542814568,-0.8969937700712557,-0.020195322446913872,-0.09817085786302025,0.007812858183202237,0.3790058186058623,0.0007966645782285162,-0.36119797294524153,-0.04818716144404996,-0.006128744112062346,0.0396223900099098,-0.006626170722596749,0.048460569706780844,-0.039477504717069,0.03017067446985009,-0.06651941668818652,0.039301957619775424,0.07173166519128998,-0.011930102869330012,-0.039797937107200046,-0.04818716144404996,-0.006128744112062346,0.0396223900099098,-0.006626170722596749,0.048460569706780844,-0.039477504717069,0.03017067446985009,-0.06651941668818652,0.039301957619775424,0.07173166519128998,-0.011930102869330012,-0.039797937107200046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0500121,1.0,1.0,1.0,1.0,1.0231601904742211,0.5626117208871297,0.551874166696372,0.4385937757820384,-0.02071932523586489,-0.010890845466079947,-0.8983805423605631,-0.04434642785954691,-0.09721647921327088,0.011360895563864663,0.4318010454619802,0.011365535161766527,-0.39013489979461335,-0.05105552942687184,-0.006402202712286642,0.04318161491539692,-0.005489155803465304,0.0517790265020537,-0.04673259663669336,0.03327692743232281,-0.07200465135549461,0.04644690565342192,0.07884330105571269,-0.013823422141144268,-0.043467305898665036,-0.05105552942687184,-0.006402202712286642,0.04318161491539692,-0.005489155803465304,0.0517790265020537,-0.04673259663669336,0.03327692743232281,-0.07200465135549461,0.04644690565342192,0.07884330105571269,-0.013823422141144268,-0.043467305898665036,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0666788,1.0,1.0,1.0,1.0,1.022574998854715,0.5643502234525555,0.5520707039084465,0.43572169962761276,-0.01892841708442189,-0.014209079551940047,-0.8997702026398682,-0.04906447005349488,-0.09523472739206358,0.0007776021468762636,0.3808473684066314,0.050690938271331226,-0.39864870940175795,-0.05384319248936936,-0.0030579472403974065,0.03180805556981594,-0.006159514263084968,0.05624665798378706,-0.0479772395001469,0.032080322262103604,-0.07013965884991415,0.046677436574853584,0.07976400048837468,-0.0108350536257147,-0.03310785849510925,-0.05384319248936936,-0.0030579472403974065,0.03180805556981594,-0.006159514263084968,0.05624665798378706,-0.0479772395001469,0.032080322262103604,-0.07013965884991415,0.046677436574853584,0.07976400048837468,-0.0108350536257147,-0.03310785849510925,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.0833455,1.0,1.0,1.0,1.0,1.0216832339829343,0.5658621509948264,0.5517952900516218,0.43275097931005196,-0.017095000097191247,-0.016359714436765264,-0.9012029242192989,-0.029288210592347506,-0.10065206445189967,-0.012628540700748645,0.2896945106338107,0.06914274721280755,-0.41569246914573577,-0.060411401816921416,0.0008025344224460547,0.019599258354123187,-0.009439417184455528,0.06303911462744198,-0.04200997016039167,0.028783453825874918,-0.06953905399668663,0.04020674806427234,0.07975543845831416,-0.007302473791682364,-0.021402480450245853,-0.060411401816921416,0.0008025344224460547,0.019599258354123187,-0.009439417184455528,0.06303911462744198,-0.04200997016039167,0.028783453825874918,-0.06953905399668663,0.04020674806427234,0.07975543845831416,-0.007302473791682364,-0.021402480450245853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1000122,1.0,1.0,1.0,1.0,1.0205592212298094,0.5671891713377486,0.5515570287887295,0.42957939436039444,-0.015685581467479105,-0.01817826593855385,-0.9027098410466406,-0.017161394654116063,-0.09870159460934472,-0.00858748616146613,0.29441300824440764,0.050327360288585386,-0.4269008691081365,-0.06290750061458902,0.0006803161839050887,0.022714392022003007,-0.009801143953411471,0.06410731052578787,-0.039850642621940595,0.028030378012255955,-0.07238166228226049,0.038744436349539675,0.08113673467342018,-0.008954667940364392,-0.023820598294403927,-0.06290750061458902,0.0006803161839050887,0.022714392022003007,-0.009801143953411471,0.06410731052578787,-0.039850642621940595,0.028030378012255955,-0.07238166228226049,0.038744436349539675,0.08113673467342018,-0.008954667940364392,-0.023820598294403927,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1166789,1.0,1.0,1.0,1.0,1.0194866834180372,0.5683658364504804,0.5514205962743324,0.4264194181947757,-0.014102523189775515,-0.02054109791858547,-0.904182316749454,-0.022412429081424975,-0.09147575833634056,0.0008276823444708183,0.31257778891735205,0.04747537720426766,-0.42970249269644234,-0.06283382434827493,0.000636821371057921,0.024648574424586414,-0.00869144131087214,0.06378802621786146,-0.04148532453207749,0.028092352596212376,-0.07352449463262117,0.04059824240274818,0.08223473563361516,-0.010373289785795986,-0.025535656553919057,-0.06283382434827493,0.000636821371057921,0.024648574424586414,-0.00869144131087214,0.06378802621786146,-0.04148532453207749,0.028092352596212376,-0.07352449463262117,0.04059824240274818,0.08223473563361516,-0.010373289785795986,-0.025535656553919057,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1333456,1.0,1.0,1.0,1.0,1.0186814678858136,0.5697039188102995,0.5514758523179091,0.42319402707865333,-0.012600524895496948,-0.022651929883052185,-0.9056682241802918,-0.017279931124467667,-0.08562173315933949,0.009929677044026766,0.2543879574548222,0.04726951689520168,-0.4214454686817186,-0.06376953503048047,0.0025671381780817217,0.01849088074801557,-0.00992942815240475,0.06452818026727598,-0.035860705643027985,0.02484941930505723,-0.07071958208396077,0.03491181985485086,0.07868952618312629,-0.008758539994759859,-0.019439766536194357,-0.06376953503048047,0.0025671381780817217,0.01849088074801557,-0.00992942815240475,0.06452818026727598,-0.035860705643027985,0.02484941930505723,-0.07071958208396077,0.03491181985485086,0.07868952618312629,-0.008758539994759859,-0.019439766536194357,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1500123,1.0,1.0,1.0,1.0,1.0176679906480492,0.570652996237768,0.5516402870985864,0.42013035998483356,-0.011433834550071477,-0.024135182521510038,-0.9070706924000738,0.006751525561244691,-0.08037114320259972,0.008558538785957272,0.14928964258656754,0.04779655644924477,-0.41478886939427373,-0.06670794942729655,0.00584322974665605,0.007497561755571112,-0.013096691035668743,0.06743906516630538,-0.0257201758628525,0.019947639306012312,-0.06683894896864244,0.024457855304554674,0.07355889769762347,-0.005243113549003098,-0.00875988231387227,-0.06670794942729655,0.00584322974665605,0.007497561755571112,-0.013096691035668743,0.06743906516630538,-0.0257201758628525,0.019947639306012312,-0.06683894896864244,0.024457855304554674,0.07355889769762347,-0.005243113549003098,-0.00875988231387227,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.166679,1.0,1.0,1.0,1.0,1.0164926739388227,0.5712779152969703,0.5516784004260227,0.41697192558344504,-0.010662339274528034,-0.024651799260205345,-0.9085224359308159,0.009920853564619175,-0.06040866525537156,-0.00017073609703723317,0.15394850085767914,0.011818380759624741,-0.37388692862368345,-0.06048975625931485,0.004128771517668497,0.013379623616689791,-0.011711336496192635,0.059108404889246964,-0.02035412490642015,0.01722691319980824,-0.062331854387843194,0.02025442718734472,0.06600533296292047,-0.007352221016254733,-0.013479321335766884,-0.06048975625931485,0.004128771517668497,0.013379623616689791,-0.011711336496192635,0.059108404889246964,-0.02035412490642015,0.01722691319980824,-0.062331854387843194,0.02025442718734472,0.06600533296292047,-0.007352221016254733,-0.013479321335766884,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.1833457,1.0,1.0,1.0,1.0,1.0159256741017788,0.5717132888682064,0.5515755170245578,0.4145005926824538,-0.010036264750780507,-0.026450705182589233,-0.9096091975409498,-0.004730577136362353,-0.03444752600114669,-0.003456376239325689,0.11513737609188102,-0.03999859688601207,-0.3021485644165272,-0.0508747244556262,0.00240665287582831,0.01719839840836705,-0.01117890186097281,0.046697144833863634,-0.008220257223167163,0.011644485533805721,-0.05239909209735976,0.009539099089322664,0.051340308128465774,-0.00810860013931111,-0.015879556542199892,-0.0508747244556262,0.00240665287582831,0.01719839840836705,-0.01117890186097281,0.046697144833863634,-0.008220257223167163,0.011644485533805721,-0.05239909209735976,0.009539099089322664,0.051340308128465774,-0.00810860013931111,-0.015879556542199892,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.200012399999999,1.0,1.0,1.0,1.0,1.0157300972126448,0.5721423169762818,0.5515113353876923,0.4123934431755712,-0.010336720403966505,-0.026721980572991393,-0.910555180091434,-0.01246630606674192,-0.025650560362519843,0.006400212373309901,-0.10495545885236537,-0.04266509672572145,-0.2816003059702445,-0.05570726568623741,0.008302090657926245,-0.004762649153026732,-0.01857911546358727,0.05175096718055594,0.013892783774448657,0.0023017818564912535,-0.04316074541295147,-0.013336093360153917,0.03942993207914806,0.0002881311096615677,0.005319339567324802,-0.05570726568623741,0.008302090657926245,-0.004762649153026732,-0.01857911546358727,0.05175096718055594,0.013892783774448657,0.0023017818564912535,-0.04316074541295147,-0.013336093360153917,0.03942993207914806,0.0002881311096615677,0.005319339567324802,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2166790999999995,1.0,1.0,1.0,1.0,1.015556497150281,0.5726003152312973,0.5517372078072161,0.41018859764520194,-0.011275516491710668,-0.025198185429233976,-0.9115828149656957,-0.009243944352166624,-0.017100308841913138,0.018199263040735665,-0.2586825553239855,-0.05287595229282417,-0.2871807493351184,-0.06290767718771505,0.012761371356950862,-0.018687661916525048,-0.024789653683755478,0.05851927678302033,0.03060251944915207,-0.0040553003772817375,-0.040118140301184456,-0.030263783554365393,0.0340627231266745,0.005639765124880018,0.01902639781131006,-0.06290767718771505,0.012761371356950862,-0.018687661916525048,-0.024789653683755478,0.05851927678302033,0.03060251944915207,-0.0040553003772817375,-0.040118140301184456,-0.030263783554365393,0.0340627231266745,0.005639765124880018,0.01902639781131006,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2333457999999995,1.0,1.0,1.0,1.0,1.015507789670166,0.5727835303510441,0.5520834361649113,0.4079592362165195,-0.01278681806829847,-0.023205848266268696,-0.9126156077317357,-0.012856816181772947,-0.010258224849007713,0.018938908815774737,-0.4029479847882619,-0.07468132966910744,-0.29749735766503144,-0.07109653604571464,0.016936440437954906,-0.029696673135516466,-0.03093777775654477,0.0653782897079092,0.04826469451721816,-0.010473112881236415,-0.03842864578283985,-0.04754071876876339,0.029685645407943453,0.010013203487112769,0.03042064888396624,-0.07109653604571464,0.016936440437954906,-0.029696673135516466,-0.03093777775654477,0.0653782897079092,0.04826469451721816,-0.010473112881236415,-0.03842864578283985,-0.04754071876876339,0.029685645407943453,0.010013203487112769,0.03042064888396624,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2500124999999995,1.0,1.0,1.0,1.0,1.0155902281864333,0.573180255959932,0.5523385872908367,0.405545463655671,-0.015032607558662885,-0.019638794495396048,-0.9137402340758898,-0.013103482500007995,-0.006826428960777598,0.010784734324609803,-0.5386688592951042,-0.0795006597921319,-0.2838854836762938,-0.07422670148541581,0.02089730479018656,-0.04219241684224539,-0.03487773935590012,0.06810592842448276,0.0629502723766109,-0.01678785821309337,-0.03224129312441395,-0.06204217551975653,0.02256110391644564,0.014967330509858942,0.04310051369909643,-0.07422670148541581,0.02089730479018656,-0.04219241684224539,-0.03487773935590012,0.06810592842448276,0.0629502723766109,-0.01678785821309337,-0.03224129312441395,-0.06204217551975653,0.02256110391644564,0.014967330509858942,0.04310051369909643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2666792,1.0,1.0,1.0,1.0,1.0156360761374774,0.5732767937457331,0.5524181394233258,0.40347433363651414,-0.017542893235305727,-0.015609358316905733,-0.914689595943039,0.005633461806053696,0.011711983896780874,0.007069093272636393,-0.5314620188746976,-0.0674450951305945,-0.2199301983229623,-0.06238327885934306,0.019859673306039195,-0.04281047736807101,-0.03075136508611849,0.05690115000465048,0.06140536449551297,-0.01818711437240261,-0.02151478018671503,-0.06030074160828905,0.013444799400848608,0.015526696511886262,0.043915100255303256,-0.06238327885934306,0.019859673306039195,-0.04281047736807101,-0.03075136508611849,0.05690115000465048,0.06140536449551297,-0.01818711437240261,-0.02151478018671503,-0.06030074160828905,0.013444799400848608,0.015526696511886262,0.043915100255303256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.2833459,1.0,1.0,1.0,1.0,1.0157566654230497,0.5727887173215971,0.5525879775267531,0.4020207825318236,-0.01957582077953867,-0.01205403894807455,-0.9153418912069664,0.01553406114572325,0.02449852420368408,0.01599401158606942,-0.45633575228861184,-0.05100837885706704,-0.17221770414708426,-0.050563913102168366,0.017184963559329976,-0.03739281307254693,-0.02494285953675272,0.04600453312331577,0.0522098666371558,-0.01618269267419872,-0.015250451037004129,-0.05103571804121765,0.00943836089123691,0.013569118526975003,0.03856696166848508,-0.050563913102168366,0.017184963559329976,-0.03739281307254693,-0.02494285953675272,0.04600453312331577,0.0522098666371558,-0.01618269267419872,-0.015250451037004129,-0.05103571804121765,0.00943836089123691,0.013569118526975003,0.03856696166848508,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3000126,1.0,1.0,1.0,1.0,1.015901379176975,0.572363688570551,0.5529794528159743,0.4006890670150681,-0.02134448689010895,-0.009045769443697218,-0.9159207708689457,0.0018651552873937454,0.028197336798957914,0.023188584503791482,-0.34144872888296424,-0.05790825674445382,-0.13609567638787237,-0.039805853742138374,0.012619783526874368,-0.024714347625700347,-0.019261738209165536,0.0349459521102438,0.04224619003360933,-0.01293190184760225,-0.01319474982047636,-0.04053528581902916,0.0076122136853672565,0.00913141876287476,0.02642525184027385,-0.039805853742138374,0.012619783526874368,-0.024714347625700347,-0.019261738209165536,0.0349459521102438,0.04224619003360933,-0.01293190184760225,-0.01319474982047636,-0.04053528581902916,0.0076122136853672565,0.00913141876287476,0.02642525184027385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3166793,1.0,1.0,1.0,1.0,1.016429390944494,0.5721311867989106,0.5533624802269069,0.39981563680247173,-0.0227199064402763,-0.007276554201910509,-0.9162850616366752,0.0008979724865737103,0.017943952234817023,0.014654139447383327,-0.31472113461974727,-0.0505554834354667,-0.1524022837888485,-0.04151266030975531,0.012705886845430054,-0.022795614850453762,-0.018492143936009713,0.03696512494369678,0.038621785438253786,-0.011413615329461394,-0.016162231784104347,-0.03689271361822786,0.011606901044307519,0.008097006314157388,0.024524686670473028,-0.04151266030975531,0.012705886845430054,-0.022795614850453762,-0.018492143936009713,0.03696512494369678,0.038621785438253786,-0.011413615329461394,-0.016162231784104347,-0.03689271361822786,0.011606901044307519,0.008097006314157388,0.024524686670473028,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.333346,1.0,1.0,1.0,1.0,1.0163369868133596,0.5719503118033881,0.5534658988863254,0.3982341815438293,-0.024195700881381406,-0.0046350622744695865,-0.916952900048136,0.011786977156311556,0.010756499658013218,0.0116505308855145,-0.24797481570644783,-0.031697235861808115,-0.1637955747612379,-0.040241174322507206,0.011641657918686758,-0.018812002327597645,-0.015986711653029388,0.03700646185429299,0.02915332014345718,-0.007796060944974685,-0.01921544537404335,-0.02793018807283794,0.01645840172452312,0.006149358561556217,0.020035134398220217,-0.040241174322507206,0.011641657918686758,-0.018812002327597645,-0.015986711653029388,0.03700646185429299,0.02915332014345718,-0.007796060944974685,-0.01921544537404335,-0.02793018807283794,0.01645840172452312,0.006149358561556217,0.020035134398220217,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3500127,1.0,1.0,1.0,1.0,1.0164393084677035,0.5716103058278077,0.5537653832174102,0.39721226967816115,-0.0248390859739789,-0.0037638545635698406,-0.9173828350388541,0.003923380682115256,0.019311806755295417,0.018565394270277893,-0.013603964076443504,-0.02643051266936847,-0.09234294253108664,-0.01770442743503229,0.002271687382783627,0.003287008386644421,-0.004989829815975311,0.01580462317486873,0.0051114922624896815,0.0004372995206494331,-0.015221050917182738,-0.00426642600236524,0.01315189713970308,-0.0016881151250992994,-0.0024419421265133184,-0.01770442743503229,0.002271687382783627,0.003287008386644421,-0.004989829815975311,0.01580462317486873,0.0051114922624896815,0.0004372995206494331,-0.015221050917182738,-0.00426642600236524,0.01315189713970308,-0.0016881151250992994,-0.0024419421265133184,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3666794,1.0,1.0,1.0,1.0,1.0167432535967245,0.5714309322273289,0.5540820595198107,0.39681565492183213,-0.024685450887882907,-0.004640717218232439,-0.9175545914369998,-0.008636827462595639,0.017207666376974406,0.015268890338409963,0.1259425815427047,-0.020571985793284894,-0.04493296970511116,-0.0033433416732432104,-0.0034082916933797724,0.015932125547436646,0.0017589312497014473,0.0024188227639013525,-0.009664134829006514,0.005387192842816333,-0.011994772170768508,0.010162370590302715,0.010489465765750999,-0.006167657713482386,-0.015433889786140447,-0.0033433416732432104,-0.0034082916933797724,0.015932125547436646,0.0017589312497014473,0.0024188227639013525,-0.009664134829006514,0.005387192842816333,-0.011994772170768508,0.010162370590302715,0.010489465765750999,-0.006167657713482386,-0.015433889786140447,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.3833461,1.0,1.0,1.0,1.0,1.0170751885563516,0.5714412632394403,0.5542532504612379,0.3965753418007429,-0.024317556516689993,-0.0058445031482641015,-0.9176614280352158,-0.003942752816830943,0.018194401293009956,0.003921679233747914,0.1255010493806959,0.0038459470453972486,-0.002642414798702636,0.004832395677030035,-0.003830081580772258,0.011919268197237182,0.0041824606834091616,-0.004192154792174492,-0.013175869564162054,0.005392287012912264,-0.004287048413153133,0.012946602273251319,0.004742352019284729,-0.0046491216245503715,-0.012148535488144586,0.004832395677030035,-0.003830081580772258,0.011919268197237182,0.0041824606834091616,-0.004192154792174492,-0.013175869564162054,0.005392287012912264,-0.004287048413153133,0.012946602273251319,0.004742352019284729,-0.0046491216245503715,-0.012148535488144586,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4000128,1.0,1.0,1.0,1.0,1.0172800087289153,0.5711148007404239,0.5542009520202408,0.39682698104893294,-0.02379737766887966,-0.006536068152515431,-0.9175616119589901,0.006607006653701579,0.027108484327928416,0.0017107880514119424,0.09348212684340579,0.02023217809854784,0.0605496630625328,0.015180612000956306,-0.004121480656975041,0.005878969338497355,0.0061809904316384645,-0.013516774708073758,-0.012205046165178986,0.0033060581973265598,0.00740273249042765,0.011515799240620997,-0.0056935633719979424,-0.0019925615606644067,-0.006568216263055342,0.015180612000956306,-0.004121480656975041,0.005878969338497355,0.0061809904316384645,-0.013516774708073758,-0.012205046165178986,0.0033060581973265598,0.00740273249042765,0.011515799240620997,-0.0056935633719979424,-0.0019925615606644067,-0.006568216263055342,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4166795,1.0,1.0,1.0,1.0,1.017585079371329,0.5706637602704716,0.5543147395937794,0.39754051008751556,-0.023396851274761397,-0.007116566418647507,-0.9172586792569442,0.005618508727530761,0.032082487644455183,0.009857117236732845,0.09445032054259975,-0.002603579401511686,0.13059462246873307,0.026977335866755877,-0.006914080904123073,0.00906891819003038,0.008453346650671401,-0.026565578872855884,-0.0085294288102095,0.0008397795115674643,0.017501342937104467,0.008539112174327831,-0.017684209704527006,-0.0021501550316383347,-0.00905923482591205,0.026977335866755877,-0.006914080904123073,0.00906891819003038,0.008453346650671401,-0.026565578872855884,-0.0085294288102095,0.0008397795115674643,0.017501342937104467,0.008539112174327831,-0.017684209704527006,-0.0021501550316383347,-0.00905923482591205,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4333462,1.0,1.0,1.0,1.0,1.0179446472750777,0.5702573880862236,0.5545322965457089,0.3988594366731713,-0.02322704362626699,-0.007946757706312143,-0.9166834258690953,0.001430572293290227,0.031219438504172532,0.00982066567779224,0.08190830106407834,-0.028363659760162776,0.159624457698223,0.030866913678890412,-0.008130657072208764,0.011595537690707659,0.008533469602620459,-0.03199695284864638,-0.0032055426453167332,-0.0013970794732880009,0.02142150219004023,0.0040124136524756744,-0.023730523549537967,-0.002444793586394052,-0.010788666683548718,0.030866913678890412,-0.008130657072208764,0.011595537690707659,0.008533469602620459,-0.03199695284864638,-0.0032055426453167332,-0.0013970794732880009,0.02142150219004023,0.0040124136524756744,-0.023730523549537967,-0.002444793586394052,-0.010788666683548718,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4500129,1.0,1.0,1.0,1.0,1.0183258477898196,0.5699303351990149,0.5546399138680725,0.4000072482012121,-0.02330709930833596,-0.008495058788069549,-0.9161761918345798,-0.005871525488898133,0.03773587939486026,0.012667655301798544,0.0344653951360114,-0.042419794422196254,0.1882102786534902,0.0335995942603661,-0.0077941939225567155,0.00886389320176323,0.007815342038923093,-0.035616781609409676,0.003847979701897563,-0.00464746753046617,0.02682992138116561,-0.0025867910013817096,-0.030431719751899185,-0.0009926663056740261,-0.0076027045012507085,0.0335995942603661,-0.0077941939225567155,0.00886389320176323,0.007815342038923093,-0.035616781609409676,0.003847979701897563,-0.00464746753046617,0.02682992138116561,-0.0025867910013817096,-0.030431719751899185,-0.0009926663056740261,-0.0076027045012507085,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4666796,1.0,1.0,1.0,1.0,1.0190151397339633,0.5695600568862853,0.5549404699234148,0.4017401646458921,-0.02367243335640298,-0.008683023815244176,-0.9154065004721685,-0.0011797475368006361,0.04040165231669719,0.013331340524032669,-0.005214037960593554,-0.03531925944104911,0.2217614428434015,0.03815688463048854,-0.0071484326946879805,0.003629337355833878,0.008207033718907077,-0.03971150870140626,0.006901736605546425,-0.006891750899095425,0.03364623096206855,-0.005843588911311828,-0.03684160181067356,0.0010831549553519378,-0.0025711896616026123,0.03815688463048854,-0.0071484326946879805,0.003629337355833878,0.008207033718907077,-0.03971150870140626,0.006901736605546425,-0.006891750899095425,0.03364623096206855,-0.005843588911311828,-0.03684160181067356,0.0010831549553519378,-0.0025711896616026123,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.4833463,1.0,1.0,1.0,1.0,1.019359678433457,0.569062947775292,0.5550775427464663,0.40338345581585217,-0.023913530555428133,-0.008564304162359142,-0.9146784043174134,-0.0013708489463069343,0.0411769436701115,0.0033815967477486765,0.048955350295867645,-0.0291781076494637,0.26830943154942977,0.048907940686026684,-0.009692403317637557,0.007814923593265863,0.01244880880036573,-0.04965503478177096,0.0007599941419980839,-0.005692573416688377,0.03954393599307697,9.107120291419002e-05,-0.04215170530234933,-0.0004186954710564328,-0.006963858248350258,0.048907940686026684,-0.009692403317637557,0.007814923593265863,0.01244880880036573,-0.04965503478177096,0.0007599941419980839,-0.005692573416688377,0.03954393599307697,9.107120291419002e-05,-0.04215170530234933,-0.0004186954710564328,-0.006963858248350258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.500013,1.0,1.0,1.0,1.0,1.0200634880507229,0.5686720159855544,0.555045753654751,0.40584503640855274,-0.023824320826171152,-0.009517728927709928,-0.9135817538653949,-0.018513082597822285,0.05426036572314671,-0.003547344549815212,0.16734012060956965,-0.04309487059977218,0.36730772081519797,0.07108363992210187,-0.016069409595443535,0.02127771984810903,0.020766068436881304,-0.07180225530840845,-0.008373701665075473,-0.004042736891643646,0.050882251868285856,0.009653321549242108,-0.05436030837687087,-0.0048505938446740645,-0.019998099963939066,0.07108363992210187,-0.016069409595443535,0.02127771984810903,0.020766068436881304,-0.07180225530840845,-0.008373701665075473,-0.004042736891643646,0.050882251868285856,0.009653321549242108,-0.05436030837687087,-0.0048505938446740645,-0.019998099963939066,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5166797,1.0,1.0,1.0,1.0,1.0211106015611278,0.5683033975791622,0.5549243003909747,0.409034528453683,-0.0234946330184279,-0.011257324842939042,-0.912146934100742,-0.01997763827808758,0.05928161425734462,-0.009097332178900183,0.13513377443478813,-0.02998583727467383,0.41403102384599083,0.07849864181583442,-0.015395631075805938,0.015981407820370806,0.022560975873695526,-0.07818465342706758,-0.006697180174078105,-0.006469355124678465,0.05971847392541333,0.007629733839511387,-0.062407021066820695,-0.003070548425848309,-0.015048854154937523,0.07849864181583442,-0.015395631075805938,0.015981407820370806,0.022560975873695526,-0.07818465342706758,-0.006697180174078105,-0.006469355124678465,0.05971847392541333,0.007629733839511387,-0.062407021066820695,-0.003070548425848309,-0.015048854154937523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5333464,1.0,1.0,1.0,1.0,1.0219712186773373,0.5678421870999257,0.5547108467907604,0.4121872064169238,-0.023441422816809086,-0.011615360593731054,-0.9107234980831523,-0.004812099237875687,0.05063154767136502,-0.011115913058241023,0.020603021007587433,0.002237922723494341,0.4059115721984269,0.07329340057840293,-0.010179223803009717,-0.0002914441720878781,0.019639820192341163,-0.07124279511230545,-0.0001627409512960531,-0.010212580141223563,0.06323150616174496,0.00011697463720009238,-0.06386616052729199,0.002167934852445888,0.00024567785799191734,0.07329340057840293,-0.010179223803009717,-0.0002914441720878781,0.019639820192341163,-0.07124279511230545,-0.0001627409512960531,-0.010212580141223563,0.06323150616174496,0.00011697463720009238,-0.06386616052729199,0.002167934852445888,0.00024567785799191734,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5500131,1.0,1.0,1.0,1.0,1.02247207350515,0.567294953856023,0.5545489840125725,0.415204458248348,-0.023399662141159402,-0.011396130937513248,-0.9093557289983005,-0.003398244753701081,0.048280349176183276,-0.004571420722282518,0.01467498267667354,0.009479810290639198,0.4357583584964484,0.07866708000571779,-0.009884090789298264,-0.0021578832672776035,0.02160617637367507,-0.07580255623574272,-0.0005563916390448939,-0.01149203239489624,0.0683377162914362,0.00028202935759455547,-0.06855293602693895,0.0024192508449917475,0.0018835209858172732,0.07866708000571779,-0.009884090789298264,-0.0021578832672776035,0.02160617637367507,-0.07580255623574272,-0.0005563916390448939,-0.01149203239489624,0.0683377162914362,0.00028202935759455547,-0.06855293602693895,0.0024192508449917475,0.0018835209858172732,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5666798,1.0,1.0,1.0,1.0,1.0232564076229966,0.5668675017917648,0.5545548636835153,0.4187980666330192,-0.023277358188441708,-0.01160196363708316,-0.9077068570964837,0.004159851229501163,0.050581118480301286,-0.0016485419595688926,-0.028301272028994538,0.008624455382031033,0.4656043194198587,0.08220132830124283,-0.008748382923278031,-0.0064469536912322755,0.022025792913679006,-0.07926451702866961,0.004045883579705353,-0.014742669088694699,0.07412266859937558,-0.004289340750184987,-0.07491820447625186,0.0036065344939806717,0.0062034965207459795,0.08220132830124283,-0.008748382923278031,-0.0064469536912322755,0.022025792913679006,-0.07926451702866961,0.004045883579705353,-0.014742669088694699,0.07412266859937558,-0.004289340750184987,-0.07491820447625186,0.0036065344939806717,0.0062034965207459795,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.5833465,1.0,1.0,1.0,1.0,1.0236632074836114,0.5660932251139269,0.5545039531385134,0.4222391082110082,-0.023560998108437235,-0.010728732837277658,-0.9061147328881775,0.016813980591974607,0.048604981190868285,-0.003988238654736709,-0.13686965268423584,0.034298209438507976,0.45913749260679343,0.0771901930760822,-0.003952868341691111,-0.021282740457731156,0.019141753569389745,-0.07311113549343659,0.010807021521519201,-0.018784442506899136,0.07729398803905742,-0.011842369634786255,-0.07683288201359159,0.008135720887303608,0.020247392344474095,0.0771901930760822,-0.003952868341691111,-0.021282740457731156,0.019141753569389745,-0.07311113549343659,0.010807021521519201,-0.018784442506899136,0.07729398803905742,-0.011842369634786255,-0.07683288201359159,0.008135720887303608,0.020247392344474095,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6000132,1.0,1.0,1.0,1.0,1.0241325007706172,0.565391599347175,0.5544503737828779,0.4256836583766721,-0.023807468914583792,-0.009113156562565304,-0.9045128953157053,0.019373416284215354,0.048682789086633135,4.588209639799186e-05,-0.18371982733707973,0.06546208075841013,0.45670285772831315,0.07559356501396443,-0.0008611946377636405,-0.030839749284830183,0.01875555480804108,-0.069809459299286,0.010499488836427257,-0.02015070090595246,0.07953470536758125,-0.0124625927778568,-0.07698871111186915,0.010586440706047232,0.02887664534340397,0.07559356501396443,-0.0008611946377636405,-0.030839749284830183,0.01875555480804108,-0.069809459299286,0.010499488836427257,-0.02015070090595246,0.07953470536758125,-0.0124625927778568,-0.07698871111186915,0.010586440706047232,0.02887664534340397,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.616679899999999,1.0,1.0,1.0,1.0,1.0245026011100298,0.5645618798467829,0.5545321648339826,0.4290608223098617,-0.02394776150062224,-0.007313083007697757,-0.9029284768434416,0.029835882766942597,0.045293211826276485,0.007430092539183372,-0.15828330554719897,0.05542852541263626,0.44923621720170254,0.07506827306470383,-0.001176495760309596,-0.026894238604082486,0.01956185766886391,-0.06967225805879587,0.009172247974702482,-0.019759691500316524,0.07708684743488742,-0.010830208710200169,-0.07526610689614978,0.008591085136397805,0.02523627786858147,0.07506827306470383,-0.001176495760309596,-0.026894238604082486,0.01956185766886391,-0.06967225805879587,0.009172247974702482,-0.019759691500316524,0.07708684743488742,-0.010830208710200169,-0.07526610689614978,0.008591085136397805,0.02523627786858147,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.633346599999999,1.0,1.0,1.0,1.0,1.0246847773084824,0.563675986858309,0.5547358970316187,0.43238839546979124,-0.024157684994196436,-0.006155786062031862,-0.9013427694372098,0.031453451501823784,0.03432773223014081,0.010034978917182084,-0.19752614783335656,0.037333100557929155,0.41962058428767496,0.06747896870558398,0.0003728026609783108,-0.027940236091196516,0.01654751339186904,-0.0637672519126822,0.015620533665126238,-0.02172318288891157,0.07268903683532982,-0.01662718510956133,-0.07265463820261985,0.008548982261660974,0.02693358464676475,0.06747896870558398,0.0003728026609783108,-0.027940236091196516,0.01654751339186904,-0.0637672519126822,0.015620533665126238,-0.02172318288891157,0.07268903683532982,-0.01662718510956133,-0.07265463820261985,0.008548982261660974,0.02693358464676475,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6500132999999995,1.0,1.0,1.0,1.0,1.0247524423645322,0.5630393538816119,0.5549062820417155,0.4352888696436756,-0.024857984510724344,-0.003909683674853417,-0.8999391062421715,0.022602680422029453,0.043434468714239824,0.004988554877778258,-0.20644240622742965,0.04884050175371982,0.43400517894228724,0.06991929476327326,0.001451502057421672,-0.03095015608110368,0.017844123852439817,-0.0653538346585945,0.014457270978985774,-0.022730288603831958,0.07559149272114832,-0.015811219549115588,-0.0748054595146554,0.008786156005125485,0.029596207510973863,0.06991929476327326,0.001451502057421672,-0.03095015608110368,0.017844123852439817,-0.0653538346585945,0.014457270978985774,-0.022730288603831958,0.07559149272114832,-0.015811219549115588,-0.0748054595146554,0.008786156005125485,0.029596207510973863,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6666799999999995,1.0,1.0,1.0,1.0,1.0253592696719316,0.5621914996719488,0.554917101840451,0.4388147404416973,-0.024946758705860966,-0.002522763820068644,-0.898227654029793,0.008974901079344202,0.049986924442976095,0.0066043560035461135,-0.10116206584281023,0.0514043470501109,0.42239153548627084,0.07252647868237433,-0.0008392038374680101,-0.02089564419993509,0.02148570597919844,-0.06682888741024853,0.0032941663868861714,-0.01803545099240395,0.0707541595282284,-0.0048530671606355135,-0.06907622369557652,0.004764475955441211,0.01933674342618575,0.07252647868237433,-0.0008392038374680101,-0.02089564419993509,0.02148570597919844,-0.06682888741024853,0.0032941663868861714,-0.01803545099240395,0.0707541595282284,-0.0048530671606355135,-0.06907622369557652,0.004764475955441211,0.01933674342618575,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.6833466999999995,1.0,1.0,1.0,1.0,1.0258919629429872,0.5617848565941403,0.5551112913656856,0.44157382200414286,-0.02484455144793593,-0.0018430080771114719,-0.8968789836456378,0.0035348697473695416,0.02939869072289363,0.01403997209491963,-0.05806250098849858,0.011864616881088627,0.3448808879594382,0.059567404398222945,-0.002093021786776111,-0.01009578975748882,0.018050846702827757,-0.056409512587309925,0.0046899677068843165,-0.01510838319094314,0.055653878865871975,-0.005098049849658158,-0.05662494088634166,0.001337388065326509,0.00968770761471831,0.059567404398222945,-0.002093021786776111,-0.01009578975748882,0.018050846702827757,-0.056409512587309925,0.0046899677068843165,-0.01510838319094314,0.055653878865871975,-0.005098049849658158,-0.05662494088634166,0.001337388065326509,0.00968770761471831,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7000134,1.0,1.0,1.0,1.0,1.0260839228337773,0.5615122039056668,0.5553717017666655,0.4439471705835032,-0.0252068254677751,-0.0014261077218648485,-0.8956972099417887,0.005157504216733538,0.017535955510552457,0.0176518722524447,-0.04134013674322062,-0.06352812173711272,0.3090389899562593,0.052062308496228775,-0.004614431825918496,0.0032083618510226957,0.015047163771682625,-0.053553308012539214,0.014333238186856098,-0.016033565146972063,0.04624041047049816,-0.012494196307837175,-0.05304870987152155,-0.0026984657161225585,-0.0013693199720071034,0.052062308496228775,-0.004614431825918496,0.0032083618510226957,0.015047163771682625,-0.053553308012539214,0.014333238186856098,-0.016033565146972063,0.04624041047049816,-0.012494196307837175,-0.05304870987152155,-0.0026984657161225585,-0.0013693199720071034,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7166801,1.0,1.0,1.0,1.0,1.0262787665454467,0.5613086975319399,0.5556953297308386,0.4461688329786062,-0.02610473447503417,-0.0015675698788353773,-0.894566631414995,-0.006797589616199541,0.012968492747079948,0.027695012332162216,0.028686262043820764,-0.1295665122618046,0.2583295268899624,0.04458173528017522,-0.008246047788151746,0.020485623301968806,0.013257865147286314,-0.049635425096431166,0.01722588445447179,-0.01349312281892483,0.033441162464250856,-0.013502364077812322,-0.04481699295180708,-0.007948214844023567,-0.016762102925312668,0.04458173528017522,-0.008246047788151746,0.020485623301968806,0.013257865147286314,-0.049635425096431166,0.01722588445447179,-0.01349312281892483,0.033441162464250856,-0.013502364077812322,-0.04481699295180708,-0.007948214844023567,-0.016762102925312668,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7333468,1.0,1.0,1.0,1.0,1.0266069226186278,0.561456977914697,0.5562738509572627,0.4478090297687499,-0.02692947363013077,-0.002705288121987407,-0.8937195072973131,-0.014796667908903362,0.011933512836429705,0.03053312984570561,0.0960285387727887,-0.13478829178204604,0.21300946774914467,0.03941159301286996,-0.009647684594255582,0.028286227218527533,0.013076724399496194,-0.04430229754303152,0.011260611344430769,-0.008983364494818073,0.024244730849940135,-0.007453329783995382,-0.035318233108185174,-0.01040988209881915,-0.024478945658088818,0.03941159301286996,-0.009647684594255582,0.028286227218527533,0.013076724399496194,-0.04430229754303152,0.011260611344430769,-0.008983364494818073,0.024244730849940135,-0.007453329783995382,-0.035318233108185174,-0.01040988209881915,-0.024478945658088818,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7500135,1.0,1.0,1.0,1.0,1.0269384409304287,0.5614946447404333,0.5566790049876624,0.44937924341449353,-0.027405145264053375,-0.003907758078520073,-0.8929120802341478,0.0001782670304025601,0.007080608157092588,0.01586385811610658,0.08380101743409522,-0.09498128277180898,0.1902712336138679,0.03573779476153042,-0.007471297446550775,0.021230553401245852,0.012338645761933241,-0.038514803478664386,0.006486415842471573,-0.007272091117106762,0.022798751699452266,-0.003820606401904595,-0.03067124011670394,-0.008244754332651354,-0.018564743960682202,0.03573779476153042,-0.007471297446550775,0.021230553401245852,0.012338645761933241,-0.038514803478664386,0.006486415842471573,-0.007272091117106762,0.022798751699452266,-0.003820606401904595,-0.03067124011670394,-0.008244754332651354,-0.018564743960682202,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7666802,1.0,1.0,1.0,1.0,1.0268168718753707,0.5613282366047405,0.5567979822797448,0.4506731221326913,-0.0277283224144555,-0.004576759044519443,-0.8922465636806347,0.015872130317532228,0.001720408316639109,-0.002197550308143325,0.06466570102899878,-0.05006404305956674,0.15309809214596515,0.0292703873969432,-0.004864726276832788,0.012808307856163386,0.010541697252183761,-0.02990655007194187,0.001533986615111372,-0.005081849439916189,0.019598709421853957,-0.00017284129889083154,-0.023810539584668965,-0.005443114373266783,-0.011447162539949507,0.0292703873969432,-0.004864726276832788,0.012808307856163386,0.010541697252183761,-0.02990655007194187,0.001533986615111372,-0.005081849439916189,0.019598709421853957,-0.00017284129889083154,-0.023810539584668965,-0.005443114373266783,-0.011447162539949507,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.7833469,1.0,1.0,1.0,1.0,1.026667910119861,0.561032808457526,0.5566332655408373,0.45168243829601284,-0.02767549900783193,-0.005174238415623244,-0.891734416150041,0.016694913119888924,0.008536082588601878,-0.00906906937619698,0.0750477297285492,-0.01762295213104382,0.1154392130435877,0.023749997060873256,-0.003586844812159891,0.009214666566305024,0.009442512187607669,-0.022689418467027742,-0.004524539435740552,-0.0019432868990882238,0.014975138434790536,0.004899647408547651,-0.016250771772350483,-0.00412743522007232,-0.008839558593494595,0.023749997060873256,-0.003586844812159891,0.009214666566305024,0.009442512187607669,-0.022689418467027742,-0.004524539435740552,-0.0019432868990882238,0.014975138434790536,0.004899647408547651,-0.016250771772350483,-0.00412743522007232,-0.008839558593494595,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8000136,1.0,1.0,1.0,1.0,1.026704081487833,0.5607013340659719,0.5565217397000521,0.4524221323074627,-0.027435057505369675,-0.005771330541201948,-0.8913631266559269,0.022011046886855273,0.01248146110400109,-0.005587437034425455,0.011087327443693187,0.003163389600902759,0.08903893019355884,0.016572417986016955,-0.000877037073944669,-5.8716739229998136e-05,0.0059801720761184585,-0.01530968702920541,-0.0013085394503630084,-0.003066835145407679,0.013559467347244074,0.0011611775628866553,-0.01365908105532283,-0.0008731826080100067,-8.864514823969369e-05,0.016572417986016955,-0.000877037073944669,-5.8716739229998136e-05,0.0059801720761184585,-0.01530968702920541,-0.0013085394503630084,-0.003066835145407679,0.013559467347244074,0.0011611775628866553,-0.01365908105532283,-0.0008731826080100067,-8.864514823969369e-05,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8166803,1.0,1.0,1.0,1.0,1.0265632264533986,0.5601890336962172,0.5564809787905879,0.453010705354465,-0.02755427592146949,-0.005274644775684596,-0.8910635447795988,0.038015950365293705,0.01209259146944356,-0.0033425348359041383,-0.11069898103775105,0.030848063426789397,0.08424294587294906,0.010776342514681344,0.003456077996520223,-0.016302323833458848,0.00186340129545842,-0.009396987699586834,0.006710097945774215,-0.00748011879668099,0.017341467036976706,-0.007505028954099279,-0.016393060015893923,0.004488401340856327,0.015507392825137113,0.010776342514681344,0.003456077996520223,-0.016302323833458848,0.00186340129545842,-0.009396987699586834,0.006710097945774215,-0.00748011879668099,0.017341467036976706,-0.007505028954099279,-0.016393060015893923,0.004488401340856327,0.015507392825137113,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.833347,1.0,1.0,1.0,1.0,1.0262795112926388,0.559437210874145,0.5564725051713324,0.4536246439906448,-0.0278207034387809,-0.003855823179863444,-0.8907501464788752,0.04429444725546248,0.01965363698412846,-0.006458221260107492,-0.1875556451657096,0.04860814509390901,0.07924589942936554,0.00672823640915788,0.006254535161790542,-0.026573306786953004,-0.0008377538266122991,-0.005356250452978587,0.01172084217163119,-0.010203081792714404,0.01945639283510946,-0.012888359760022245,-0.01776907202846127,0.007845607220338667,0.02540578919855862,0.00672823640915788,0.006254535161790542,-0.026573306786953004,-0.0008377538266122991,-0.005356250452978587,0.01172084217163119,-0.010203081792714404,0.01945639283510946,-0.012888359760022245,-0.01776907202846127,0.007845607220338667,0.02540578919855862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8500137,1.0,1.0,1.0,1.0,1.02621632548369,0.5586037561153864,0.556332352024079,0.45410322229718475,-0.028256176608183643,-0.002086131731610026,-0.8904984559431864,0.04141605925377826,0.0350734578690083,-0.014149681905190007,-0.22867687701845005,0.05080562902387681,0.07137328719595819,0.0033922471632283633,0.007590140159953786,-0.030902066508963672,-0.002748367514359401,-0.0026195715934555375,0.015504944128266486,-0.011746262310529082,0.019484654340290664,-0.01657858671691072,-0.017886876988116845,0.009274942586883005,0.029828423920322766,0.0033922471632283633,0.007590140159953786,-0.030902066508963672,-0.002748367514359401,-0.0026195715934555375,0.015504944128266486,-0.011746262310529082,0.019484654340290664,-0.01657858671691072,-0.017886876988116845,0.009274942586883005,0.029828423920322766,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8666804,1.0,1.0,1.0,1.0,1.026393365570808,0.5576200577570425,0.5560480367865022,0.45457781963418703,-0.028799995525652718,-4.380713415325956e-05,-0.8902412955122257,0.05936827418196826,0.033285563262912744,-0.015130998473484989,-0.3319742971916224,0.04506235440977944,0.033089367566665515,-0.008539118318129335,0.010588340680115653,-0.039792271099439815,-0.008942881416742526,0.006912258115644743,0.02683572048123661,-0.015250390144858019,0.01624139269845277,-0.027291538577665433,-0.015654153243461217,0.012565310133970204,0.039336453003014325,-0.008539118318129335,0.010588340680115653,-0.039792271099439815,-0.008942881416742526,0.006912258115644743,0.02683572048123661,-0.015250390144858019,0.01624139269845277,-0.027291538577665433,-0.015654153243461217,0.012565310133970204,0.039336453003014325,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.8833471,1.0,1.0,1.0,1.0,1.0259306954523344,0.5563378439168185,0.5559014113011869,0.4544339499355056,-0.030104655417361067,0.0031960004206648862,-0.8902658481877913,0.0847100438961992,0.018430600685316142,-0.017080777956161957,-0.5130656121421174,0.05592078947134939,-0.030430120413239125,-0.028481132080860526,0.01672784394965908,-0.05845994107589565,-0.018997792233886857,0.023765580327923547,0.04365521378963753,-0.020846215736965136,0.012134253275199557,-0.043505606676984436,-0.011362875889978141,0.019171989653445704,0.05860954818854708,-0.028481132080860526,0.01672784394965908,-0.05845994107589565,-0.018997792233886857,0.023765580327923547,0.04365521378963753,-0.020846215736965136,0.012134253275199557,-0.043505606676984436,-0.011362875889978141,0.019171989653445704,0.05860954818854708,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9000138,1.0,1.0,1.0,1.0,1.0252058490129805,0.554961844389174,0.5556025678859091,0.45386219283723084,-0.031858847238395466,0.007976636568023564,-0.8904664491347682,0.08903272484362101,0.025513515070015074,-0.009550777126034235,-0.45098265168399077,0.033910282255880456,-0.026436613576355118,-0.025471604520979685,0.014314747575150125,-0.04895014619807007,-0.016785694740735844,0.02007310992648875,0.040795072110383225,-0.019085375948256985,0.010251848668816635,-0.039931295059581796,-0.010399466167999824,0.016010211020138606,0.04981392324886983,-0.025471604520979685,0.014314747575150125,-0.04895014619807007,-0.016785694740735844,0.02007310992648875,0.040795072110383225,-0.019085375948256985,0.010251848668816635,-0.039931295059581796,-0.010399466167999824,0.016010211020138606,0.04981392324886983,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9166805,1.0,1.0,1.0,1.0,1.0248582392604435,0.5534328407098457,0.555693960531813,0.4538038145853982,-0.033015505681388384,0.010132257962098008,-0.890432148791211,0.08517360513138357,0.03344523925533453,0.003234721147412776,-0.30654441791304665,0.005391747441189573,-0.02371957104773559,-0.01891613524014141,0.009254620292812543,-0.03033400615926381,-0.011955692170548458,0.013813292965030954,0.030592811353936072,-0.013560627361243712,0.005439928413631023,-0.029210219711109552,-0.006600184291630777,0.009998601085836112,0.031716597802085335,-0.01891613524014141,0.009254620292812543,-0.03033400615926381,-0.011955692170548458,0.013813292965030954,0.030592811353936072,-0.013560627361243712,0.005439928413631023,-0.029210219711109552,-0.006600184291630777,0.009998601085836112,0.031716597802085335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9333472,1.0,1.0,1.0,1.0,1.024449840480992,0.5520113162085039,0.5557974327803833,0.45333987894427263,-0.03410229774845529,0.012553120234434643,-0.890596657651177,0.08983032230125304,0.028739822769714974,0.012057477794933668,-0.27030120141384867,0.0025376784170379058,-0.029204301486804737,-0.018278462098291162,0.00820602311187518,-0.026256434961353346,-0.010990116552009961,0.01341782171242229,0.02737478292753351,-0.011786408938233838,0.0035161547853009264,-0.025962629267051177,-0.004498063391939315,0.008727953385836377,0.02766858862183401,-0.018278462098291162,0.00820602311187518,-0.026256434961353346,-0.010990116552009961,0.01341782171242229,0.02737478292753351,-0.011786408938233838,0.0035161547853009264,-0.025962629267051177,-0.004498063391939315,0.008727953385836377,0.02766858862183401,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9500139,1.0,1.0,1.0,1.0,1.0239033699450988,0.5504518968367551,0.5561915787994618,0.45321749733657585,-0.035025810772472535,0.014147348619477506,-0.8905992057119414,0.10222522575771409,0.03199437347909684,0.017840416624336487,-0.1396674172601889,-0.021179663730186177,-0.0064159721023265524,-0.008345364692413062,0.0032988638322397953,-0.010231416143264536,-0.005525521135572063,0.004536665406421777,0.017561261855594323,-0.007369983705520391,0.0022289630292872927,-0.016114885779516877,-0.004550140148676061,0.003466764603469274,0.011677792219336985,-0.008345364692413062,0.0032988638322397953,-0.010231416143264536,-0.005525521135572063,0.004536665406421777,0.017561261855594323,-0.007369983705520391,0.0022289630292872927,-0.016114885779516877,-0.004550140148676061,0.003466764603469274,0.011677792219336985,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9666806,1.0,1.0,1.0,1.0,1.02335514397074,0.5486331180985865,0.556498574485125,0.45316918571475057,-0.03547327436246439,0.014462553369849848,-0.8906010164347778,0.09293669689033882,0.022537881276520528,0.008096423154774244,-0.08803415014772861,-0.011057286820373134,-0.03343213473113748,-0.010510793074101623,0.0024016270697016944,-0.0063724164566315005,-0.005234000842320511,0.007912026080409881,0.010846085135131646,-0.00335599311922758,-0.0030176435114500884,-0.009934405098324951,0.0019207991125468704,0.0024927554992547674,0.0072840964934398605,-0.010510793074101623,0.0024016270697016944,-0.0063724164566315005,-0.005234000842320511,0.007912026080409881,0.010846085135131646,-0.00335599311922758,-0.0030176435114500884,-0.009934405098324951,0.0019207991125468704,0.0024927554992547674,0.0072840964934398605,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +6.9833473,1.0,1.0,1.0,1.0,1.0227118816246659,0.5475074775490356,0.5565722948040734,0.4526714115673682,-0.03586302039710425,0.015350559554545614,-0.890823662258118,0.08508733614334565,0.0052071447580791,-0.008174030311108967,-0.08786615157759974,0.006852905703300045,-0.051979925272879236,-0.01349552285757873,0.003268197037342287,-0.00880991951255728,-0.006027836285932842,0.011760737834975651,0.008190402636229827,-0.0018809398260910993,-0.005116041777601346,-0.007786208825702616,0.00558674674555812,0.003376499020020361,0.009214113323087823,-0.01349552285757873,0.003268197037342287,-0.00880991951255728,-0.006027836285932842,0.011760737834975651,0.008190402636229827,-0.0018809398260910993,-0.005116041777601346,-0.007786208825702616,0.00558674674555812,0.003376499020020361,0.009214113323087823,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.000014,1.0,1.0,1.0,1.0,1.0218071481850055,0.5462388060821817,0.556358358979971,0.45234335567332407,-0.03604783520753738,0.015787709174635473,-0.8909751906725933,0.10310147108006149,-0.004150154139216709,-0.02270289696451011,-0.08863089124158406,0.005626070301626207,-0.04552726994240227,-0.012407859916378695,0.0032175240964675516,-0.00876898695271794,-0.0056530251974019965,0.010640602105633034,0.00844694869244101,-0.002249580311904229,-0.004137337340306011,-0.007991713374907505,0.0045052544070824626,0.0032857406688644665,0.009224222270251445,-0.012407859916378695,0.0032175240964675516,-0.00876898695271794,-0.0056530251974019965,0.010640602105633034,0.00844694869244101,-0.002249580311904229,-0.004137337340306011,-0.007991713374907505,0.0045052544070824626,0.0032857406688644665,0.009224222270251445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0166807,1.0,1.0,1.0,1.0,1.020519726439122,0.5448116517572719,0.5559979503973596,0.45194045226427293,-0.03645950306062848,0.016681818393661486,-0.891146592418339,0.13158437402810702,-0.018939437714681113,-0.012438594402993264,-0.12506867282966896,-0.038824568215385574,-0.08148523676443968,-0.021447761790366556,0.002795125186651593,-0.004992186216315261,-0.009839765645937073,0.01601668558198245,0.019122940220146403,-0.004381640320581541,-0.010429932819249617,-0.017007435196602055,0.007226355823857935,0.0027916275760795756,0.007107691239862937,-0.021447761790366556,0.002795125186651593,-0.004992186216315261,-0.009839765645937073,0.01601668558198245,0.019122940220146403,-0.004381640320581541,-0.010429932819249617,-0.017007435196602055,0.007226355823857935,0.0027916275760795756,0.007107691239862937,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0333474,1.0,1.0,1.0,1.0,1.0186834548642825,0.5430722006726729,0.5562035295818465,0.4510682385722736,-0.037589745477658344,0.01730342251950508,-0.891529610700252,0.14367183964495092,-0.030770815283230734,-0.0024745618991964804,-0.18303742558345865,-0.0773319995233055,-0.1000511630093914,-0.028360023096031497,0.0031545165301874035,-0.004415728433020216,-0.013493789849806898,0.019380952683871175,0.03103847077100246,-0.008094190514276896,-0.01314364282236861,-0.027289890220522337,0.006772042731951034,0.0030827933313084983,0.008164308983498672,-0.028360023096031497,0.0031545165301874035,-0.004415728433020216,-0.013493789849806898,0.019380952683871175,0.03103847077100246,-0.008094190514276896,-0.01314364282236861,-0.027289890220522337,0.006772042731951034,0.0030827933313084983,0.008164308983498672,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.050014099999999,1.0,1.0,1.0,1.0,1.0168625525595645,0.541561109300229,0.5562284042244402,0.450360286821245,-0.03901250688992859,0.018757979497473223,-0.8917969357233864,0.15032232583120353,-0.030793270013547785,-0.006056637956627721,-0.22154514697478578,-0.096158033544358,-0.06940900976594633,-0.025090246418855412,0.003329682241954533,-0.0056383635643427535,-0.11329203423993098,-0.09785086967070247,0.09970775241895807,-0.012146582822846919,-0.007990404379229073,-0.03316332574304406,-0.00011986471141526527,0.003259983305175141,0.010254838417319457,-0.025090246418855412,0.003329682241954533,-0.0056383635643427535,-0.11329203423993098,-0.09785086967070247,0.09970775241895807,-0.012146582822846919,-0.007990404379229073,-0.03316332574304406,-0.00011986471141526527,0.003259983305175141,0.010254838417319457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.066680799999999,1.0,0.0,1.0,1.0,1.0148801012554405,0.5396489357243768,0.5563368082772777,0.4499235474937944,-0.04070344150244221,0.01983006576095218,-0.8919186060131121,0.17000472601820887,-0.02963666043124634,-0.008234786228629156,-0.2593572458614788,-0.09026865941261661,-0.052634406529958086,-0.023956981942726576,0.004621654337743862,-0.010302421968903524,-0.4110573875546076,-0.30406731638886453,0.2885497321008913,-0.0146085571296817,-0.003989992178397112,-0.03596898473468946,-0.003641776757963533,0.004526694842254562,0.01510884370613735,-0.023956981942726576,0.004621654337743862,-0.010302421968903524,-0.4110573875546076,-0.30406731638886453,0.2885497321008913,-0.0146085571296817,-0.003989992178397112,-0.03596898473468946,-0.003641776757963533,0.004526694842254562,0.01510884370613735,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.0833474999999995,1.0,0.0,1.0,1.0,1.0126926775906884,0.5375906236220798,0.55633650503435,0.4494295116940993,-0.042316180437229,0.02190064887415806,-0.8920441785419029,0.18330526486766194,-0.03333332554533775,-0.015413479664797983,-0.24223292827329196,-0.031089305443300554,-0.059891490575409344,-0.023435431310403612,0.006631749109246991,-0.017424301183004948,-0.7211586966305561,-0.4742303357505791,0.5201504844180276,-0.011097155911822374,-0.0031381448173815807,-0.027176076999403276,0.0005629708946861494,0.006464736282288314,0.02038573880511399,-0.023435431310403612,0.006631749109246991,-0.017424301183004948,-0.7211586966305561,-0.4742303357505791,0.5201504844180276,-0.011097155911822374,-0.0031381448173815807,-0.027176076999403276,0.0005629708946861494,0.006464736282288314,0.02038573880511399,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1000141999999995,1.0,0.0,1.0,1.0,1.0103223935851984,0.5354000469450226,0.5562520451195232,0.44887414589156993,-0.04300266901639397,0.02315576721851322,-0.892259257196081,0.17406514225338152,-0.05363393341882626,-0.042604950331771786,-0.18452450360806355,0.08182891772299877,-0.11177485456706023,-0.028062717445603257,0.010119239655824645,-0.028041598819916084,-0.9578768320747604,-0.5110854482578578,0.6618241880460299,-0.001392196227747705,-0.00827433739758229,-0.008222366579691193,0.015489072847499806,0.009560275575856805,0.02726619180997979,-0.028062717445603257,0.010119239655824645,-0.028041598819916084,-0.9578768320747604,-0.5110854482578578,0.6618241880460299,-0.001392196227747705,-0.00827433739758229,-0.008222366579691193,0.015489072847499806,0.009560275575856805,0.02726619180997979,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1166808999999995,1.0,0.0,1.0,1.0,1.0076830775846781,0.5340006800700831,0.5553906450010545,0.4476008249599037,-0.04252340383036423,0.025175487635723626,-0.8928669869830538,0.17116188944549293,-0.07820503646944124,-0.0816251039716437,-0.1171166763523267,0.20177256401293586,-0.1664469407999878,-0.03252120646975849,0.013688880814244448,-0.03879301420948751,-1.2012484844967855,-0.5108911242618173,0.5840240174611322,0.009256098900898931,-0.014000212124767273,0.012415566247636832,0.031404462148763454,0.0125749347061016,0.03395233443335557,-0.03252120646975849,0.013688880814244448,-0.03879301420948751,-1.2012484844967855,-0.5108911242618173,0.5840240174611322,0.009256098900898931,-0.014000212124767273,0.012415566247636832,0.031404462148763454,0.0125749347061016,0.03395233443335557,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1333476,1.0,0.0,1.0,1.0,1.004577752690717,0.5324052602143896,0.5540655806687804,0.44622720656253245,-0.04094517662359215,0.026284378066286276,-0.8935960519744536,0.2014659192895799,-0.08565129166462992,-0.0987983003937018,0.04940489591196129,0.26677174746511284,-0.15497407074709763,-0.02092478211991613,0.011260573701314159,-0.03296442677913951,-1.332667062163322,-0.6310315710209666,0.41308640589024065,0.019879255950863286,-0.015001060311317259,0.036213536997663845,0.037520188940721094,0.00994748173427483,0.02481579472366763,-0.02092478211991613,0.011260573701314159,-0.03296442677913951,-1.332667062163322,-0.6310315710209666,0.41308640589024065,0.019879255950863286,-0.015001060311317259,0.036213536997663845,0.037520188940721094,0.00994748173427483,0.02481579472366763,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1500143,1.0,0.0,1.0,1.0,1.001075448903272,0.5303790980196258,0.5526852916050787,0.4452064051641323,-0.03825198059000094,0.026315606676585133,-0.8942234237745151,0.23087110359129018,-0.10379388704682815,-0.09329720989850394,0.16941760290203775,0.28540457339738634,-0.18622487098025287,-0.020044141310671188,0.008704326647906548,-0.023950545498861872,-1.3444120395688006,-0.6532027638798037,0.35474972543042715,0.02764108504999182,-0.02305915808379544,0.0497906798431437,0.04696259479391367,0.007104864850522666,0.01442199322172897,-0.020044141310671188,0.008704326647906548,-0.023950545498861872,-1.3444120395688006,-0.6532027638798037,0.35474972543042715,0.02764108504999182,-0.02305915808379544,0.0497906798431437,0.04696259479391367,0.007104864850522666,0.01442199322172897,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.166681,1.0,0.0,1.0,1.0,0.9969218206942112,0.528386146184873,0.5515959016821564,0.4434324136526273,-0.03551682415780611,0.025760615752353076,-0.895233288255083,0.25556103466564384,-0.13347269791609104,-0.07569942099998729,0.29944041464599463,0.2199688144152424,-0.27513285929462694,-0.030671703516808025,0.002771413322094738,-0.00030071980945328843,-1.2497994793260994,-0.47482119759281777,0.2632411733281769,0.034299876252579284,-0.04377405658882341,0.05391415161312447,0.0625216302150242,0.0008672876038912626,-0.007970801488831952,-0.030671703516808025,0.002771413322094738,-0.00030071980945328843,-1.2497994793260994,-0.47482119759281777,0.2632411733281769,0.034299876252579284,-0.04377405658882341,0.05391415161312447,0.0625216302150242,0.0008672876038912626,-0.007970801488831952,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.1833477,1.0,0.0,1.0,1.0,0.992185997749913,0.5263304898288791,0.550864135618543,0.4411776005576762,-0.03287843564808961,0.023312221340182473,-0.896514290779401,0.279450764907884,-0.15537541166808425,-0.07078321972098536,0.37557537529255974,0.14506726664748743,-0.3378415864743205,-0.039509295409162225,-0.0019658504479776596,0.018993316316022843,-1.014458227209815,-0.17808126179021727,-0.03726065362579266,0.036726180715525567,-0.05893086802424718,0.052088601188774494,0.07186681345854126,-0.0044268295141679515,-0.025362329736842715,-0.039509295409162225,-0.0019658504479776596,0.018993316316022843,-1.014458227209815,-0.17808126179021727,-0.03726065362579266,0.036726180715525567,-0.05893086802424718,0.052088601188774494,0.07186681345854126,-0.0044268295141679515,-0.025362329736842715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2000144,1.0,0.0,1.0,1.0,0.9869763770203963,0.5241908616721722,0.5499683930473274,0.4385333831265772,-0.03071747901982532,0.021032698165362837,-0.8979435026626731,0.30701575678502585,-0.17118012014331896,-0.061618814606684974,0.37673910121345483,0.05553438782674301,-0.3919370713358907,-0.05116855810925392,-0.004731676310086567,0.03314661088443164,-0.8891105457670279,0.07661845918431893,-0.3749230642319857,0.03443719163581952,-0.07096652547209696,0.041411968652760714,0.07703587720654476,-0.008353487908540055,-0.03660327973355272,-0.05116855810925392,-0.004731676310086567,0.03314661088443164,-0.8891105457670279,0.07661845918431893,-0.3749230642319857,0.03443719163581952,-0.07096652547209696,0.041411968652760714,0.07703587720654476,-0.008353487908540055,-0.03660327973355272,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2166811,1.0,0.0,1.0,1.0,0.9812699843282026,0.5217860577981835,0.5495608893131639,0.4354808557144333,-0.029432710965325598,0.01788283081800799,-0.8995389620207627,0.33003354108965294,-0.19002761254479805,-0.0416482510720688,0.4199072213605889,-0.006285250587924561,-0.47164508114464593,-0.06484212519964633,-0.00704476113354952,0.04739500721675201,-0.8149692531975539,0.0894705672308082,-0.5689165077043975,0.036046174825348436,-0.08721595793603402,0.03831070593583964,0.08876166947996796,-0.012732530495036712,-0.04900280427036894,-0.06484212519964633,-0.00704476113354952,0.04739500721675201,-0.8149692531975539,0.0894705672308082,-0.5689165077043975,0.036046174825348436,-0.08721595793603402,0.03831070593583964,0.08876166947996796,-0.012732530495036712,-0.04900280427036894,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2333478,1.0,0.0,1.0,1.0,0.9751157520574392,0.519497069428913,0.5493607596242889,0.4316686594603393,-0.027902767507739033,0.014460506478564126,-0.9014846076098617,0.3448582194746059,-0.21652299990228488,-0.03875747112657738,0.44485539913207134,0.015638809185096313,-0.5931148080598585,-0.08522622524151868,-0.004207021963300563,0.04750313759767576,-0.5599133826647983,0.2622258056420674,-0.8091455359556569,0.04121556185701802,-0.10619410801717898,0.043781980792067576,0.10997264097735386,-0.013694311003212199,-0.04950136902305243,-0.08522622524151868,-0.004207021963300563,0.04750313759767576,-0.5599133826647983,0.2622258056420674,-0.8091455359556569,0.04121556185701802,-0.10619410801717898,0.043781980792067576,0.10997264097735386,-0.013694311003212199,-0.04950136902305243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2500145,1.0,0.0,1.0,1.0,0.9683840729207026,0.5173573839019237,0.5490683526956509,0.42677070739101514,-0.026135965310152578,0.011036431051343347,-0.9039147480929427,0.37777968455803856,-0.2372685628200922,-0.03990911607903021,0.47050060709527686,0.07629657899709338,-0.7092279861019457,-0.10366811646065315,0.0005092051199396871,0.04152783187512692,-0.16259653597411047,0.6420859653372211,-1.117267110884622,0.047108850844371504,-0.12295404529903516,0.05428929241875397,0.13186686228612882,-0.01374397847221539,-0.045016551417078415,-0.10366811646065315,0.0005092051199396871,0.04152783187512692,-0.16259653597411047,0.6420859653372211,-1.117267110884622,0.047108850844371504,-0.12295404529903516,0.05428929241875397,0.13186686228612882,-0.01374397847221539,-0.045016551417078415,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2666812,1.0,1.0,1.0,1.0,0.960954545609153,0.5147971250470919,0.5488432010349976,0.4211748782673126,-0.023534519527744564,0.007602803463618645,-0.9066421817269514,0.42103267417449447,-0.23794522534357043,-0.021709984570418048,0.587107611781578,0.14481751936162657,-0.7589478201285568,-0.10609725056906022,0.0017399595271872723,0.04233390341702707,0.030772495448931774,0.44761624632437846,-0.6720571529944319,-0.1167747327764932,-0.2984230692218866,0.17199380034905615,0.1466535854878224,-0.016940197663991404,-0.047803083920654056,-0.10609725056906022,0.0017399595271872723,0.04233390341702707,0.030772495448931774,0.44761624632437846,-0.6720571529944319,-0.1167747327764932,-0.2984230692218866,0.17199380034905615,0.1466535854878224,-0.016940197663991404,-0.047803083920654056,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.2833479,1.0,1.0,0.0,1.0,0.9532542022060206,0.5117464320824887,0.5491211889381246,0.41551083359466634,-0.019930270412046643,0.0028776196889048287,-0.9093653010708591,0.469184990166949,-0.23655905949235584,-0.002958088683905075,0.6789606565168216,0.1188021394245482,-0.7742156974550256,-0.10604549698292356,-0.00019255550100999105,0.05423650435096093,-0.010031463002805645,0.11528345257480463,-0.0866770834778376,-0.31387321773238047,-0.5027174562085708,0.3173162784884388,0.15155859182457979,-0.023283441142292482,-0.05875568121383445,-0.10604549698292356,-0.00019255550100999105,0.05423650435096093,-0.010031463002805645,0.11528345257480463,-0.0866770834778376,-0.31387321773238047,-0.5027174562085708,0.3173162784884388,0.15155859182457979,-0.023283441142292482,-0.05875568121383445,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3000146,1.0,1.0,0.0,1.0,0.9447658878742575,0.508137783781466,0.5494460456942943,0.4096566618968753,-0.017070110903774135,-0.002116636131906555,-0.9120776011550373,0.51100304504499,-0.2480112782557359,-0.00850316271660171,0.5220434524274598,-0.03981415273564888,-0.8488379517354159,-0.130888274429009,0.0030030297861860173,0.061845772309328695,-0.02132512519525692,0.1280555862724156,-0.048084741918637194,-0.3349118657289469,-0.615873304033081,0.36852182839918524,0.15213331620414552,-0.02697206335932534,-0.0611783119114855,-0.130888274429009,0.0030030297861860173,0.061845772309328695,-0.02132512519525692,0.1280555862724156,-0.048084741918637194,-0.3349118657289469,-0.615873304033081,0.36852182839918524,0.15213331620414552,-0.02697206335932534,-0.0611783119114855,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3166813,1.0,1.0,0.0,1.0,0.9357610075374057,0.5045061320921719,0.5494815552507607,0.40274763332973046,-0.01692574115652527,-0.005550690134034491,-0.9151377234999327,0.5176963631282107,-0.2396218371376441,-0.05431255827459399,0.3231202770195287,-0.2960031829465893,-0.9133400041596775,-0.15846644763339213,0.004706504655014827,0.08075672359803984,-0.03688696493149945,0.1378464787379562,0.009699884054309233,-0.37973320941944816,-0.8705525046083861,0.4971896422936949,0.14544217251066185,-0.03336856038778374,-0.07218670765409899,-0.15846644763339213,0.004706504655014827,0.08075672359803984,-0.03688696493149945,0.1378464787379562,0.009699884054309233,-0.37973320941944816,-0.8705525046083861,0.4971896422936949,0.14544217251066185,-0.03336856038778374,-0.07218670765409899,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.333348,1.0,1.0,0.0,1.0,0.9271801013862495,0.5007731632172223,0.5482762657920758,0.39578037515887365,-0.019333439608222383,-0.0092701345117728,-0.9180948629407258,0.5189069549109242,-0.2093597257328657,-0.12222132670401248,0.2799224387090724,-0.5989838069065259,-0.9531679431020673,-0.1763508312046768,0.00080001511409177,0.12274242530296871,-0.04707994716567298,0.13735724963629703,0.05856876515329116,-0.5393266761665593,-1.2607047524263146,0.691746814637229,0.1378551248307752,-0.047751571577240325,-0.10481466487301554,-0.1763508312046768,0.00080001511409177,0.12274242530296871,-0.04707994716567298,0.13735724963629703,0.05856876515329116,-0.5393266761665593,-1.2607047524263146,0.691746814637229,0.1378551248307752,-0.047751571577240325,-0.10481466487301554,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3500147,1.0,1.0,0.0,1.0,0.9187070311555494,0.4966016384116034,0.5461402198970741,0.3881475902887309,-0.024102718915092226,-0.014075587506697785,-0.92117445955166,0.5309202877093085,-0.189906399675613,-0.17074937108334395,0.13571609009007463,-0.8695071273471914,-1.0078505222858762,-0.19942906763422488,0.0032787019692582945,0.1504934772429931,-0.059463772438002764,0.14637194256426744,0.1121721176243003,-0.8203660442469046,-1.7416613305507227,0.6930946397558546,0.1298344942795415,-0.05743740913737554,-0.12357425469949117,-0.19942906763422488,0.0032787019692582945,0.1504934772429931,-0.059463772438002764,0.14637194256426744,0.1121721176243003,-0.8203660442469046,-1.7416613305507227,0.6930946397558546,0.1298344942795415,-0.05743740913737554,-0.12357425469949117,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3666814,1.0,1.0,0.0,1.0,0.9101141975892932,0.4922959375624606,0.5435270033741897,0.380134335867323,-0.03155384352302899,-0.017362801742517114,-0.9242298278941681,0.5532390581291502,-0.1822177122956046,-0.1895883102500848,-0.09115814624797788,-0.9665986392945672,-1.066126037744626,-0.22011131397896383,0.014775991370042717,0.14503111416585038,-0.06783100036263735,0.16542364950241306,0.14781315654874816,-1.253754511883104,-2.247483224635032,0.3305283268655258,0.12562744867556216,-0.05695774113100439,-0.11388042703359857,-0.22011131397896383,0.014775991370042717,0.14503111416585038,-0.06783100036263735,0.16542364950241306,0.14781315654874816,-1.253754511883104,-2.247483224635032,0.3305283268655258,0.12562744867556216,-0.05695774113100439,-0.11388042703359857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.3833481,1.0,1.0,0.0,1.0,0.9010722771092831,0.4876242507718714,0.5411068045351506,0.3713864525054115,-0.03924709599401819,-0.0193592429366184,-0.9274464879789038,0.5908799820962344,-0.15983015748204485,-0.19799949042158987,-0.1641852275529906,-0.7996108146261278,-1.110060028317004,-0.8164794590577595,-0.0672945132534559,0.16142509182712056,-0.06215685125590191,0.18293343531564982,0.12814833259999084,-1.6435395936772805,-2.6826527901876123,-0.2056303921851143,0.13542239699533204,-0.050961011055553444,-0.08801069949886232,-0.8164794590577595,-0.0672945132534559,0.16142509182712056,-0.06215685125590191,0.18293343531564982,0.12814833259999084,-1.6435395936772805,-2.6826527901876123,-0.2056303921851143,0.13542239699533204,-0.050961011055553444,-0.08801069949886232,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4000148,0.0,1.0,0.0,1.0,0.8918482916244165,0.48218223309515246,0.5386333588162646,0.36261517803823534,-0.04456448935873202,-0.020522920242918987,-0.930646575607087,0.6349934562503212,-0.13166453478803233,-0.22851089924538423,-0.1278559121780652,-0.5110988613283782,-1.1191716433893173,-1.5424051100993301,-0.10266741298268196,0.4023969598863509,-0.04890058395448963,0.19186493388402237,0.07935619622155522,-1.9112912253149994,-2.9819253770456315,-0.5792664318821786,0.14928465372997263,-0.04353873647985789,-0.05818593526636712,-1.5424051100993301,-0.10266741298268196,0.4023969598863509,-0.04890058395448963,0.19186493388402237,0.07935619622155522,-1.9112912253149994,-2.9819253770456315,-0.5792664318821786,0.14928465372997263,-0.04353873647985789,-0.05818593526636712,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4166815,0.0,1.0,0.0,1.0,0.8820675761144579,0.47607081583807426,0.5355713737529175,0.3537616256046571,-0.04756126887545403,-0.0213184963439809,-0.9338823050396334,0.6886760412893352,-0.11809718269802826,-0.254890181636913,-0.05294133518482524,-0.25248332597749246,-1.1444864927870393,-1.8360590450568244,0.10352895513737691,0.7638978357945404,-0.0364272591241191,0.2001064433065648,0.031185651855869488,-2.147700907263332,-3.126249051038643,-0.7228899638911853,0.166284675676381,-0.03969193245390037,-0.03566842734646087,-1.8360590450568244,0.10352895513737691,0.7638978357945404,-0.0364272591241191,0.2001064433065648,0.031185651855869488,-2.147700907263332,-3.126249051038643,-0.7228899638911853,0.166284675676381,-0.03969193245390037,-0.03566842734646087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4333482,0.0,1.0,0.0,1.0,0.8715063160281087,0.46938429698135453,0.5325443864593853,0.34467220828670375,-0.048399657090734405,-0.022115871508550117,-0.9372136524057275,0.7499735992954493,-0.11686425734167816,-0.2669729872999525,-0.057070688874699994,-0.10382894244795458,-1.150698602974215,-2.3375309803759605,0.5185371160136898,1.2057055999576436,-0.028699430592551457,0.20556136375306958,0.008071557916988669,-2.3186083982514103,-3.106874043604133,-0.7262050109762156,0.17351236257389926,-0.03650375563676632,-0.01766076256585482,-2.3375309803759605,0.5185371160136898,1.2057055999576436,-0.028699430592551457,0.20556136375306958,0.008071557916988669,-2.3186083982514103,-3.106874043604133,-0.7262050109762156,0.17351236257389926,-0.03650375563676632,-0.01766076256585482,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.4500149,0.0,1.0,0.0,1.0,0.8599285395918203,0.4622735895777256,0.5293402272348533,0.33570354152404785,-0.04907772425972046,-0.02195313654675063,-0.9404321182230319,0.784803708485569,-0.11156407166225547,-0.2612840419445657,-0.17819974246647757,-0.10754204948898612,-1.1124142512674844,-2.893688576567204,0.8705169199779649,1.6301827322799542,-0.027211565090389512,0.20489631989641158,0.020933626323936045,-2.3715193110171873,-2.9653936991823393,-0.6707536608352879,0.16362097730196706,-0.032912819047076394,-0.0058020585243229806,-2.893688576567204,0.8705169199779649,1.6301827322799542,-0.027211565090389512,0.20489631989641158,0.020933626323936045,-2.3715193110171873,-2.9653936991823393,-0.6707536608352879,0.16362097730196706,-0.032912819047076394,-0.0058020585243229806,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.466681599999999,0.0,1.0,0.0,1.0,0.8483367959658943,0.4551532171676368,0.5266546329531994,0.3270518579463034,-0.050666123244935794,-0.020825495142467964,-0.9434173651789918,0.7904538210961052,-0.09335385962398664,-0.2170727019989398,-0.310558759973509,-0.19170891560833533,-1.105934523065736,-3.2646061343146626,0.8306362217785818,1.6528424692990746,-0.02853262117891015,0.2087444926986134,0.04726911705699534,-2.296588685078606,-2.7559727030294017,-0.39787920405062566,0.1545639898497155,-0.03294176287079021,-0.003072950195047784,-3.2646061343146626,0.8306362217785818,1.6528424692990746,-0.02853262117891015,0.2087444926986134,0.04726911705699534,-2.296588685078606,-2.7559727030294017,-0.39787920405062566,0.1545639898497155,-0.03294176287079021,-0.003072950195047784,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.483348299999999,0.0,1.0,1.0,1.0,0.8368319293155149,0.44798899799118175,0.5250065349145898,0.31798377036590836,-0.053395060357636505,-0.019038925967024015,-0.9463999200186504,0.7691827446259598,-0.06019322669772929,-0.18342644321976992,-0.3764164741317984,-0.22362575119095285,-1.1697530057080832,-3.6198845501610926,0.6170804898793498,1.500797949740252,-0.027261302306684373,0.2231101003160914,0.0582981906358217,-1.1361241417892625,-1.407481224907574,-0.10397118560375995,0.16062093175760978,-0.036702541827880485,-0.001942294620133699,-3.6198845501610926,0.6170804898793498,1.500797949740252,-0.027261302306684373,0.2231101003160914,0.0582981906358217,-1.1361241417892625,-1.407481224907574,-0.10397118560375995,0.16062093175760978,-0.036702541827880485,-0.001942294620133699,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.500014999999999,0.0,1.0,1.0,1.0,0.8262728939938949,0.44094473878168594,0.5234772599220673,0.30819229739405657,-0.055816783555863496,-0.01711910644405346,-0.9495309003371131,0.7206908309093647,-0.0328944235508524,-0.16281170527076672,-0.5007217557296288,-0.2938726721224977,-1.2490242455467078,-3.78224790084272,0.5360143835528867,1.371366795572245,-0.027081481653838644,0.242428163570846,0.0810450979495179,-0.04490503425098801,-0.19209259695676248,-0.06987647691388471,0.16572607032656236,-0.03989375573554789,0.00041479941081369457,-3.78224790084272,0.5360143835528867,1.371366795572245,-0.027081481653838644,0.242428163570846,0.0810450979495179,-0.04490503425098801,-0.19209259695676248,-0.06987647691388471,0.16572607032656236,-0.03989375573554789,0.00041479941081369457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5166816999999995,0.0,1.0,1.0,1.0,0.8163602439280321,0.43449916827579677,0.522418466425442,0.29766317887656674,-0.0602468766851523,-0.013766943171420023,-0.952668576718313,0.6478564436490529,-0.0081169326122629,-0.14399802549442842,-0.8458783617546629,-0.3650887580532602,-1.2875800185408022,-3.6709835668006683,0.3980806824197192,1.1132660218502821,-0.029101531081847307,0.2648662200818169,0.12697675748224216,-0.06773435772598892,-0.18715073003624824,-0.11181752858551605,0.16087199325645557,-0.031420117419267826,0.024333646892188164,-3.6709835668006683,0.3980806824197192,1.1132660218502821,-0.029101531081847307,0.2648662200818169,0.12697675748224216,-0.06773435772598892,-0.18715073003624824,-0.11181752858551605,0.16087199325645557,-0.031420117419267826,0.024333646892188164,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5333483999999995,0.0,1.0,1.0,1.0,0.8079956808315313,0.4286572921617037,0.5213725111329957,0.2867959965803356,-0.06547400941925527,-0.006784933119931725,-0.9557275632305566,0.6290328461591285,0.03998581124640313,-0.1835026216571055,-1.1006799016077062,-0.2895612772468782,-1.2578451624967677,-3.48511535957281,0.1602530698761625,0.8901886835198912,-0.02405898752113956,0.2727599802038937,0.14368837530527379,-0.07882731069129975,-0.16794472238858307,-0.1290400328967066,0.029600731271831684,-0.1771578944276909,0.18480608356538683,-3.48511535957281,0.1602530698761625,0.8901886835198912,-0.02405898752113956,0.2727599802038937,0.14368837530527379,-0.07882731069129975,-0.16794472238858307,-0.1290400328967066,0.029600731271831684,-0.1771578944276909,0.18480608356538683,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5500150999999995,0.0,1.0,1.0,0.0,0.799011641724725,0.421600770936956,0.5190276724287579,0.2763863542242748,-0.06996538814338692,0.0010029402644424062,-0.958495916408299,0.6740319128733362,0.0443507985687544,-0.23656840029048803,-1.2326613297484397,-0.12183019781329726,-1.1976022711960437,-3.2624543197458515,-0.03961931775896391,0.6531918287548443,-0.01423641425218395,0.2706637417881395,0.1347831474167327,-0.07841904437677004,-0.14461526944317524,-0.12357236606468625,-0.12601310638830124,-0.463680444619271,0.42719789340067327,-3.2624543197458515,-0.03961931775896391,0.6531918287548443,-0.01423641425218395,0.2706637417881395,0.1347831474167327,-0.07841904437677004,-0.14461526944317524,-0.12357236606468625,-0.12601310638830124,-0.463680444619271,0.42719789340067327,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5666818,0.0,1.0,1.0,0.0,0.7889015299784264,0.41520771633300174,0.5165050737704941,0.26620775330350266,-0.07309227408546018,0.010935106972902866,-0.9610782356216421,0.6859166888962596,-0.007999146178980315,-0.21469803890519024,-1.4514781781906994,0.25858375259948696,-1.088021087837329,-3.037878583866283,-0.13597759371240814,0.2656530082967552,-0.002230162938026258,0.26843836697466783,0.10296439734313367,-0.06572702379690437,-0.10401992295799466,-0.10213599936542364,-0.22531989778757136,-0.7198236980056525,0.6213310636268253,-3.037878583866283,-0.13597759371240814,0.2656530082967552,-0.002230162938026258,0.26843836697466783,0.10296439734313367,-0.06572702379690437,-0.10401992295799466,-0.10213599936542364,-0.22531989778757136,-0.7198236980056525,0.6213310636268253,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.5833485,0.0,1.0,1.0,0.0,0.7784494397977856,0.4099656125209671,0.5150443667918803,0.25709329015328486,-0.07241591492385001,0.024037120138911138,-0.9633697069553975,0.7114946522371208,-0.027818990782258163,-0.13446944559352578,-1.4262469627120997,0.6564250770353253,-0.9465490497372229,-2.7788658546212743,-0.10463389096421284,-0.18727727524545762,0.010786677875499601,0.2502825975259052,0.04519276346117532,-0.03945116026442734,-0.06952805176700803,-0.05616825737756159,-0.4203964951455413,-0.9330436701183631,0.6867327225453004,-2.7788658546212743,-0.10463389096421284,-0.18727727524545762,0.010786677875499601,0.2502825975259052,0.04519276346117532,-0.03945116026442734,-0.06952805176700803,-0.05616825737756159,-0.4203964951455413,-0.9330436701183631,0.6867327225453004,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6000152,0.0,1.0,1.0,0.0,0.7674320028926676,0.4042214596624751,0.5151683769679959,0.24899737650756854,-0.06904676349622817,0.035479203857746285,-0.9653880447968396,0.7872752168121725,-0.012934326182673817,-0.0679375752636404,-1.1545955222919098,0.8087877749547712,-0.8719429134848748,-2.495420319259146,-0.025140673191985857,-0.6302232589990586,0.020285019717579792,0.22852977232307728,-0.000995992113366335,-0.018560166974296934,-0.06520036095175595,-0.014567320130201563,-0.7265650346926547,-1.2430510544941937,0.5523401180860088,-2.495420319259146,-0.025140673191985857,-0.6302232589990586,0.020285019717579792,0.22852977232307728,-0.000995992113366335,-0.018560166974296934,-0.06520036095175595,-0.014567320130201563,-0.7265650346926547,-1.2430510544941937,0.5523401180860088,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6166819,0.0,1.0,1.0,0.0,0.755164084674894,0.3976745731993929,0.5158862605253938,0.24124538336640994,-0.06472348091584776,0.04495828141877016,-0.9672591632827268,0.8571968735325526,-0.024117882562201876,-0.03113163755103121,-1.005329735268002,0.8799143240547995,-0.8445375195159723,-2.2334932189391457,0.08294928383169475,-1.0737857868161915,0.02683462615507066,0.21946864963890755,-0.023129284871163402,-0.00852734064841069,-0.06638691087328305,0.006539279710349104,-1.0264694384378779,-1.6444607133389364,0.3882390124529054,-2.2334932189391457,0.08294928383169475,-1.0737857868161915,0.02683462615507066,0.21946864963890755,-0.023129284871163402,-0.00852734064841069,-0.06638691087328305,0.006539279710349104,-1.0264694384378779,-1.6444607133389364,0.3882390124529054,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6333486,0.0,1.0,1.0,0.0,0.7419010503811894,0.3914851527000458,0.5171963837606717,0.23363054323564386,-0.059536247191239865,0.054304894099236015,-0.968980486395197,0.9172769102458672,-0.0715651249484413,-0.007982479929129066,-1.0002057826699309,0.920710226011533,-0.894660561425397,-1.8869242788299219,0.24858949422986396,-1.513969264962274,0.033009294185001876,0.229303446446298,-0.02467747051024394,-0.008742201878698843,-0.07353681306971163,0.009881166205082309,-1.207428719635041,-2.0261114688282076,0.333903435470308,-1.8869242788299219,0.24858949422986396,-1.513969264962274,0.033009294185001876,0.229303446446298,-0.02467747051024394,-0.008742201878698843,-0.07353681306971163,0.009881166205082309,-1.207428719635041,-2.0261114688282076,0.333903435470308,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6500153,0.0,1.0,1.0,0.0,0.7270406462588838,0.38576470350095793,0.5186930177253628,0.2249722363608488,-0.05456663328615974,0.06381468315446542,-0.9707407798235878,0.9678352216400232,-0.10193331181587756,0.021789517380175136,-0.9149775782607251,0.9194331100365774,-0.9503206891294699,-1.4806536596568325,0.34386347718278276,-1.9463751203197854,0.03940498049174492,0.23614603298903472,-0.02839064001311363,-0.00925389882581382,-0.08728334656626666,0.015526217044483516,-1.4264569457607725,-2.278608184690207,0.36316041618456196,-1.4806536596568325,0.34386347718278276,-1.9463751203197854,0.03940498049174492,0.23614603298903472,-0.02839064001311363,-0.00925389882581382,-0.08728334656626666,0.015526217044483516,-1.4264569457607725,-2.278608184690207,0.36316041618456196,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.666682,0.0,1.0,1.0,0.0,0.7117349551062686,0.38012344433180445,0.520908292612894,0.2164362875564836,-0.04911628234921139,0.07168696336926164,-0.9724216696062742,0.9851491001929992,-0.12061036660724489,0.05418122762768739,-0.7977614149669114,0.9376438138433062,-1.0214473388519532,-1.0823022482838356,0.14420775430144178,-2.2983634260444323,0.04782392626126942,0.24488962986612814,-0.03791619235412669,-0.008762120107729986,-0.10467679339391235,0.025662041577859836,-1.6597479848125802,-2.3428695514701743,0.39856456029516474,-1.0823022482838356,0.14420775430144178,-2.2983634260444323,0.04782392626126942,0.24488962986612814,-0.03791619235412669,-0.008762120107729986,-0.10467679339391235,0.025662041577859836,-1.6597479848125802,-2.3428695514701743,0.39856456029516474,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.6833487,0.0,1.0,1.0,0.0,0.6960018899838707,0.37509961568894495,0.5232355974325364,0.20663953606723004,-0.04348022954297746,0.07929427888827799,-0.9742289202792114,1.0078172558052352,-0.15084851144195716,0.0699987370287956,-0.8157804781353963,0.963208692518961,-1.1768573681296601,-0.583345666611315,-0.27813431272095696,-2.407842001898034,0.058885157459606347,0.2732661805911167,-0.032329721412036584,-0.01664010341899955,-0.12734924315127227,0.022862330037834538,-1.8446752770731198,-2.3963315671020755,0.3284143292479743,-0.583345666611315,-0.27813431272095696,-2.407842001898034,0.058885157459606347,0.2732661805911167,-0.032329721412036584,-0.01664010341899955,-0.12734924315127227,0.022862330037834538,-1.8446752770731198,-2.3963315671020755,0.3284143292479743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7000154,0.0,1.0,1.0,0.0,0.6794211964289193,0.3705829857969052,0.5258158239082071,0.1954630064703783,-0.03784606825407058,0.08740311920605648,-0.9760750908471751,1.050713621562628,-0.16435043402853883,0.09751674702792128,-0.6883721937187613,0.8763139152280535,-1.2697534732521865,-0.14994655978586952,-0.42561428917254657,-1.9311325626746885,0.06688305606511619,0.28098570377688226,-0.02630080992524418,-0.02559463132259539,-0.14943440428922652,0.019717396673501336,-2.0316109416488595,-2.3618563712707084,0.20311897058921158,-0.14994655978586952,-0.42561428917254657,-1.9311325626746885,0.06688305606511619,0.28098570377688226,-0.02630080992524418,-0.02559463132259539,-0.14943440428922652,0.019717396673501336,-2.0316109416488595,-2.3618563712707084,0.20311897058921158,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7166821,0.0,1.0,1.0,0.0,0.6620516619113577,0.36597325873739284,0.528833882695043,0.18427050991458926,-0.033351317013476656,0.09256123274371478,-0.9779388973868703,1.0780584308614396,-0.16759738852818457,0.10356913033060663,-0.3136905008862433,0.7323460194749349,-1.297207357567277,0.01898425471395309,-0.2400761237017987,-0.7695350426126547,0.07322706223724709,0.26681988835597537,-0.04129206301550132,-0.02884492934291581,-0.17686266589444002,0.033212549769492165,-2.1888574568880816,-2.256002058692434,0.06190526930021356,0.01898425471395309,-0.2400761237017987,-0.7695350426126547,0.07322706223724709,0.26681988835597537,-0.04129206301550132,-0.02884492934291581,-0.17686266589444002,0.033212549769492165,-2.1888574568880816,-2.256002058692434,0.06190526930021356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7333488,0.0,1.0,1.0,0.0,0.6443701914230449,0.3619385397819799,0.5313996074634623,0.1730020961077789,-0.028916963122494015,0.09404603226457373,-0.9799946060062668,1.0706590360539074,-0.16269661956690812,0.09678113068866713,0.13542781238257792,0.5835102831825643,-1.3156592639239273,0.005229858421414019,-0.005135746168654018,-0.18758500019523974,0.07894678532482748,0.24837532467776774,-0.06587438331882771,-0.031273353926284345,-0.20726301245124895,0.05374007626947732,-2.3068381724849636,-2.1117841073523986,-0.09552026235247404,0.005229858421414019,-0.005135746168654018,-0.18758500019523974,0.07894678532482748,0.24837532467776774,-0.06587438331882771,-0.031273353926284345,-0.20726301245124895,0.05374007626947732,-2.3068381724849636,-2.1117841073523986,-0.09552026235247404,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7500155,0.0,1.0,1.0,0.0,0.6270373420050421,0.3581180298921552,0.5339127912078271,0.16191631224601805,-0.025539668053041153,0.09140931269242379,-0.9822296934716895,1.0826904364402687,-0.154707597146093,0.10301482499484955,0.4631707429721601,0.411306069601306,-1.3306939950243208,-0.1724388989615081,0.24021367777828054,-0.21185814309557935,-0.1323241990477848,0.19176028409123128,0.05687611404676228,-0.039110948999221254,-0.2288218339339977,0.06250231614321303,-2.3602309178730554,-1.9166578039973883,-0.20694688624758606,-0.1724388989615081,0.24021367777828054,-0.21185814309557935,-0.1323241990477848,0.19176028409123128,0.05687611404676228,-0.039110948999221254,-0.2288218339339977,0.06250231614321303,-2.3602309178730554,-1.9166578039973883,-0.20694688624758606,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7666822,1.0,0.0,1.0,0.0,0.6088775405748297,0.35450281513228543,0.5364826363328513,0.15078010119792484,-0.022980701202740397,0.08701637187228482,-0.9844619847821235,1.0845978190537746,-0.1377252137505965,0.097385287891581,0.5998626257835759,0.27548958901324716,-1.2998538783244349,-0.2317137272862699,0.22574333277987496,-0.03786859491554386,-0.5650864860827712,0.1695762601102022,0.17062328754200587,-0.04733373432450915,-0.23099501125073793,0.06058471213760985,-2.4039988862700743,-1.7116385927947448,-0.30961048968775173,-0.2317137272862699,0.22574333277987496,-0.03786859491554386,-0.5650864860827712,0.1695762601102022,0.17062328754200587,-0.04733373432450915,-0.23099501125073793,0.06058471213760985,-2.4039988862700743,-1.7116385927947448,-0.30961048968775173,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.7833489,1.0,0.0,1.0,0.0,0.5914535781194789,0.35101935063557477,0.5386118960414261,0.14041377501020358,-0.021410495658287766,0.0817713527607023,-0.9864780830463165,1.0458077866267903,-0.12609115569507967,0.07298309166131796,0.6304123421786186,0.0929134093666732,-1.2822658724936322,-0.15894653880861165,0.10919824351768523,0.07751276989973005,-1.0082933808453274,0.18362383890143777,0.22967765904722895,-0.0612202581378899,-0.227745329201572,0.043841510708125794,-2.462511121057335,-1.464447791715992,-0.3894094923300714,-0.15894653880861165,0.10919824351768523,0.07751276989973005,-1.0082933808453274,0.18362383890143777,0.22967765904722895,-0.0612202581378899,-0.227745329201572,0.043841510708125794,-2.462511121057335,-1.464447791715992,-0.3894094923300714,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8000156,1.0,0.0,1.0,0.0,0.574432763009237,0.3483266349392846,0.5402560498415386,0.12978629663695537,-0.021724888653181878,0.07643174845064864,-0.9883530413000448,1.007615833326192,-0.13079881322926412,0.017540262634652387,0.5874962383225169,-0.020771146471158686,-1.3081618588383062,-0.16531426044096473,0.11483043906446219,0.0900510811130238,-1.3110931749445869,0.3588278862253204,0.3994571924653703,-0.07495041121410351,-0.22638476059012938,0.02828571149649972,-2.461252467880628,-1.162583061282814,-0.39649061470300634,-0.16531426044096473,0.11483043906446219,0.0900510811130238,-1.3110931749445869,0.3588278862253204,0.3994571924653703,-0.07495041121410351,-0.22638476059012938,0.02828571149649972,-2.461252467880628,-1.162583061282814,-0.39649061470300634,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8166823,1.0,0.0,1.0,0.0,0.557962180844191,0.3463681271480222,0.5406484984702505,0.1191042221599693,-0.022142757455746207,0.07157673355465566,-0.9900508339320616,0.9627719342705414,-0.08310186857896229,-0.035590769775142576,0.6609036997257656,-0.1303443545302011,-1.1553754695621836,-0.14622258248070397,0.09269414024861374,0.10864611852671673,-0.949915204285468,0.6610180639791889,0.5111723958751628,-0.07399618472498484,-0.2067356049878489,0.02630041955065124,-2.4140400299123947,-0.8594807000314685,-0.4131754076857565,-0.14622258248070397,0.09269414024861374,0.10864611852671673,-0.949915204285468,0.6610180639791889,0.5111723958751628,-0.07399618472498484,-0.2067356049878489,0.02630041955065124,-2.4140400299123947,-0.8594807000314685,-0.4131754076857565,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.833349,1.0,0.0,1.0,0.0,0.5425655349525951,0.34348124833729976,0.5403501271378682,0.11111662168916142,-0.023975603007930602,0.06485865203297135,-0.9913988209097587,0.9170885719835131,-0.053519291948760817,-0.06703531326224203,0.6818342863243101,-0.2790200262369707,-0.9670162136208578,-0.12515722393151255,0.06771698989947124,0.12724181778205307,-0.6566149938148551,0.6819127784616585,0.7800782554901533,-0.07224015108174497,-0.1790290356625764,0.01595247795944164,-2.2607960639279807,-0.5734073143576403,-0.482381608886414,-0.12515722393151255,0.06771698989947124,0.12724181778205307,-0.6566149938148551,0.6819127784616585,0.7800782554901533,-0.07224015108174497,-0.1790290356625764,0.01595247795944164,-2.2607960639279807,-0.5734073143576403,-0.482381608886414,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8500157,1.0,0.0,1.0,0.0,0.5276565919491494,0.3415382615117915,0.5396869013996182,0.10369420147434179,-0.02652948569815142,0.05941525266823318,-0.9924784767034297,0.879241916364883,-0.08471009630770648,-0.11129111905259462,0.5513755188240437,-0.3157454700028524,-0.9727291930109762,-0.1278508310845111,0.07877287807554813,0.12049694033882648,-1.2656911486009264,0.5542114007340442,1.1568976377381672,-0.07963830469526674,-0.1703677763774423,0.001966889813770697,-1.8988234803649713,-0.31829889759155167,-0.531722081209857,-0.1278508310845111,0.07877287807554813,0.12049694033882648,-1.2656911486009264,0.5542114007340442,1.1568976377381672,-0.07963830469526674,-0.1703677763774423,0.001966889813770697,-1.8988234803649713,-0.31829889759155167,-0.531722081209857,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8666824,1.0,0.0,1.0,0.0,0.5131155823312277,0.3405165234945819,0.5382026068392666,0.09558028207449411,-0.02919899665734154,0.05476160201709689,-0.9934852767994531,0.8310377699920026,-0.09908340284074241,-0.14124745568553698,0.4653515444673938,-0.36396467152566436,-0.9605984659782849,-0.12792967025121854,0.08436745425520424,0.1194000092535287,-1.8383583937139756,0.1160994653514768,1.1392569239051884,-0.08547572610514055,-0.16212447326776297,-0.00974638909207047,-1.2649748209139657,-0.15502345584282742,-0.47030899734116444,-0.12792967025121854,0.08436745425520424,0.1194000092535287,-1.8383583937139756,0.1160994653514768,1.1392569239051884,-0.08547572610514055,-0.16212447326776297,-0.00974638909207047,-1.2649748209139657,-0.15502345584282742,-0.47030899734116444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.8833491,1.0,0.0,1.0,1.0,0.4995695124696323,0.33989742867143924,0.5367098984898963,0.08834263651714863,-0.03269109212869595,0.05067225672148193,-0.9942631409578575,0.7655330682843448,-0.07771723709972994,-0.1475887298809816,0.48668774052897146,-0.46539797901020974,-0.8372447591967397,-0.11426846600075037,0.06779464027877777,0.1342331824191166,-2.019664918188136,-0.19537719702787038,1.181966297541617,-0.08400378543458019,-0.14473236115973553,-0.016923485158315453,-0.39938672977701933,-0.09390995464749896,-0.2653618068050465,-0.11426846600075037,0.06779464027877777,0.1342331824191166,-2.019664918188136,-0.19537719702787038,1.181966297541617,-0.08400378543458019,-0.14473236115973553,-0.016923485158315453,-0.39938672977701933,-0.09390995464749896,-0.2653618068050465,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.900015799999999,1.0,0.0,1.0,1.0,0.4872402426696583,0.338953365632923,0.5350251274694808,0.08236515837766223,-0.036914141180176746,0.04556515093325177,-0.9948754413929327,0.7223131689308226,-0.07092058846567262,-0.15605890962258337,0.5443740059658366,-0.5418834668287866,-0.7041665140407449,-0.098090363710244,0.04817982997014667,0.14857599451415082,-2.2967606103329827,0.030531059407817186,1.2281263208473066,-0.07901148826967169,-0.12873948538976734,-0.017649908976580368,0.05069376133279196,-0.09584441717531135,-0.13493348163545243,-0.098090363710244,0.04817982997014667,0.14857599451415082,-2.2967606103329827,0.030531059407817186,1.2281263208473066,-0.07901148826967169,-0.12873948538976734,-0.017649908976580368,0.05069376133279196,-0.09584441717531135,-0.13493348163545243,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.916682499999999,1.0,0.0,1.0,1.0,0.4750840472916852,0.3386326496838631,0.5333601509281609,0.07741174379920374,-0.0414688904314437,0.04047542196158943,-0.9953137662392613,0.7428300208531367,-0.09078469675701661,-0.13226807021856685,0.443035489692909,-0.5175081092304,-0.5925427604068252,-0.08369940813517517,0.04220850964033067,0.13313253054221488,-2.374079404920409,0.21435511031943635,0.9123162110617324,-0.07160181929525425,-0.1069611786609856,-0.02189321970316467,0.037345104298106425,-0.08146794969682163,-0.11884685779257743,-0.08369940813517517,0.04220850964033067,0.13313253054221488,-2.374079404920409,0.21435511031943635,0.9123162110617324,-0.07160181929525425,-0.1069611786609856,-0.02189321970316467,0.037345104298106425,-0.08146794969682163,-0.11884685779257743,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.933349199999999,1.0,0.0,1.0,1.0,0.4620133690022976,0.33836152370870126,0.5327978808191804,0.07318775174156118,-0.04532251875111719,0.037139134255931724,-0.9955953530404761,0.7986693817756498,-0.07419647631749199,-0.09372794806213806,0.1669959407636647,-0.3129104098974227,-0.4245794189512845,-0.059601124435188675,0.04094772944724336,0.07238872861256576,-2.381083809198309,0.18028768164804992,0.7450619616842522,-0.050825929505756845,-0.06782039313656296,-0.02222090047997988,0.029788631689368926,-0.0526316109269755,-0.06246373136993952,-0.059601124435188675,0.04094772944724336,0.07238872861256576,-2.381083809198309,0.18028768164804992,0.7450619616842522,-0.050825929505756845,-0.06782039313656296,-0.02222090047997988,0.029788631689368926,-0.0526316109269755,-0.06246373136993952,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9500158999999995,1.0,0.0,1.0,1.0,0.4482052205784677,0.3373135474564851,0.5327144688282085,0.07068367306996577,-0.04671322927673814,0.03699894376977159,-0.9957172142389618,0.828430385568941,-0.042261378159045515,-0.040181789087461985,-0.0007521725557506874,-0.015039754965428552,-0.30671993667930186,-0.03708518975662355,0.04062332648577476,0.008602867997386807,-2.8309816859218313,-0.09869789119285222,0.6213564962890896,-0.17880367106244793,-0.14530279504609173,0.17057732739522966,0.03453322592815237,-0.033206872166397124,-0.007469714025460905,-0.03708518975662355,0.04062332648577476,0.008602867997386807,-2.8309816859218313,-0.09869789119285222,0.6213564962890896,-0.17880367106244793,-0.14530279504609173,0.17057732739522966,0.03453322592815237,-0.033206872166397124,-0.007469714025460905,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9666825999999995,1.0,0.0,0.0,1.0,0.43447038823523937,0.3358596390931362,0.5340055269396798,0.06810665087159484,-0.04576206975271089,0.03688912959028067,-0.9959450332207467,0.8491659111927643,-0.0413586012951766,-0.031099135113262302,-0.10170530565828584,0.20839588373872597,-0.3005452775858641,-0.02963351623809235,0.04968169604102361,-0.03537628431825385,-3.46823578883291,-0.3462399366669384,0.22455233574134456,-0.45885183341287616,-0.22028509473895483,0.5161181132670117,0.04786597482736404,-0.028591838579025777,0.02977823160351656,-0.02963351623809235,0.04968169604102361,-0.03537628431825385,-3.46823578883291,-0.3462399366669384,0.22455233574134456,-0.45885183341287616,-0.22028509473895483,0.5161181132670117,0.04786597482736404,-0.028591838579025777,0.02977823160351656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +7.9833492999999995,1.0,0.0,0.0,1.0,0.41999870620515506,0.33480980845031777,0.5342327953886599,0.06549092287638897,-0.04354916273450304,0.038691126407606774,-0.996151296833585,0.8868015180266283,-0.023867704471504714,-0.08668036194711748,-0.29778765232617754,0.29073986482915554,-0.325080775511833,-0.03216868506363618,0.06608046695298182,-0.06602194698865933,-3.8965766115971046,-0.2661803297287496,-0.0795962274356012,-0.7732373644841422,-0.20020791200182947,0.7856689317754797,0.0560300674042066,-0.023298472635284093,0.059532510476621114,-0.03216868506363618,0.06608046695298182,-0.06602194698865933,-3.8965766115971046,-0.2661803297287496,-0.0795962274356012,-0.7732373644841422,-0.20020791200182947,0.7856689317754797,0.0560300674042066,-0.023298472635284093,0.059532510476621114,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.000016,1.0,0.0,0.0,1.0,0.40490951421778154,0.3328957150977716,0.5336165731746607,0.0623089397190022,-0.04146678840540655,0.041915947599975266,-0.9963137833168982,0.9096258021709661,0.0043225999688535355,-0.1405691982922202,-0.5969152356862993,0.3215924956390771,-0.4418434732635842,-0.0482525262449985,0.10081009832697108,-0.0961314246506514,-4.082074414375464,0.09213211563852002,-0.17593326094620124,-1.174163493573456,-0.19699205301058775,0.9620515879901328,0.07157508501858313,-0.024500432528208858,0.09215353176669935,-0.0482525262449985,0.10081009832697108,-0.0961314246506514,-4.082074414375464,0.09213211563852002,-0.17593326094620124,-1.174163493573456,-0.19699205301058775,0.9620515879901328,0.07157508501858313,-0.024500432528208858,0.09215353176669935,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0166827,1.0,0.0,0.0,1.0,0.3896232430918023,0.3311644892462863,0.531913918063898,0.057521819340149334,-0.03913062515262841,0.04863308108379791,-0.9963909162067168,0.9475471998263423,0.01992288428914013,-0.13960074282479096,-0.6729536538774754,0.32242522481982616,-0.5431943177748114,-0.06004863035981428,0.1204143095715783,-0.10023138058355219,-4.041442638055171,0.5152907255742302,-0.2882247732008503,-1.694442290912902,-0.10513321850472493,1.13720569802004,0.0827599176730312,-0.03402003806214827,0.09797333117737715,-0.06004863035981428,0.1204143095715783,-0.10023138058355219,-4.041442638055171,0.5152907255742302,-0.2882247732008503,-1.694442290912902,-0.10513321850472493,1.13720569802004,0.0827599176730312,-0.03402003806214827,0.09797333117737715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0333494,1.0,0.0,0.0,1.0,0.37331498231036897,0.3289284363677284,0.531218360120309,0.052586365109825894,-0.037210421327309604,0.05304907730737095,-0.996511843454967,0.9940658278975134,0.02059318451429376,-0.1003436714633393,-0.5121553748013272,0.4109325011807826,-0.6780460062422019,-0.06795672094571034,0.13283667524454817,-0.0944362919183765,-3.6540708487942863,0.7528543179905496,-0.42239975570430305,-2.249557445977779,-0.10430200717466337,1.4817058550126139,0.10187946968181963,-0.05850333684643671,0.08894563574098592,-0.06795672094571034,0.13283667524454817,-0.0944362919183765,-3.6540708487942863,0.7528543179905496,-0.42239975570430305,-2.249557445977779,-0.10430200717466337,1.4817058550126139,0.10187946968181963,-0.05850333684643671,0.08894563574098592,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0500161,1.0,0.0,0.0,1.0,0.3565651878429216,0.32722263459819095,0.5307944513884607,0.04556951162710344,-0.0333646058678295,0.05707245193341547,-0.9967712665981397,1.0136312958566593,0.014485317777444884,-0.05129396812355258,-0.24686863802441109,0.5429593526214036,-0.8353363488833009,-0.07524101740172312,0.1425221974295453,-0.08553832794435752,-3.098553367208691,0.8292698065117337,-0.8437088239223023,-2.7838530072948737,-0.24430794643724818,1.6897527135687436,0.1251269532489374,-0.08985851319833857,0.07386671114820928,-0.07524101740172312,0.1425221974295453,-0.08553832794435752,-3.098553367208691,0.8292698065117337,-0.8437088239223023,-2.7838530072948737,-0.24430794643724818,1.6897527135687436,0.1251269532489374,-0.08985851319833857,0.07386671114820928,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0666828,1.0,0.0,0.0,1.0,0.3396621619376085,0.32544195832531353,0.5315387025325504,0.03803886555665215,-0.029202726626206203,0.057098014517950095,-0.9972161562083048,1.0329283302259857,0.005284290956005022,-0.006139714418304729,0.23982786708085008,0.6126824374181014,-0.9607018741596911,-0.07833821161392293,0.13278257606752827,-0.04840344284899504,-2.5499329315543657,0.9360216627552597,-1.5408707741606062,-3.1580621447745925,-0.2575181442558079,1.5799621877451853,0.13949380249469703,-0.12648063073530605,0.029781132880451394,-0.07833821161392293,0.13278257606752827,-0.04840344284899504,-2.5499329315543657,0.9360216627552597,-1.5408707741606062,-3.1580621447745925,-0.2575181442558079,1.5799621877451853,0.13949380249469703,-0.12648063073530605,0.029781132880451394,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.0833495,1.0,0.0,0.0,1.0,0.32229250742125,0.324344037779096,0.5324268234179291,0.029118112146162833,-0.02397434411405239,0.05300371102334323,-0.997881742987163,1.0548772870481524,0.0062864949568429696,-0.005830186611109983,0.584010631534925,0.7185213076629884,-1.042677950939661,-0.0769173682004993,0.1261455754274875,-0.03212861448212314,-1.8733820446577163,1.0005103469290635,-2.163119530346414,-3.326365280464485,-0.15483891029168975,1.373597936515309,0.15105862201295447,-0.15308047955625317,0.007352577390508188,-0.0769173682004993,0.1261455754274875,-0.03212861448212314,-1.8733820446577163,1.0005103469290635,-2.163119530346414,-3.326365280464485,-0.15483891029168975,1.373597936515309,0.15105862201295447,-0.15308047955625317,0.007352577390508188,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.1000162,1.0,0.0,0.0,1.0,0.3046013090240402,0.32312146080072235,0.5328971121328777,0.02029143615852497,-0.01790502099160993,0.04730878772763319,-0.9985136686323609,1.0955444352877817,0.030132994790153633,0.007813642397009754,0.9752503084005231,0.8501948889983094,-1.006420749011941,-0.06260522170310479,0.10055590411689028,-0.01755401161203589,-0.8812327441490116,0.8252466144966828,-2.573597673757752,-3.295662467799091,-0.06865984913195412,1.176455771507488,0.15114325313143673,-0.16911380248403204,-0.013251941073697258,-0.06260522170310479,0.10055590411689028,-0.01755401161203589,-0.8812327441490116,0.8252466144966828,-2.573597673757752,-3.295662467799091,-0.06865984913195412,1.176455771507488,0.15114325313143673,-0.16911380248403204,-0.013251941073697258,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.116682899999999,1.0,0.0,0.0,1.0,0.2858765872168327,0.32177882994996826,0.5338259830216466,0.011968534432298172,-0.010334677232550075,0.036742957412472105,-0.9991996315604941,1.1709666972706492,0.05219917452606171,0.004509410248665045,1.5216085344804302,0.9031339696012632,-0.949918264084293,-0.05055611894127247,0.06223534764337026,0.02319560405541153,-0.16157087763543274,0.18653367224245296,-1.7665238278797784,-3.165105108338237,-0.06559128931370402,0.9928315760396158,0.14511185859379613,-0.18962686057994066,-0.05687326892378986,-0.05055611894127247,0.06223534764337026,0.02319560405541153,-0.16157087763543274,0.18653367224245296,-1.7665238278797784,-3.165105108338237,-0.06559128931370402,0.9928315760396158,0.14511185859379613,-0.18962686057994066,-0.05687326892378986,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.133349599999999,1.0,0.0,0.0,1.0,0.26563205964706227,0.3204124671908046,0.5336905934296519,0.004145126736764927,-0.003183334105049175,0.021984667999402692,-0.9997446467379898,1.2573519184798068,0.05552075404074264,0.003624103412868441,1.8775707072070964,0.7831398600611869,-0.761294714188367,-0.03639737798890091,0.014898960542797924,0.07262154043249872,0.07113711353293672,-0.3213745110801926,-0.4653522161592317,-2.989793666046101,-0.04337035943969076,0.6721875973392487,0.11762672112874853,-0.1859630662870988,-0.10016023854411062,-0.03639737798890091,0.014898960542797924,0.07262154043249872,0.07113711353293672,-0.3213745110801926,-0.4653522161592317,-2.989793666046101,-0.04337035943969076,0.6721875973392487,0.11762672112874853,-0.1859630662870988,-0.10016023854411062,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.150016299999999,1.0,0.0,0.0,1.0,0.24398293319272712,0.31957144270969273,0.5341243972679147,-0.0009372447489743864,0.002510200934429944,0.005465203906757081,-0.9999814758333311,1.2905721343160361,0.03504782927492034,0.03598218066862979,1.81133474610381,0.677133070925821,-0.5590076359892991,-0.3240149735559999,0.032042247864557706,0.24105399496625185,0.26711565462422976,0.1746862819274229,-0.3710715941452883,-2.8719898934913783,-0.09685634638217623,0.2629914215148664,0.09069472926381543,-0.16076959823445972,-0.09873126387568068,-0.3240149735559999,0.032042247864557706,0.24105399496625185,0.26711565462422976,0.1746862819274229,-0.3710715941452883,-2.8719898934913783,-0.09685634638217623,0.2629914215148664,0.09069472926381543,-0.16076959823445972,-0.09873126387568068,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.166682999999999,0.0,1.0,0.0,1.0,0.22260532868973465,0.3193129893862249,0.5346616114835873,-0.005295203228569301,0.008025009446176339,-0.008192443591753406,-0.9999202187745545,1.2722613059486356,0.005805537289585994,0.07613799504638576,1.673896805436637,0.5338915533199329,-0.44782146456504957,-0.9008832161242883,0.10788190032448859,0.48163215655791924,0.21924719971206066,0.3379417404187368,-0.42759085393211976,-2.749915850255677,-0.18616384370819072,-0.09082406138848324,0.07241404478655172,-0.14420124683394808,-0.09779977312730256,-0.9008832161242883,0.10788190032448859,0.48163215655791924,0.21924719971206066,0.3379417404187368,-0.42759085393211976,-2.749915850255677,-0.18616384370819072,-0.09082406138848324,0.07241404478655172,-0.14420124683394808,-0.09779977312730256,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.183349699999999,0.0,1.0,0.0,1.0,0.2015393934795916,0.31986327171036794,0.5359805349244815,-0.008584720514315747,0.011303793142391815,-0.02241328901313434,-0.9996480237112955,1.2195317467756421,-0.03198783037490316,0.12329961438058043,1.6445239633989002,0.2096617158105577,-0.3630894881206703,-1.48891159787551,0.2657647006198106,0.6965617105820081,0.05073992736668843,-0.03841020252886516,-0.19323288226473764,-2.6960655485317098,-0.23870826634342177,-0.3850916718271903,0.047898210660340425,-0.13658681080479174,-0.13152069007199305,-1.48891159787551,0.2657647006198106,0.6965617105820081,0.05073992736668843,-0.03841020252886516,-0.19323288226473764,-2.6960655485317098,-0.23870826634342177,-0.3850916718271903,0.047898210660340425,-0.13658681080479174,-0.13152069007199305,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.200016399999999,0.0,1.0,0.0,1.0,0.18189810762753567,0.3212401072558738,0.5377845098225091,-0.011617469083035181,0.011418527057621307,-0.0355431946412916,-0.9992353741569753,1.1325443358805876,-0.05178577131269957,0.1603691621855248,1.3399397033103624,-0.18830643020902016,-0.362595493797123,-1.947141959141392,0.38102628277521805,0.9917835501986035,0.028885384997574377,-0.021203206316342177,-0.10426375648366133,-2.706641546126013,-0.3595831637427375,-0.6326404637699173,0.027392573134933523,-0.12516369660786736,-0.1484715528081027,-1.947141959141392,0.38102628277521805,0.9917835501986035,0.028885384997574377,-0.021203206316342177,-0.10426375648366133,-2.706641546126013,-0.3595831637427375,-0.6326404637699173,0.027392573134933523,-0.12516369660786736,-0.1484715528081027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2166831,0.0,1.0,0.0,1.0,0.16373178241213632,0.3228116120255846,0.540296474701085,-0.015034335480002993,0.008140898944964114,-0.04461363877668142,-0.9988580068038432,1.0705473445973401,-0.06532604074918402,0.1582696242414762,0.8519567915498372,-0.5651060893422402,-0.49685193111357423,-2.3298579676334548,0.312129012930408,1.2224712599525136,0.02243870492207284,0.0305300579665401,-0.0035110687935599526,-2.5573006254395936,-0.46951417074298424,-0.8834547369562761,0.019838635626498118,-0.11937946936400545,-0.14506765328682425,-2.3298579676334548,0.312129012930408,1.2224712599525136,0.02243870492207284,0.0305300579665401,-0.0035110687935599526,-2.5573006254395936,-0.46951417074298424,-0.8834547369562761,0.019838635626498118,-0.11937946936400545,-0.14506765328682425,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2333498,0.0,1.0,0.0,1.0,0.14622224722726113,0.32492533413065006,0.5422167105504576,-0.02046254405281045,0.0021994645454285824,-0.049514919338046935,-0.9985613248116246,1.0278873619053677,-0.06082387375927795,0.14697306447207606,0.2775885018057377,-0.8600266248441177,-0.650598782928927,-2.7094567461476107,0.5404768505266585,1.3970378075465903,0.02517991115910178,0.09199079479312015,0.09224151608084766,-2.468150888922959,-0.6175759279628888,-1.1790255061908366,0.017800944182112272,-0.10862812500906002,-0.12449481124085371,-2.7094567461476107,0.5404768505266585,1.3970378075465903,0.02517991115910178,0.09199079479312015,0.09224151608084766,-2.468150888922959,-0.6175759279628888,-1.1790255061908366,0.017800944182112272,-0.10862812500906002,-0.12449481124085371,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2500165,0.0,1.0,0.0,1.0,0.12956953043494365,0.3267050756082108,0.5447512741778693,-0.026624057497538323,-0.005696405914246142,-0.04890971383584781,-0.9984320459673375,0.9761285146616678,-0.047254885478152764,0.1479973456653788,-0.22599492292977924,-1.11117257635189,-0.7099867930435753,-3.0673732784017154,1.0706740031628321,1.2521655648363323,0.02373379669076617,0.1345602678823,0.17637255746226752,-2.3891481919778204,-0.7597980197759705,-1.4394300341398611,0.008555403698510086,-0.08815896093085203,-0.10746689987392412,-3.0673732784017154,1.0706740031628321,1.2521655648363323,0.02373379669076617,0.1345602678823,0.17637255746226752,-2.3891481919778204,-0.7597980197759705,-1.4394300341398611,0.008555403698510086,-0.08815896093085203,-0.10746689987392412,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2666832,0.0,1.0,0.0,1.0,0.11388463351592272,0.32871903036352046,0.5472570997584876,-0.03322575101962977,-0.015593404488580934,-0.04531853411560245,-0.9982981146287165,0.9514536553656117,-0.05014959356926918,0.1138576998545423,-0.6532550665854061,-1.2372757864675343,-0.7852786772611273,-3.724811591145217,1.3383785933447094,0.3936980000187357,0.03426102701132428,0.17093753525240948,0.23513504549892617,-2.195557993351693,-0.8677121916727596,-1.6319612136419315,0.008517480211553649,-0.07308935512205239,-0.08265507950242379,-3.724811591145217,1.3383785933447094,0.3936980000187357,0.03426102701132428,0.17093753525240948,0.23513504549892617,-2.195557993351693,-0.8677121916727596,-1.6319612136419315,0.008517480211553649,-0.07308935512205239,-0.08265507950242379,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.2833499,0.0,1.0,0.0,1.0,0.09817791504864555,0.3308544076359359,0.5492680175081219,-0.04083447265797497,-0.025302943339240765,-0.037569822770393446,-0.9981386753944151,0.9162378785800656,-0.04039664670770743,0.10285145977502536,-1.25062932148493,-1.1975073552991538,-0.8568282848290518,-4.009131373747071,1.5933364298892074,-0.08117848728527273,0.056676251414931156,0.21045864483253265,0.2873037612912661,-1.9682074145269495,-0.9613897960515706,-1.763054006009114,0.020557102481531385,-0.046922080587365626,-0.021304210286323785,-4.009131373747071,1.5933364298892074,-0.08117848728527273,0.056676251414931156,0.21045864483253265,0.2873037612912661,-1.9682074145269495,-0.9613897960515706,-1.763054006009114,0.020557102481531385,-0.046922080587365626,-0.021304210286323785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3000166,0.0,1.0,0.0,1.0,0.08377516992153444,0.3328550416324443,0.5520166305894066,-0.04881696280669773,-0.03408417799693508,-0.0240694058207676,-0.9979357878421027,0.8669227617281103,-0.012940648456813475,0.10468381169380903,-1.8400270125515896,-1.0895681726852193,-0.944890295331175,-3.921923375614452,1.9187799270376524,0.11262211139355154,0.08599309485968155,0.24515018707775174,0.33157819381686543,-1.6742366191588924,-0.9911418273631654,-1.7951547383304742,0.0401304898882818,-0.02598767090674303,0.04696401030786809,-3.921923375614452,1.9187799270376524,0.11262211139355154,0.08599309485968155,0.24515018707775174,0.33157819381686543,-1.6742366191588924,-0.9911418273631654,-1.7951547383304742,0.0401304898882818,-0.02598767090674303,0.04696401030786809,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3166833,0.0,1.0,0.0,1.0,0.06977220574589141,0.33430219262287075,0.5546210953627231,-0.05808068208127071,-0.04153196964516268,-0.006638678911103174,-0.9974255149176218,0.8480369832806853,0.03651162276099401,0.08195417215974574,-2.3701590628315934,-0.9541327638254393,-1.0423473939984196,-3.94945428714477,2.0768207432970938,0.16591859398299247,0.11907678210636417,0.27115398540060337,0.36933261082419466,-1.1553715731547323,-0.860272951299192,-1.7242876500404438,-0.190662028503775,0.00014742501000054804,0.24174833357237968,-3.94945428714477,2.0768207432970938,0.16591859398299247,0.11907678210636417,0.27115398540060337,0.36933261082419466,-1.1553715731547323,-0.860272951299192,-1.7242876500404438,-0.190662028503775,0.00014742501000054804,0.24174833357237968,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.33335,0.0,1.0,0.0,0.0,0.05588354691178879,0.33496008058358506,0.5570809697497348,-0.06794463799199287,-0.04749818951667429,0.015512507562452671,-0.9964370578565914,0.819055157602882,0.07434719983162852,0.01183073656509067,-2.7572050336932374,-0.9735916786610221,-1.1574611178201404,-3.688018266604719,2.1277963273296248,0.19945855162071868,0.1475754866120953,0.2852909798119961,0.4210370079371647,-0.75545585218228,-0.5345621861633407,-1.126562564169699,-0.45571579645868615,-0.0912399341278471,0.460193708573525,-3.688018266604719,2.1277963273296248,0.19945855162071868,0.1475754866120953,0.2852909798119961,0.4210370079371647,-0.75545585218228,-0.5345621861633407,-1.126562564169699,-0.45571579645868615,-0.0912399341278471,0.460193708573525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3500167,0.0,1.0,1.0,0.0,0.04254285872303179,0.33548986803558023,0.5575947591643913,-0.07920492173823368,-0.054888552173155185,0.03933683405857919,-0.9945684695882043,0.771988479672578,0.11567389972360925,-0.12815520394349975,-2.9620746794306263,-1.1490233574190027,-1.2906593947979021,-3.2044257841717565,1.9842172651303671,0.1792891810526941,0.173412398212949,0.28644708066204416,0.4799015370574623,-0.4557103146946458,-0.12914753327680317,-0.5098636408347506,-0.4969675175497215,-0.15017270112191303,0.7618181836099474,-3.2044257841717565,1.9842172651303671,0.1792891810526941,0.173412398212949,0.28644708066204416,0.4799015370574623,-0.4557103146946458,-0.12914753327680317,-0.5098636408347506,-0.4969675175497215,-0.15017270112191303,0.7618181836099474,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3666834,0.0,1.0,1.0,0.0,0.029564553341093258,0.33547908436966434,0.5555498066288141,-0.09127070250695098,-0.06347514843819323,0.06494674908590826,-0.9916766026169062,0.7644397629374989,0.1812771816478586,-0.23612990782079107,-2.935902115012604,-1.136736910760857,-1.3578173444224975,-2.4593527396687533,1.6480768836442972,-0.11835084494085495,0.19492688263711155,0.2672299125024649,0.4863927003316375,-0.24218876868027112,0.07530498870436955,-0.40362692065866423,-0.45229965689534246,0.12591315457172636,1.1650319963020686,-2.4593527396687533,1.6480768836442972,-0.11835084494085495,0.19492688263711155,0.2672299125024649,0.4863927003316375,-0.24218876868027112,0.07530498870436955,-0.40362692065866423,-0.45229965689534246,0.12591315457172636,1.1650319963020686,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.3833501,0.0,1.0,1.0,0.0,0.015650095125819996,0.33510661336541947,0.5526552656197347,-0.10353774899895064,-0.07071794362769791,0.08813344506965283,-0.9881859151199508,0.7564100377845504,0.2134281221956872,-0.23926510027797412,-2.323673310740949,-0.7986586682367626,-1.353366684730875,-1.597388392734742,1.2221390284862501,-0.6999386376572296,0.20274332441047693,0.22837327367022478,0.378645282453273,-0.22191128198141788,0.04587369207342927,-0.3047010329022961,-0.36809054345678743,0.4094057437580645,1.5127257478798881,-1.597388392734742,1.2221390284862501,-0.6999386376572296,0.20274332441047693,0.22837327367022478,0.378645282453273,-0.22191128198141788,0.04587369207342927,-0.3047010329022961,-0.36809054345678743,0.4094057437580645,1.5127257478798881,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4000168,0.0,1.0,1.0,0.0,0.002629995903438903,0.33497902112337,0.5506270935343258,-0.11515752881325673,-0.07470753265001356,0.1029769154618234,-0.9851666270255706,0.6973176647402357,0.1903553943365599,-0.24247834494002565,-1.4961865195236694,-0.32807469966928104,-1.1314509050291475,-1.0621086565289464,0.9732131710399524,-1.267938889527535,0.17587914052412648,0.17230034546042367,0.22087875593263012,-0.16410914453094522,0.0062258977059579,-0.17437299773596865,-0.8196939696387434,0.2859657702025154,1.5974426176106216,-1.0621086565289464,0.9732131710399524,-1.267938889527535,0.17587914052412648,0.17230034546042367,0.22087875593263012,-0.16410914453094522,0.0062258977059579,-0.17437299773596865,-0.8196939696387434,0.2859657702025154,1.5974426176106216,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4166835,0.0,1.0,1.0,0.0,-0.009253326713897503,0.33575969865443783,0.5476287880745639,-0.12345597703308148,-0.07520284945952818,0.11190364790575083,-0.9831483747397238,0.7147751574991971,0.18147771311085542,-0.3505477500062433,-0.9614121207153954,0.012179864844274468,-0.7868631047392449,-0.5530116117972689,0.8507535420018876,-1.511797442031692,0.13038632208928688,0.11809832478271544,0.11031437942365471,-0.09886618315825324,-0.006477424029671077,-0.08730716838520736,-1.4992646885843695,0.15892303606177394,1.4775411823035438,-0.5530116117972689,0.8507535420018876,-1.511797442031692,0.13038632208928688,0.11809832478271544,0.11031437942365471,-0.09886618315825324,-0.006477424029671077,-0.08730716838520736,-1.4992646885843695,0.15892303606177394,1.4775411823035438,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4333502,0.0,1.0,1.0,0.0,-0.023175407327209324,0.337436479409606,0.5423297087626542,-0.12929713043195326,-0.0740043467237942,0.11771038773574784,-0.9818094893344365,0.8202526300314316,0.2099790186657614,-0.4478571056037133,-0.7554307125044446,0.2755315578605844,-0.6394224334273829,-0.1272508271152961,0.3884898426696057,-1.547867451610687,0.11513344083136424,0.09925794605494304,0.04780803413779357,-0.06362928827877053,-0.016500611108100176,-0.039618561821349485,-1.9540726190359685,0.10768177221722554,1.287900420643955,-0.1272508271152961,0.3884898426696057,-1.547867451610687,0.11513344083136424,0.09925794605494304,0.04780803413779357,-0.06362928827877053,-0.016500611108100176,-0.039618561821349485,-1.9540726190359685,0.10768177221722554,1.287900420643955,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4500169,0.0,1.0,1.0,0.0,-0.03899542179903695,0.33939009967730294,0.5365990105082229,-0.13540616314320594,-0.07032587771260651,0.1228676936142433,-0.9806237666774671,0.9001530481183937,0.22222945611423262,-0.4280644610314178,-0.8405933079199984,0.5735682049911777,-0.6942845866736411,0.00820116669427772,0.07360969760221195,-1.0962820137675373,0.135838934325757,0.11286320127007868,0.014264042608214357,-0.051888462424339296,-0.027205329465598387,-0.015006313414306915,-2.391917082630023,-0.005034260445766618,0.9291857043215727,0.00820116669427772,0.07360969760221195,-1.0962820137675373,0.135838934325757,0.11286320127007868,0.014264042608214357,-0.051888462424339296,-0.027205329465598387,-0.015006313414306915,-2.391917082630023,-0.005034260445766618,0.9291857043215727,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4666836,0.0,1.0,1.0,0.0,-0.05537199553108474,0.3416840682215676,0.5321257485733966,-0.14280818314338695,-0.06415168026852047,0.12932635056029884,-0.9791655017394992,0.9379756460190354,0.20732376935026875,-0.33368041394483194,-0.973380812874399,0.8722714908228827,-0.7391421130393385,-0.006429498067778105,0.08891991718334397,-0.43093034007901365,0.15768940411555893,0.12642438568914394,-0.013256135544240833,-0.0395818545075959,-0.03457362274495745,0.005614103733883387,-2.739799785853953,-0.04969665894416455,0.5532135689092387,-0.006429498067778105,0.08891991718334397,-0.43093034007901365,0.15768940411555893,0.12642438568914394,-0.013256135544240833,-0.0395818545075959,-0.03457362274495745,0.005614103733883387,-2.739799785853953,-0.04969665894416455,0.5532135689092387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.4833503,0.0,1.0,1.0,0.0,-0.07176259474636695,0.3442383302387986,0.529399122644175,-0.1504024657969267,-0.05536695508776341,0.1358649272252439,-0.9776780247691942,0.9395773398732095,0.17868326081478586,-0.20941475472495127,-0.9610384235336298,1.0847496897404716,-0.7817618621068503,-0.17347316332199605,0.13148290866365445,-0.29491298981899405,0.1740584125773894,0.13380075135937688,-0.0416872647918031,-0.0340433279043661,-0.04864749882630189,0.02833924107143425,-3.0056253785954397,-0.3372424241298014,0.17721463873111756,-0.17347316332199605,0.13148290866365445,-0.29491298981899405,0.1740584125773894,0.13380075135937688,-0.0416872647918031,-0.0340433279043661,-0.04864749882630189,0.02833924107143425,-3.0056253785954397,-0.3372424241298014,0.17721463873111756,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.500017,0.0,1.0,1.0,0.0,-0.08739402803595331,0.34692754605671616,0.528633297006124,-0.1588998888837725,-0.045849815310146994,0.1415463772662832,-0.9760190791329548,0.9095706821029943,0.17259863483225246,-0.09105278433644019,-0.7376436271037504,1.1792147758409968,-0.8586460927217452,0.08772155913176327,0.42993867922010964,-0.35976219722291763,0.1878057425967195,0.13763647286321384,-0.07423219164133327,-0.043830711631012015,-0.07632703374144091,0.05481541889476522,-3.0811681524262435,-0.7744009205598813,-0.1170713906624193,0.08772155913176327,0.42993867922010964,-0.35976219722291763,0.1878057425967195,0.13763647286321384,-0.07423219164133327,-0.043830711631012015,-0.07632703374144091,0.05481541889476522,-3.0811681524262435,-0.7744009205598813,-0.1170713906624193,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5166837,1.0,1.0,1.0,0.0,-0.10241748160343056,0.3488997345293336,0.5290700072240834,-0.16774622029995429,-0.03628672021405945,0.1440886328138553,-0.9745680814622547,0.8847813294533592,0.19493339520276104,-0.002329526784351582,-0.5317538368123551,1.1583819813220146,-0.9592623075814761,0.2247532896568398,0.4432955724116129,-0.25056872513245027,0.2009775552956397,0.13991731782875141,-0.08729819323067911,-0.06346839600111168,-0.09774184718914683,0.06623134292005338,-2.9367221549416818,-1.0449653524074152,-0.3577274760416487,0.2247532896568398,0.4432955724116129,-0.25056872513245027,0.2009775552956397,0.13991731782875141,-0.08729819323067911,-0.06346839600111168,-0.09774184718914683,0.06623134292005338,-2.9367221549416818,-1.0449653524074152,-0.3577274760416487,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5333504,1.0,1.0,1.0,0.0,-0.1173435538783988,0.3504225516717111,0.5303249409764597,-0.17758278104209585,-0.027856494595792494,0.14638475492100175,-0.9727588987580159,0.863802936545889,0.1979197165218446,0.054052018688913295,-0.5310407226619606,1.0386774484560166,-1.1453620541507186,0.012636465063684831,0.25976369329215776,-0.13817967736769976,0.22688167729408412,0.15069177016286076,-0.060767340899625065,-0.09789300023691633,-0.10421110454042912,0.04723565812495841,-2.6672015459521594,-1.2971420714442656,-0.6170521633817148,0.012636465063684831,0.25976369329215776,-0.13817967736769976,0.22688167729408412,0.15069177016286076,-0.060767340899625065,-0.09789300023691633,-0.10421110454042912,0.04723565812495841,-2.6672015459521594,-1.2971420714442656,-0.6170521633817148,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5500171,1.0,1.0,1.0,0.0,-0.13167939131246353,0.3521833414211597,0.5320355895095339,-0.18908632256851365,-0.02066904682063045,0.1491175249750938,-0.9703520582068885,0.8331591391219741,0.19911209997413437,0.10547950451668142,-0.7137663235880756,0.8931986962546237,-1.3909686214029668,0.008830553056748755,0.31095481786020757,-0.1176691893403532,0.2637038839262375,0.16735989578042265,-0.008112015960065253,-0.1376506170867918,-0.09797585411449397,0.008315812260282109,-2.432374485460413,-1.565908510312858,-0.8346016056636817,0.008830553056748755,0.31095481786020757,-0.1176691893403532,0.2637038839262375,0.16735989578042265,-0.008112015960065253,-0.1376506170867918,-0.09797585411449397,0.008315812260282109,-2.432374485460413,-1.565908510312858,-0.8346016056636817,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5666838,1.0,1.0,1.0,0.0,-0.14563964959725434,0.35353029381651907,0.5344928474966764,-0.20251322675728178,-0.01459046488868037,0.15465704323895513,-0.9668798841113978,0.7664534325487968,0.23372172067556185,0.17154323010655545,-0.9017819426944576,0.7334301409053725,-1.6468304883239613,0.0066372803971532675,0.36474241716865685,-0.09277843971211386,0.30221067427708304,0.1815357310513385,0.04899594145934607,-0.17940329785810405,-0.08824021584177857,-0.034165692180696615,-2.330708418822525,-1.7042686354683205,-0.9817104991518553,0.0066372803971532675,0.36474241716865685,-0.09277843971211386,0.30221067427708304,0.1815357310513385,0.04899594145934607,-0.17940329785810405,-0.08824021584177857,-0.034165692180696615,-2.330708418822525,-1.7042686354683205,-0.9817104991518553,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.5833505,1.0,1.0,1.0,0.0,-0.15840439950471247,0.35355020249563496,0.5375149992434763,-0.21771471832276643,-0.010052780925308341,0.16080183282655125,-0.962622466796266,0.7064064478932245,0.2607580433787509,0.23725381393467537,-1.031821497978715,0.6307124405178638,-1.9241484360288124,0.010134822963315838,0.41934153854271383,-0.06857285632193003,0.3470932457507343,0.19340634448609742,0.09256119902170949,-0.22225004695063422,-0.08377318761907047,-0.06617199787523843,-2.3645572483436017,-1.793233548613164,-1.0118474485131237,0.010134822963315838,0.41934153854271383,-0.06857285632193003,0.3470932457507343,0.19340634448609742,0.09256119902170949,-0.22225004695063422,-0.08377318761907047,-0.06617199787523843,-2.3645572483436017,-1.793233548613164,-1.0118474485131237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6000172,1.0,1.0,1.0,0.0,-0.17102162683485675,0.3534225519542019,0.5414423441290089,-0.23522287616767543,-0.005872245539392806,0.16860776096130772,-0.9571870967597432,0.6472846262625236,0.25522684593653483,0.27096861582605625,-1.1329980352562279,0.5399137942109301,-2.1260396094986773,0.0190118039335549,0.4590411629809974,-0.045835125586976215,0.20885314066075736,0.32803168422027984,0.1944005011046149,-0.2544678235187658,-0.07321659138008672,-0.0928144109874788,-2.5298565841765246,-1.8361837596551809,-0.8908461565196242,0.0190118039335549,0.4590411629809974,-0.045835125586976215,0.20885314066075736,0.32803168422027984,0.1944005011046149,-0.2544678235187658,-0.07321659138008672,-0.0928144109874788,-2.5298565841765246,-1.8361837596551809,-0.8908461565196242,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6166839,1.0,0.0,1.0,0.0,-0.1820542554769631,0.3532005365128458,0.5452645650226369,-0.25324332790525034,-0.0029732680127857528,0.17657510525610456,-0.9511467861232532,0.5569615344381849,0.25814917434827306,0.2919726025699101,-0.9650953166031102,0.4662042727290987,-2.210397413242084,0.025267538074388283,0.4584284325345143,-0.010132681701975217,0.08106724625977833,0.6227587354315894,0.29043298762655273,-0.27792816773121587,-0.07431975709845173,-0.09293857504525907,-2.7413432130034168,-1.732838273161672,-0.6739573537181456,0.025267538074388283,0.4584284325345143,-0.010132681701975217,0.08106724625977833,0.6227587354315894,0.29043298762655273,-0.27792816773121587,-0.07431975709845173,-0.09293857504525907,-2.7413432130034168,-1.732838273161672,-0.6739573537181456,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6333506,1.0,0.0,1.0,0.0,-0.19217522204094556,0.35209837244035047,0.5494556496419353,-0.2716831481971206,-0.0009676212759344716,0.18184873007612484,-0.9450494008592718,0.48986083220627064,0.28463942024555533,0.3003947867227029,-0.4679480249650013,0.48430612407454166,-2.249287178766533,0.02535811366716489,0.42732959360246636,0.032361551167895505,0.1265486556892071,1.02633749543283,0.41339738818242283,-0.3041222620559265,-0.10259354326397847,-0.05518818101916391,-2.9025782127652575,-1.4621252451506193,-0.4544505611440596,0.02535811366716489,0.42732959360246636,0.032361551167895505,0.1265486556892071,1.02633749543283,0.41339738818242283,-0.3041222620559265,-0.10259354326397847,-0.05518818101916391,-2.9025782127652575,-1.4621252451506193,-0.4544505611440596,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6500173,1.0,0.0,1.0,0.0,-0.20181904525455702,0.3506729749546995,0.5530026363525391,-0.2901529170676614,-0.00014757675940088588,0.18174180465085904,-0.9395643561675144,0.4503107002349781,0.2900412403992655,0.26183504185386114,0.06252152387444598,0.5031747161258705,-2.263700414222358,0.02296281894639025,0.38998138149274914,0.07133938631220534,-0.030096126861061903,1.373532526852685,0.4538771976711772,-0.3296356597338615,-0.131614720460151,-0.011613174959620255,-2.7959247225192616,-1.1129382457005599,-0.33399076949158335,0.02296281894639025,0.38998138149274914,0.07133938631220534,-0.030096126861061903,1.373532526852685,0.4538771976711772,-0.3296356597338615,-0.131614720460151,-0.011613174959620255,-2.7959247225192616,-1.1129382457005599,-0.33399076949158335,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.666684,1.0,0.0,1.0,0.0,-0.21084814809813068,0.3498987961023276,0.5558932117774663,-0.30865343413732155,-0.00030850499044552537,0.1784487619466729,-0.9342852892878111,0.4219039235485802,0.2922006659767984,0.1997754841766649,0.5960339133898456,0.5223688262320384,-2.294384417110924,0.01790991315634062,0.35689271586154664,0.1095966888477686,-0.21818263603090657,1.5101563757072751,0.2816652725652662,-0.36039772997511743,-0.15922949696275845,0.03425231005391458,-2.4500815470333746,-0.8366542386806272,-0.37730672431392087,0.01790991315634062,0.35689271586154664,0.1095966888477686,-0.21818263603090657,1.5101563757072751,0.2816652725652662,-0.36039772997511743,-0.15922949696275845,0.03425231005391458,-2.4500815470333746,-0.8366542386806272,-0.37730672431392087,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.6833507,1.0,0.0,1.0,0.0,-0.219551236734146,0.34929676664107134,0.5575491245659974,-0.327419288943243,-0.002006524697503932,0.16978520627186808,-0.9294974808022659,0.4044457115890266,0.31974669459572386,0.14101182294839157,1.098958205485738,0.5121200825238472,-2.3783515860970885,0.01300407535122998,0.3366494706379284,0.14993655107538337,-0.23871963939212026,1.5441217972668417,0.1894882849477344,-0.3994862638699721,-0.18167410375143314,0.07770680563683423,-2.05464586936107,-0.7124126050242463,-0.6163640936811821,0.01300407535122998,0.3366494706379284,0.14993655107538337,-0.23871963939212026,1.5441217972668417,0.1894882849477344,-0.3994862638699721,-0.18167410375143314,0.07770680563683423,-2.05464586936107,-0.7124126050242463,-0.6163640936811821,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7000174,1.0,0.0,1.0,0.0,-0.2284387454132004,0.3488471191995866,0.5585217168335042,-0.34689935594000515,-0.00514297948542506,0.15857014042371745,-0.9243862272753877,0.3589966980588909,0.348173522416585,0.12201364432546061,1.2203479367585095,0.4606047165065509,-2.4812388342914864,0.023091588064624347,0.3466300626023241,0.1664479336321248,-0.2806415304379625,1.5219401074614731,0.28610916107877693,-0.4765619780383519,-0.32741795545262714,0.15077775975838476,-1.6377448607676504,-0.658928824870005,-0.8687761837806623,0.023091588064624347,0.3466300626023241,0.1664479336321248,-0.2806415304379625,1.5219401074614731,0.28610916107877693,-0.4765619780383519,-0.32741795545262714,0.15077775975838476,-1.6377448607676504,-0.658928824870005,-0.8687761837806623,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7166841,1.0,0.0,0.0,1.0,-0.236508039469308,0.34751614183481583,0.5594808523375289,0.3667586773828177,0.008498152761455331,-0.14811178397217384,0.9184109937346294,0.2780173383028263,0.3808654898727906,0.09569007877819685,1.1638264000304253,0.3805789208263998,-2.6185453800369696,0.04287525729117159,0.37437470387401556,0.1749231542722563,-0.2638688362802565,1.397948386938598,0.4105002874869482,-0.5685719900547391,-0.46850981021592447,0.20855578546988154,-0.7473001476202031,-0.539150775112855,-0.5807744641006485,0.04287525729117159,0.37437470387401556,0.1749231542722563,-0.2638688362802565,1.397948386938598,0.4105002874869482,-0.5685719900547391,-0.46850981021592447,0.20855578546988154,-0.7473001476202031,-0.539150775112855,-0.5807744641006485,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7333508,1.0,0.0,0.0,1.0,-0.24409287003148544,0.3454560895893881,0.5593477176013999,0.387751488470803,0.012868208960656465,-0.13807177820652616,0.9112734915763268,0.18246361984375511,0.40425241462998956,0.027351532729714412,0.9968033463875695,0.20324014979071436,-2.754217420120785,0.06616705419707686,0.4067042504058269,0.1881543610660939,-0.04001760335376867,1.1174925548530286,0.4558804576458157,-0.7182996913734703,-0.45510264994629124,0.2509854880248062,-0.0731921695251878,-0.4414468588039608,-0.20390080333800212,0.06616705419707686,0.4067042504058269,0.1881543610660939,-0.04001760335376867,1.1174925548530286,0.4558804576458157,-0.7182996913734703,-0.45510264994629124,0.2509854880248062,-0.0731921695251878,-0.4414468588039608,-0.20390080333800212,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7500175,1.0,0.0,0.0,1.0,-0.2504061644205723,0.3426448823840694,0.5578949623767968,0.4088636946270946,0.018114438317851714,-0.13108837193455317,0.9029497134856731,0.10452665658925887,0.41370996168738156,-0.038926513038359825,0.5795038110342163,0.006854716584400372,-2.7269241982413828,0.09564202062626273,0.4238654418149409,0.17680993206698895,0.2980238877158949,0.6808098217616279,0.36951089110107016,-0.8915822214211412,-0.5873216979388155,0.35458136008490354,-0.0869465866247684,-0.41877940110811207,-0.17524252599997744,0.09564202062626273,0.4238654418149409,0.17680993206698895,0.2980238877158949,0.6808098217616279,0.36951089110107016,-0.8915822214211412,-0.5873216979388155,0.35458136008490354,-0.0869465866247684,-0.41877940110811207,-0.17524252599997744,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7666842,1.0,0.0,0.0,1.0,-0.2565610900786634,0.33963282155237795,0.5555227271809133,0.4286626091026246,0.02257690676992895,-0.12847542223983935,0.8939981637108253,0.05152210018168317,0.4285133513106266,-0.1102064122744387,0.07754236475898951,-0.10047472033681822,-2.5876998955955104,0.12743091363667683,0.4244580454749523,0.14221869139731144,0.5286152617341568,0.4147498803769992,0.2564234859259465,-1.072816121881589,-0.8912041134798558,0.40823309113249456,-0.08895473559345238,-0.38345111138090204,-0.12626011110198762,0.12743091363667683,0.4244580454749523,0.14221869139731144,0.5286152617341568,0.4147498803769992,0.2564234859259465,-1.072816121881589,-0.8912041134798558,0.40823309113249456,-0.08895473559345238,-0.38345111138090204,-0.12626011110198762,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.7833509,1.0,0.0,0.0,1.0,-0.2622649812984756,0.3363032646551645,0.5516002045742371,0.4471998068470766,0.025624707680905717,-0.12965509048188853,0.8846158853560899,0.01376298582189156,0.42884329977429314,-0.14704907767119732,-0.2625102141053301,-0.014920552895639152,-2.443069347815164,0.15678502707216957,0.41281290237553747,0.09448960502184024,0.7901370311743099,0.2846268610908129,0.20280896152987568,-1.3167895291509943,-1.1835904522902931,0.29331098908347736,-0.08716469262336253,-0.36201518582285663,-0.07568969913845165,0.15678502707216957,0.41281290237553747,0.09448960502184024,0.7901370311743099,0.2846268610908129,0.20280896152987568,-1.3167895291509943,-1.1835904522902931,0.29331098908347736,-0.08716469262336253,-0.36201518582285663,-0.07568969913845165,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8000176,1.0,0.0,0.0,1.0,-0.26789460541615134,0.33313284555043704,0.5479148498652824,0.4647765085863153,0.026106759767539373,-0.1313661218680019,0.8752394964728889,-0.001705785710119992,0.4291284078239892,-0.1320976239549648,-0.44576520968320327,0.21595553789987032,-2.36895542420521,0.18746344667749335,0.40261278553528196,0.0413500265416204,1.0646567595142085,0.07764423356451496,0.06777854875902736,-1.6814020946167116,-1.42113025904413,0.18086355142101485,-0.08809230951050027,-0.36331199176281964,-0.02866360447450381,0.18746344667749335,0.40261278553528196,0.0413500265416204,1.0646567595142085,0.07764423356451496,0.06777854875902736,-1.6814020946167116,-1.42113025904413,0.18086355142101485,-0.08809230951050027,-0.36331199176281964,-0.02866360447450381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8166843,1.0,0.0,0.0,1.0,-0.2736321362045551,0.32974614302572025,0.5444031805343684,0.48242395191810594,0.02420101482006401,-0.13340559046826794,0.8653810663107953,-0.016836648910659113,0.4297186336724257,-0.09328175753085381,-0.5010667764409839,0.4685392216568002,-2.3463096386016318,0.21476714413875983,0.39284203629175474,-0.0016755921213463573,1.1400568627013377,-0.2813866390923878,-0.14855377298203004,-2.2407647458931095,-1.5642507925360343,0.21300683661946485,-0.09556532104828824,-0.37453497195224583,0.0050279565562391,0.21476714413875983,0.39284203629175474,-0.0016755921213463573,1.1400568627013377,-0.2813866390923878,-0.14855377298203004,-2.2407647458931095,-1.5642507925360343,0.21300683661946485,-0.09556532104828824,-0.37453497195224583,0.0050279565562391,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.833351,1.0,0.0,0.0,1.0,-0.2793777414996867,0.3263116045656802,0.5418511812712616,0.4998665066631143,0.02056878609275025,-0.13384445730890598,0.855450794495376,-0.014887692829202825,0.41229436952861104,-0.05387338629828631,-0.4454032100900726,0.6861750873643273,-2.286895121728832,0.23161495347045452,0.37060146857560283,-0.03299687896429401,1.1297461051431332,-0.707597732299305,-0.3450386100928367,-2.768623305731594,-1.5127788617659637,0.2999445572951236,-0.10611604537957012,-0.3779946423413211,0.025989857045237486,0.23161495347045452,0.37060146857560283,-0.03299687896429401,1.1297461051431332,-0.707597732299305,-0.3450386100928367,-2.768623305731594,-1.5127788617659637,0.2999445572951236,-0.10611604537957012,-0.3779946423413211,0.025989857045237486,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8500177,1.0,0.0,0.0,1.0,-0.28503633911404774,0.323389761398294,0.5397248811659711,0.5167184430402586,0.015829322224904248,-0.13323230098709726,0.8455771030211466,-0.0025030923145151623,0.38391252167225853,-0.0058654614175967165,-0.2701392372741363,0.8794717819796175,-2.2445744289131406,0.24067679543063494,0.34494499920386784,-0.050248750806957496,1.0893542719135616,-1.0264066985522113,-0.5308634041569514,-3.0645178483864686,-1.2014205537179383,0.33603813388536763,-0.12278452723582918,-0.38123092417768195,0.031734331916069385,0.24067679543063494,0.34494499920386784,-0.050248750806957496,1.0893542719135616,-1.0264066985522113,-0.5308634041569514,-3.0645178483864686,-1.2014205537179383,0.33603813388536763,-0.12278452723582918,-0.38123092417768195,0.031734331916069385,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8666844,1.0,0.0,0.0,1.0,-0.29055395459470523,0.320777110130382,0.5389749275147924,0.5335299529060633,0.010893517634512656,-0.12948069716199623,0.8357403123506989,0.022081243105731035,0.36397722553051565,0.040029806471911296,0.004300673904325869,1.025924042763654,-2.278491515525091,0.24757080222575828,0.3261086361735755,-0.050681771171577565,1.024641284017891,-1.2824135840553446,-0.6973505953523368,-3.2183116956867726,-0.8514042249390439,0.37229024154033485,-0.14841610199874383,-0.39054830944542324,0.02100097518674059,0.24757080222575828,0.3261086361735755,-0.050681771171577565,1.024641284017891,-1.2824135840553446,-0.6973505953523368,-3.2183116956867726,-0.8514042249390439,0.37229024154033485,-0.14841610199874383,-0.39054830944542324,0.02100097518674059,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.8833511,1.0,0.0,0.0,1.0,-0.2963671270031519,0.31892118929673424,0.5386444882574952,0.5506665049056813,0.006532772982762114,-0.12364808911501884,0.8254906863861768,0.06294526544446234,0.33809406863137864,0.06730957298153309,0.16951681440964073,1.1655753582311446,-2.2982204101937116,0.25768010481233716,0.3090824256959925,-0.06148599742808398,0.9283667820765745,-1.4461638692465717,-0.8170915965327759,-3.240613015032175,-0.5064788570372953,0.39914964072842474,-0.17035903120766496,-0.39638662896568877,0.02355793080031382,0.25768010481233716,0.3090824256959925,-0.06148599742808398,0.9283667820765745,-1.4461638692465717,-0.8170915965327759,-3.240613015032175,-0.5064788570372953,0.39914964072842474,-0.17035903120766496,-0.39638662896568877,0.02355793080031382,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9000178,1.0,0.0,0.0,1.0,-0.3019248720855058,0.31811665520677057,0.5392385961143021,0.5675257609048893,0.0011826354638721434,-0.11618007259068283,0.8151167418324259,0.08133421799830111,0.27545927766463035,0.10042110261465138,0.1703005747659293,1.3463371997885403,-2.2588644371471034,0.27253605879169907,0.28807491821194053,-0.09642183676590671,0.7381078160085675,-1.588419096199706,-0.9161022612396659,-3.098608192911989,-0.12391387453776653,0.29841618772932815,-0.18258014313614893,-0.3963229710491146,0.0523992645274848,0.27253605879169907,0.28807491821194053,-0.09642183676590671,0.7381078160085675,-1.588419096199706,-0.9161022612396659,-3.098608192911989,-0.12391387453776653,0.29841618772932815,-0.18258014313614893,-0.3963229710491146,0.0523992645274848,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9166845,1.0,0.0,0.0,1.0,-0.30626448970994413,0.31777096011581824,0.5405374878416074,0.5839439082638926,-0.005767609736966141,-0.10852315667071791,0.8044867749973492,0.06457791673903053,0.20153524371258202,0.12537257809800875,0.19855229089393678,1.4655257591395956,-2.3243560568973183,0.2941232093186548,0.2806703294443597,-0.11513235112484205,0.48836889729186506,-1.28462495628235,-0.8150819844546385,-2.8683277334331345,0.17829229032549476,0.16054457439733863,-0.20550279689204776,-0.40414566950769903,0.06839561596195895,0.2941232093186548,0.2806703294443597,-0.11513235112484205,0.48836889729186506,-1.28462495628235,-0.8150819844546385,-2.8683277334331345,0.17829229032549476,0.16054457439733863,-0.20550279689204776,-0.40414566950769903,0.06839561596195895,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9333512,1.0,0.0,0.0,1.0,-0.30948110216488567,0.31746209241666346,0.5423535650342757,0.6013441855369348,-0.012315081378186578,-0.09949353412056533,0.7926755616011945,0.0497708826347584,0.13572035239617283,0.12970985240545452,0.33781673382537547,1.4774442046204546,-2.4667897455082426,0.31344242749466805,0.28069318434698715,-0.10574506263219056,0.22850209098383176,-0.5597889976161181,-0.5072990639907369,-2.6167678482272643,0.4337659296393473,0.021201527505240684,-0.2399553653319491,-0.4124910492099421,0.058799536987522,0.31344242749466805,0.28069318434698715,-0.10574506263219056,0.22850209098383176,-0.5597889976161181,-0.5072990639907369,-2.6167678482272643,0.4337659296393473,0.021201527505240684,-0.2399553653319491,-0.4124910492099421,0.058799536987522,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.9500179,1.0,1.0,0.0,1.0,-0.3116267921656022,0.31757615894372776,0.544159786053277,0.6190489860821755,-0.017802798499665155,-0.0897861384462954,0.779999911884042,0.03267108094465305,0.07497771433045036,0.1211385849268613,0.4002274930067414,1.3170211135281464,-2.5715864919120763,0.3287326022958125,0.28170901685457844,-0.07968673122189827,0.2703028299906793,-0.21640899564507116,-0.26211215774716756,-2.3724384522410444,0.6394793813840327,-0.13525599254592396,-0.2688993412611401,-0.4029930335371665,0.039385726994534506,0.3287326022958125,0.28170901685457844,-0.07968673122189827,0.2703028299906793,-0.21640899564507116,-0.26211215774716756,-2.3724384522410444,0.6394793813840327,-0.13525599254592396,-0.2688993412611401,-0.4029930335371665,0.039385726994534506,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.966684599999999,1.0,1.0,0.0,1.0,-0.3127013721167245,0.317497273003062,0.5460095283176125,0.6368692886826337,-0.021497186257472736,-0.08150992175528342,0.7663494716976944,0.015313146332899825,0.02461113610511429,0.1252593979033359,0.45935203120241797,1.042564347688312,-2.6742857740226795,0.34168174885937624,0.2868425219424598,-0.036040763453465914,0.4541706502615875,-0.2282910232867464,-0.164388894714384,-2.16956094943439,0.8187426264267607,-0.2697386924625634,-0.2973540543217495,-0.38476113504043813,0.005542640625949332,0.34168174885937624,0.2868425219424598,-0.036040763453465914,0.4541706502615875,-0.2282910232867464,-0.164388894714384,-2.16956094943439,0.8187426264267607,-0.2697386924625634,-0.2973540543217495,-0.38476113504043813,0.005542640625949332,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +8.983351299999999,1.0,1.0,0.0,1.0,-0.3130916665386476,0.31752492499035223,0.5481869921005583,0.6547931572960682,-0.022630152554388758,-0.07387151193844219,0.7518489190505898,0.012152590539718101,-0.011761831414239737,0.125995530870256,0.4603636865451624,0.7337492732568035,-2.721181392060231,0.3518685245869374,0.28745716244686487,0.0056621703466532775,0.4409819904756155,-0.24235135485837936,-0.11937591290992282,-2.0131334609278086,0.8934587571570637,-0.3817615803484238,-0.31667261325842083,-0.35740064382857717,-0.025809665270589636,0.3518685245869374,0.28745716244686487,0.0056621703466532775,0.4409819904756155,-0.24235135485837936,-0.11937591290992282,-2.0131334609278086,0.8934587571570637,-0.3817615803484238,-0.31667261325842083,-0.35740064382857717,-0.025809665270589636,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.000017999999999,1.0,1.0,0.0,1.0,-0.31292317700198685,0.3176070127485606,0.5502398222896674,0.6720599175804427,-0.02237600400798462,-0.06879406566195637,0.7369546513565822,0.005465163098697842,-0.03044669617942844,0.11779107737399036,0.39551994138538193,0.43016748832940555,-2.6954096917751094,0.35784375366055915,0.281331621129363,0.04056917567660381,0.4195098256927914,-0.24847077458536634,-0.06974136353772027,-1.8475271544418252,0.8637093815605237,-0.4761623149066956,-0.32426506030548347,-0.32178140947397244,-0.05032225634348801,0.35784375366055915,0.281331621129363,0.04056917567660381,0.4195098256927914,-0.24847077458536634,-0.06974136353772027,-1.8475271544418252,0.8637093815605237,-0.4761623149066956,-0.32426506030548347,-0.32178140947397244,-0.05032225634348801,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.016684699999999,1.0,1.0,0.0,1.0,-0.3125994676538944,0.31751441216946696,0.5522165403680377,0.6885528472194832,-0.020426602002244103,-0.06524065946218695,0.7219566378041856,-0.003509222852115159,-0.03364624263302176,0.11068727595049178,0.3792384930337338,0.19813184334421627,-2.660138870868588,0.36142627600449423,0.2709279220952814,0.06996380264063162,0.3977214529547766,-0.2542330370134801,-0.03723716635606066,-1.689814103093052,0.8393806068898978,-0.5159118624664165,-0.3311402786993622,-0.28960449229884866,-0.0726581339373528,0.36142627600449423,0.2709279220952814,0.06996380264063162,0.3977214529547766,-0.2542330370134801,-0.03723716635606066,-1.689814103093052,0.8393806068898978,-0.5159118624664165,-0.3311402786993622,-0.28960449229884866,-0.0726581339373528,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.033351399999999,1.0,1.0,0.0,1.0,-0.31224546089854865,0.3172951620843793,0.5540250591047632,0.7044190085136819,-0.017542321576952333,-0.06288495463164653,0.706775501753752,-0.009288366447719697,-0.054631432726352666,0.0844264347388875,0.307720994686291,0.038749841617700384,-2.6308403756580114,0.40366662914843005,0.45068982020532833,0.17968663372686025,0.3815544080767011,-0.26222818033166495,-0.01021480698438951,-1.4631261343911823,0.7784860589946057,-0.47007563220012005,-0.33546320918269473,-0.26286748510543434,-0.0815783751852039,0.40366662914843005,0.45068982020532833,0.17968663372686025,0.3815544080767011,-0.26222818033166495,-0.01021480698438951,-1.4631261343911823,0.7784860589946057,-0.47007563220012005,-0.33546320918269473,-0.26286748510543434,-0.0815783751852039,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.050018099999999,0.0,1.0,0.0,1.0,-0.3111071563734511,0.31702424482979497,0.555193899300187,0.719679587696511,-0.014544495996974485,-0.06193394379665613,0.6913855185748156,-0.007553624556447751,-0.07792405320618162,0.038816276322529396,0.29090305722749454,-0.07757464423414132,-2.6501151418737336,0.6194555167266073,0.8280149302579082,0.2876288671067212,0.3713385706784332,-0.2757788625362767,0.005274779982764748,-1.1055969957071308,0.5626031371280399,-0.2594669999193892,-0.3472375905471202,-0.24237169487993798,-0.09306540705309672,0.6194555167266073,0.8280149302579082,0.2876288671067212,0.3713385706784332,-0.2757788625362767,0.005274779982764748,-1.1055969957071308,0.5626031371280399,-0.2594669999193892,-0.3472375905471202,-0.24237169487993798,-0.09306540705309672,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.066684799999999,0.0,1.0,1.0,1.0,-0.30981576435834157,0.3168473023008373,0.5555679085128333,0.73493396860815,-0.010428235415037537,-0.0611275157781227,0.6752975199915953,-0.0420217592589567,-0.05872112658887986,-0.013746039297275338,0.30996063345891234,-0.11345441334978032,-2.576175593804223,1.124366433456104,1.011876905921894,0.20782422558845717,0.34788482472832,-0.2810484558582189,0.0033671000428434636,-0.5975614610253185,0.3388785642645339,-0.04492904419650314,-0.34825782052366855,-0.21833862076550475,-0.09675972939564348,1.124366433456104,1.011876905921894,0.20782422558845717,0.34788482472832,-0.2810484558582189,0.0033671000428434636,-0.5975614610253185,0.3388785642645339,-0.04492904419650314,-0.34825782052366855,-0.21833862076550475,-0.09675972939564348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.0833515,0.0,1.0,1.0,1.0,-0.3092318638511416,0.31549118540919924,0.5548246955637449,0.7486395680341099,-0.0068455985261925015,-0.06028072748890059,0.6601955534899705,-0.05203651874433988,-0.07310692500984148,-0.04907166783238976,0.1193104283362434,0.0013523504587147697,-2.5058021018767196,1.9014311241300599,0.5948306967484654,0.06328133453036307,0.334569539512196,-0.29486185933225395,0.0006208451846453835,-0.2845706653027481,0.2874703550245572,0.003793384865716046,-0.34307633752674915,-0.20650571336905676,-0.06059932312336412,1.9014311241300599,0.5948306967484654,0.06328133453036307,0.334569539512196,-0.29486185933225395,0.0006208451846453835,-0.2845706653027481,0.2874703550245572,0.003793384865716046,-0.34307633752674915,-0.20650571336905676,-0.06059932312336412,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1000182,0.0,1.0,1.0,1.0,-0.3074563929315884,0.314932311163968,0.5540222874338494,0.7625138893107415,-0.006450258422350991,-0.060015287244296375,0.6441499267029966,-0.0407474197028311,-0.10123689108269562,-0.04934408688476264,-0.07923817825984715,0.1781598837678568,-2.3881464500533367,2.4271090126850905,0.18852147190476648,0.15405877801774315,0.3166827901578131,-0.30310507140867954,-0.007682615800283219,-0.25223798571514977,0.27390607598373895,0.007660644032744863,-0.33040471922472764,-0.196789476849331,-0.01632974357887136,2.4271090126850905,0.18852147190476648,0.15405877801774315,0.3166827901578131,-0.30310507140867954,-0.007682615800283219,-0.25223798571514977,0.27390607598373895,0.007660644032744863,-0.33040471922472764,-0.196789476849331,-0.01632974357887136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1166849,0.0,1.0,1.0,1.0,-0.3059765812853738,0.31369298015321395,0.5533729569270317,0.7744848840648669,-0.007362873451010206,-0.05910026345063862,0.6297825905101214,-0.062336559466465595,-0.08863207816762127,-0.01838379961793486,0.020156050918289467,0.3181809241693032,-2.179890342089784,2.7246298044356214,0.15703366519164216,0.38117901170928553,0.27513563572290584,-0.29234626957978926,-0.040589463229365644,-0.22923620230010922,0.2506346263886944,0.03453638099723817,-0.3155600557595386,-0.17490334971504584,-0.005359796303610993,2.7246298044356214,0.15703366519164216,0.38117901170928553,0.27513563572290584,-0.29234626957978926,-0.040589463229365644,-0.22923620230010922,0.2506346263886944,0.03453638099723817,-0.3155600557595386,-0.17490334971504584,-0.005359796303610993,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1333516,0.0,1.0,1.0,1.0,-0.30493019920426645,0.3123316230227146,0.5534965137898233,0.7857206173897338,-0.007340899098422957,-0.05598166159687438,0.615999412478596,-0.050852181211737124,-0.08372293523684075,0.025105430192763498,-0.03192242675573759,0.35851336765130243,-2.051530338715582,3.09389909941935,0.12506637467727916,0.4518691832444931,0.25111681407699027,-0.2878143514953974,-0.04292784165998633,-0.2055754609456509,0.23891814312875165,0.03541897752698409,-0.3019757223505243,-0.15878850077473397,0.009350340761787902,3.09389909941935,0.12506637467727916,0.4518691832444931,0.25111681407699027,-0.2878143514953974,-0.04292784165998633,-0.2055754609456509,0.23891814312875165,0.03541897752698409,-0.3019757223505243,-0.15878850077473397,0.009350340761787902,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1500183,0.0,1.0,1.0,1.0,-0.30375661848403523,0.311330153965505,0.5542953532973086,0.7958913034538438,-0.009581337807324725,-0.05494539545020209,0.6028650218508157,-0.05387303892286703,-0.08767606539290346,0.06618212212995613,-0.3920814858620129,0.3263832284094588,-1.9059590381519902,3.301768294414856,0.13634591717569677,0.4412235201562655,0.2382708212850734,-0.28180216327180263,-0.00045064793754806163,-0.1617934324994231,0.22549083390878163,-0.003026291152306035,-0.2710866852610667,-0.1445099412417307,0.04591424040430904,3.301768294414856,0.13634591717569677,0.4412235201562655,0.2382708212850734,-0.28180216327180263,-0.00045064793754806163,-0.1617934324994231,0.22549083390878163,-0.003026291152306035,-0.2710866852610667,-0.1445099412417307,0.04591424040430904,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.166685,0.0,1.0,1.0,1.0,-0.30282674521471714,0.3096963192153535,0.5557907383197175,0.8051113982015081,-0.014107219647841568,-0.0558563434935592,0.5903191439648131,-0.07653045865287679,-0.08430495807097156,0.08873817162433816,-0.7262907997528552,0.24725746620489011,-1.7952739156470046,3.3548732987372696,0.044722828150224464,0.44878986600258985,0.229223074654455,-0.27694062469379926,0.0484045122135898,-0.12238867492451365,0.21637937285837386,-0.04571726202456196,-0.2445011922067572,-0.13153746196785748,0.07220561405745715,3.3548732987372696,0.044722828150224464,0.44878986600258985,0.229223074654455,-0.27694062469379926,0.0484045122135898,-0.12238867492451365,0.21637937285837386,-0.04571726202456196,-0.2445011922067572,-0.13153746196785748,0.07220561405745715,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.1833517,0.0,1.0,1.0,1.0,-0.3021623195362805,0.3079229058057664,0.5572958657116794,0.8136056444482724,-0.02012629230962738,-0.05916879474471591,0.5780483036980875,-0.0690359085793339,-0.0705369353318954,0.08471361673008462,-0.9230286635897147,0.1031156507426253,-1.670010407053434,3.2817875799988947,-0.17639583890302765,0.4762856395425924,0.2137980419277363,-0.26319639422413865,0.09358749331131122,-0.08845375556229858,0.2079706519959342,-0.0830817251954678,-0.2186306758154457,-0.11361530971648676,0.07567562405494731,3.2817875799988947,-0.17639583890302765,0.4762856395425924,0.2137980419277363,-0.26319639422413865,0.09358749331131122,-0.08845375556229858,0.2079706519959342,-0.0830817251954678,-0.2186306758154457,-0.11361530971648676,0.07567562405494731,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2000184,0.0,1.0,1.0,1.0,-0.3017055783931524,0.3066475822455266,0.5586622941335057,0.8209989829357495,-0.02599620521161269,-0.06390499496350859,0.566745991562159,-0.040213792117498794,-0.06401619716925723,0.06981714341398336,-1.119022878974076,-0.011286004418934015,-1.6302632137860167,3.0496809528164897,-0.42813831042900474,0.41166356148423805,0.20661845406877172,-0.26255975018538796,0.13508370461257058,-0.06191498704759431,0.2076574272482409,-0.11648853559239704,-0.20666028222391802,-0.10316389845070165,0.08044726883330802,3.0496809528164897,-0.42813831042900474,0.41166356148423805,0.20661845406877172,-0.26255975018538796,0.13508370461257058,-0.06191498704759431,0.2076574272482409,-0.11648853559239704,-0.20666028222391802,-0.10316389845070165,0.08044726883330802,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2166851,0.0,1.0,1.0,1.0,-0.3009648078866455,0.30584160161540275,0.559745451457652,0.8284779365646152,-0.0336164829231191,-0.07057781889802645,0.554538557884945,-0.030637300585324316,-0.07653216868816075,0.0642601751887559,-1.3693153104872655,-0.09862703075843293,-1.6044557466214058,2.7731587911984206,-0.5416567312925044,0.2654697278433194,0.2017274444190929,-0.2654209709389107,0.17884971240256536,-0.033091685529495984,0.20526085394557345,-0.1511757243530622,-0.1957041362366438,-0.09723682976347474,0.09373842940941923,2.7731587911984206,-0.5416567312925044,0.2654697278433194,0.2017274444190929,-0.2654209709389107,0.17884971240256536,-0.033091685529495984,0.20526085394557345,-0.1511757243530622,-0.1957041362366438,-0.09723682976347474,0.09373842940941923,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2333518,0.0,1.0,1.0,1.0,-0.3000869724741404,0.30467968014824587,0.5610385562403454,0.8349384092250918,-0.04213418050929634,-0.07879861603393949,0.5430408288007627,-0.031268865854746995,-0.08264534450084476,0.058188663993886294,-1.3070339502178807,-0.1507659069718551,-1.5179021678981226,2.4836976482475133,-0.533783742276076,0.09354667409721613,0.1806350248268646,-0.25332063851254827,0.184123398769358,-0.019920309037121893,0.19771860476290326,-0.15251033156621635,-0.18628541228982126,-0.08375469294421115,0.07875923995456448,2.4836976482475133,-0.533783742276076,0.09354667409721613,0.1806350248268646,-0.25332063851254827,0.184123398769358,-0.019920309037121893,0.19771860476290326,-0.15251033156621635,-0.18628541228982126,-0.08375469294421115,0.07875923995456448,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2500185,0.0,1.0,1.0,1.0,-0.2992435752433108,0.30373969168078724,0.5619942436928705,0.8411218142440743,-0.04843203081107335,-0.0855988817216645,0.5318282273838734,-0.02873959212638426,-0.07934111161797017,0.03612759018521414,-1.1578874053144286,-0.12906816901594587,-1.4371835061168972,2.1072123400993106,-0.5812001329016971,-0.1719942678909805,0.1594357399883615,-0.24277668621919443,0.16699003454159764,-0.017266120649447537,0.18816867795034703,-0.13586984748835262,-0.18290851626202723,-0.0736699235285531,0.06468619313572885,2.1072123400993106,-0.5812001329016971,-0.1719942678909805,0.1594357399883615,-0.24277668621919443,0.16699003454159764,-0.017266120649447537,0.18816867795034703,-0.13586984748835262,-0.18290851626202723,-0.0736699235285531,0.06468619313572885,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2666852,0.0,1.0,1.0,1.0,-0.298380253539259,0.30266689386715084,0.5625871880032123,0.846571715596361,-0.055174286460881836,-0.09201970732820329,0.5213487335066602,-0.023785251394807735,-0.07517300680876238,0.014610396807921942,-1.2073571048906884,-0.023470148104077104,-1.325608384722031,1.6993392428683425,-0.7102922491109582,-0.44151698927098876,0.14295067355771482,-0.234680883630024,0.15766001660072104,-0.005063912516905179,0.1660677456533516,-0.12706409504520075,-0.17302267652605885,-0.07125185454947504,0.0827745212537204,1.6993392428683425,-0.7102922491109582,-0.44151698927098876,0.14295067355771482,-0.234680883630024,0.15766001660072104,-0.005063912516905179,0.1660677456533516,-0.12706409504520075,-0.17302267652605885,-0.07125185454947504,0.0827745212537204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.2833519,0.0,1.0,1.0,1.0,-0.29750944460867584,0.3019021956717226,0.5628666401210112,0.8515045974339255,-0.06322457992322801,-0.09762002049597876,0.5112855412005942,-0.008688726410023611,-0.08351096404425576,5.4033323903029604e-05,-1.2418456667184332,0.16225462798678958,-1.3243189731727512,1.3174453700732995,-0.9162216687924669,-0.5305029795551132,0.13705557621539186,-0.24646999366913097,0.13735540144017688,-0.006003685061023977,0.15646871226471493,-0.10970466608823523,-0.1848240705774455,-0.0753571733117226,0.10498955739335333,1.3174453700732995,-0.9162216687924669,-0.5305029795551132,0.13705557621539186,-0.24646999366913097,0.13735540144017688,-0.006003685061023977,0.15646871226471493,-0.10970466608823523,-0.1848240705774455,-0.0753571733117226,0.10498955739335333,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3000186,0.0,1.0,1.0,1.0,-0.29612387465599066,0.30110509262004315,0.5631371216152415,0.8568131066392949,-0.072002833330893,-0.101692963922492,0.5003453141302543,0.0020425862066431044,-0.09992012229177147,-0.0050097102758765565,-1.1923964420498474,0.33116078589066006,-1.3980025241286684,0.8532931168246952,-1.03474001065805,-0.5300237359314249,0.13553646854277188,-0.2674265858170578,0.11241154961846613,-0.017068572167091456,0.16082536865585237,-0.08860214938285174,-0.20959513503798174,-0.07786759083259989,0.11389510479023301,0.8532931168246952,-1.03474001065805,-0.5300237359314249,0.13553646854277188,-0.2674265858170578,0.11241154961846613,-0.017068572167091456,0.16082536865585237,-0.08860214938285174,-0.20959513503798174,-0.07786759083259989,0.11389510479023301,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3166853,0.0,1.0,1.0,1.0,-0.2946287608784201,0.30032945704950814,0.5634616931277018,0.8622974059588416,-0.08062658378130318,-0.10451818630713859,0.488895169126752,0.02167077023308912,-0.11676299976467039,-0.009661845951976004,-1.1655647722105018,0.4794951303407632,-1.3854278821114219,0.3001854859943052,-1.0260926247647573,-0.624947287480861,0.1275880696018349,-0.27451489542543694,0.09106427150773179,-0.021609161587635897,0.15333765968453839,-0.07046939488113056,-0.22041841274890717,-0.07637086012274544,0.1263577605830819,0.3001854859943052,-1.0260926247647573,-0.624947287480861,0.1275880696018349,-0.27451489542543694,0.09106427150773179,-0.021609161587635897,0.15333765968453839,-0.07046939488113056,-0.22041841274890717,-0.07637086012274544,0.1263577605830819,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.333352,0.0,1.0,1.0,1.0,-0.29246315092214153,0.2997335202387238,0.5638384935268825,0.8673788160112276,-0.09023335756707339,-0.10614406761824328,0.47775031933698126,0.04608521632590901,-0.12196029374779072,-0.015728241091704502,-1.0311256569807015,0.6386800068784266,-1.359934064948837,-0.18861606078605161,-0.9930357762435863,-0.8239618575022282,0.11771275963707009,-0.277977000859565,0.05687134382554732,-0.033980326086469545,0.14817829031368332,-0.04287412963667059,-0.2312137123767865,-0.07155368295201919,0.12880155935551765,-0.18861606078605161,-0.9930357762435863,-0.8239618575022282,0.11771275963707009,-0.277977000859565,0.05687134382554732,-0.033980326086469545,0.14817829031368332,-0.04287412963667059,-0.2312137123767865,-0.07155368295201919,0.12880155935551765,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3500187,0.0,1.0,1.0,1.0,-0.2903952979959281,0.29945978808451185,0.5641568574467339,0.8727244534050493,-0.09818569367530472,-0.1055648161807721,0.4664414942638325,0.053908070807803736,-0.11433244648612229,-0.02952159880610778,-0.7388677020370524,0.7340976959664495,-1.4051507245948776,-0.3082829975143502,-0.9620520926106165,-0.7258915439074641,0.1100789595797252,-0.28679634960283334,0.01602318181968069,-0.05734735776730823,0.16231219730592047,-0.010896775486469603,-0.25060732296902305,-0.061907546287378094,0.10477119432404237,-0.3082829975143502,-0.9620520926106165,-0.7258915439074641,0.1100789595797252,-0.28679634960283334,0.01602318181968069,-0.05734735776730823,0.16231219730592047,-0.010896775486469603,-0.25060732296902305,-0.061907546287378094,0.10477119432404237,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3666854,0.0,1.0,1.0,1.0,-0.2881929240667743,0.29908274371142934,0.5640903044692167,0.8783948124508556,-0.10419743389273203,-0.10353812349925766,0.4548024903316257,0.05538325823430818,-0.11887916768936148,-0.043705263212467434,-0.508108198509762,0.7274731023761989,-1.4204690354938534,-0.08894647255348691,-1.0353229173493796,-0.24292826063566128,0.10037286778907224,-0.2868909113755673,-0.005063531676181845,-0.06875791325191005,0.1746219530927477,0.005276273439780167,-0.2572624067742555,-0.04974087751755953,0.07776107049034338,-0.08894647255348691,-1.0353229173493796,-0.24292826063566128,0.10037286778907224,-0.2868909113755673,-0.005063531676181845,-0.06875791325191005,0.1746219530927477,0.005276273439780167,-0.2572624067742555,-0.04974087751755953,0.07776107049034338,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.3833521,0.0,1.0,1.0,1.0,-0.28586879320060654,0.2986078836006825,0.5640222796952142,0.8838761023200931,-0.10868430071325058,-0.10125155642522495,0.4435074755259282,0.07687388709586095,-0.11141663674598828,-0.05358100863964914,-0.320129177602237,0.6865698282928476,-1.3502240052480445,0.17449741954064352,-0.3613898207164548,-0.25374494614467896,0.08643225207488332,-0.2716416392368891,-0.020126249492102417,-0.07165446942436625,0.17437911340856252,0.016548047867517974,-0.24737062709860802,-0.037110798514385264,0.05540399485438859,0.17449741954064352,-0.3613898207164548,-0.25374494614467896,0.08643225207488332,-0.2716416392368891,-0.020126249492102417,-0.07165446942436625,0.17437911340856252,0.016548047867517974,-0.24737062709860802,-0.037110798514385264,0.05540399485438859,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4000188,1.0,1.0,1.0,1.0,-0.28336920744265043,0.29880028780759404,0.5636417888210677,0.8889703924830022,-0.11170011500068999,-0.09825184691481338,0.4331296574644568,0.10533336811122296,-0.08611692408107742,-0.06709642381967297,-0.18336115040200354,0.6466191544786031,-1.2402882202962406,0.2728689576543415,0.16998807085421228,-0.2821965953305854,0.2524894477598503,-0.20586478623319213,0.09501804731475606,-0.07024478435185183,0.16586395405510748,0.025326842783670714,-0.23020722925531673,-0.02665255161591872,0.0409954694767973,0.2728689576543415,0.16998807085421228,-0.2821965953305854,0.2524894477598503,-0.20586478623319213,0.09501804731475606,-0.07024478435185183,0.16586395405510748,0.025326842783670714,-0.23020722925531673,-0.02665255161591872,0.0409954694767973,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4166855,1.0,0.0,1.0,1.0,-0.28098818010989346,0.29941308257747895,0.5629727249679937,0.8935591444537082,-0.11403692180917788,-0.09530987105009527,0.42363151949289446,0.10800795170635526,-0.07907327781518415,-0.07817082349284912,-0.18266742433563354,0.6166743663005193,-1.1861057630386265,0.22102597581546932,-0.060770164106022796,-0.04606595536431472,0.594747016711697,-0.23319637524892192,0.2630987570783608,-0.06294354901285765,0.159829773085564,0.022933636624727423,-0.22042317593033744,-0.02033783162688388,0.0403661602356046,0.22102597581546932,-0.060770164106022796,-0.04606595536431472,0.594747016711697,-0.23319637524892192,0.2630987570783608,-0.06294354901285765,0.159829773085564,0.022933636624727423,-0.22042317593033744,-0.02033783162688388,0.0403661602356046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4333522,1.0,0.0,1.0,1.0,-0.2784927907837946,0.2996624504195262,0.5621665911930127,0.8979754079052338,-0.11689303129424466,-0.09260641456341243,0.41400511834273424,0.103841576944961,-0.08431777058340119,-0.10293751679907431,-0.20601903621350665,0.6446438002921607,-1.1637134319658091,0.21740961396068562,-0.06802309514592556,-0.05310559876920203,0.8820022168935053,-0.4409102060167638,0.2995186835817846,-0.05918298415630945,0.15624993229518575,0.024261217999115365,-0.2189099876659844,-0.01642584359294404,0.047426945989994515,0.21740961396068562,-0.06802309514592556,-0.05310559876920203,0.8820022168935053,-0.4409102060167638,0.2995186835817846,-0.05918298415630945,0.15624993229518575,0.024261217999115365,-0.2189099876659844,-0.01642584359294404,0.047426945989994515,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4500189,1.0,0.0,1.0,1.0,-0.27584102003224115,0.29983413303550094,0.5607403073596218,0.9021852431190971,-0.11976573374621184,-0.08934976230824687,0.4046412931150586,0.13169860802575314,-0.07999799830825438,-0.13168708990281935,-0.1595866385703626,0.6689849689000604,-1.0996791078512151,0.20210012954521545,-0.07076744552323265,-0.056172989224449646,1.1129360906432468,-0.6105740617135372,0.31463244121879175,-0.05880857357396184,0.14934357474199908,0.03202262802269179,-0.21134493540870833,-0.011518146305678751,0.048329124734594324,0.20210012954521545,-0.07076744552323265,-0.056172989224449646,1.1129360906432468,-0.6105740617135372,0.31463244121879175,-0.05880857357396184,0.14934357474199908,0.03202262802269179,-0.21134493540870833,-0.011518146305678751,0.048329124734594324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4666856,1.0,0.0,1.0,1.0,-0.2725874756279157,0.30061355209145924,0.5590243609612061,0.9060769872256038,-0.12216250427112514,-0.08582216888405957,0.3958981827419981,0.15677207421275782,-0.07403443987148707,-0.14312899707865992,-0.08824494085888947,0.6418789192308892,-1.011408987227362,0.18093738148446112,-0.06777739355732365,-0.05105843945476245,1.382232122215234,-0.5232585281068914,0.35612711027624705,-0.056536955383346715,0.1408923963673997,0.03676563903328567,-0.19678133411798449,-0.0059421331404641686,0.041681981249658176,0.18093738148446112,-0.06777739355732365,-0.05105843945476245,1.382232122215234,-0.5232585281068914,0.35612711027624705,-0.056536955383346715,0.1408923963673997,0.03676563903328567,-0.19678133411798449,-0.0059421331404641686,0.041681981249658176,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.4833523,1.0,0.0,1.0,1.0,-0.26940815208052743,0.30134025549113125,0.5572032781477642,0.9096065030295498,-0.12388513076458038,-0.08230332822859548,0.38793639450854905,0.13918055206886448,-0.08104499137280968,-0.15399510978434955,0.03624635399921501,0.6402666761565343,-0.9664701871860051,0.16432270903300575,-0.06380112285592959,-0.04336193474828746,1.5046907268340675,-0.3909178812366463,0.42545957851585636,-0.06015576141037441,0.14148921038581388,0.04768898537698218,-0.1910032581139078,-0.00014980299498636445,0.030389640940057534,0.16432270903300575,-0.06380112285592959,-0.04336193474828746,1.5046907268340675,-0.3909178812366463,0.42545957851585636,-0.06015576141037441,0.14148921038581388,0.04768898537698218,-0.1910032581139078,-0.00014980299498636445,0.030389640940057534,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.500019,1.0,0.0,1.0,1.0,-0.266293923865451,0.3013477854382921,0.5551483512720247,0.913278606511734,-0.12441901294731586,-0.07788718162410682,0.37996800265792696,0.11724065671920895,-0.10333618842617998,-0.14970660757634446,0.18882745108369695,0.6469607157557775,-0.943928884213269,0.1501614709805128,-0.058716245016583825,-0.0338920146685619,1.5520471668412321,-0.24578246364991432,0.43477338317212394,-0.06633837256908472,0.1468417568186625,0.061582299103409045,-0.18942994284102288,0.005684171747752091,0.01639094826622567,0.1501614709805128,-0.058716245016583825,-0.0338920146685619,1.5520471668412321,-0.24578246364991432,0.43477338317212394,-0.06633837256908472,0.1468417568186625,0.061582299103409045,-0.18942994284102288,0.005684171747752091,0.01639094826622567,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5166857,1.0,0.0,1.0,1.0,-0.26317035076641054,0.3009463118236931,0.5536012457031146,0.9168199485760652,-0.12387875667686464,-0.07322680997858119,0.3724688843883959,0.11812661881598503,-0.12957079648291386,-0.12872673358951378,0.300428371481122,0.5381403711860273,-0.9137928992287231,0.13778277822050328,-0.04786265446972456,-0.011487001818017048,1.3183728043976894,-0.20836621257283203,0.320766952496384,-0.06226901344141245,0.15064977974039134,0.059246407791567736,-0.17881578186227828,0.012115125876338503,-0.006041164549401217,0.13778277822050328,-0.04786265446972456,-0.011487001818017048,1.3183728043976894,-0.20836621257283203,0.320766952496384,-0.06226901344141245,0.15064977974039134,0.059246407791567736,-0.17881578186227828,0.012115125876338503,-0.006041164549401217,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5333524,1.0,0.0,1.0,1.0,-0.25964758136493826,0.3003797767850302,0.5524171667266197,0.9202342794809869,-0.12206235111933524,-0.0696970201604799,0.3652560453819741,0.1388135826560787,-0.14064892291541997,-0.10480500317854163,0.4131062133439766,0.36774367386919826,-0.8698072482713505,0.12393429012903064,-0.03196500352955579,0.019636718186696118,0.9428359103601557,-0.4640400951250614,0.032584781406308765,-0.05435562835398251,0.15300029167687232,0.050608130645461075,-0.1622747327919533,0.018668051661983372,-0.03559108959917052,0.12393429012903064,-0.03196500352955579,0.019636718186696118,0.9428359103601557,-0.4640400951250614,0.032584781406308765,-0.05435562835398251,0.15300029167687232,0.050608130645461075,-0.1622747327919533,0.018668051661983372,-0.03559108959917052,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5500191,1.0,0.0,1.0,1.0,-0.2559912581294856,0.3002309899238612,0.5517186741104737,0.9233882025318476,-0.118774163009851,-0.06685496956054802,0.3588555958479279,0.13498884590401947,-0.14245645877665938,-0.07082516414017224,0.5188958438627296,0.2307621657339392,-0.828241557958291,0.11157605364480577,-0.01841157676802917,0.045507403389750144,0.8311991334572851,-0.5638992083332014,-0.34967345042890907,-0.048498706878567735,0.15449868148800144,0.045673552988377844,-0.14839775654698636,0.02433257972474896,-0.06059479189423192,0.11157605364480577,-0.01841157676802917,0.045507403389750144,0.8311991334572851,-0.5638992083332014,-0.34967345042890907,-0.048498706878567735,0.15449868148800144,0.045673552988377844,-0.14839775654698636,0.02433257972474896,-0.06059479189423192,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5666858,1.0,0.0,1.0,1.0,-0.2527827541415176,0.29963712739050424,0.5515854574211428,0.9264725209195042,-0.11453818906244037,-0.0646890143184094,0.3526258678172495,0.12256768468416505,-0.1575678966049847,-0.03783305045032516,0.581308209376674,0.0990981369904386,-0.8268623998589159,0.10909863525182559,-0.009143021276567647,0.06911229541437397,0.6248648434965056,-0.48978004326037705,-0.6003575541041059,-0.04111568936118935,0.15971243442387034,0.036869517452705586,-0.14068337508800016,0.029874451257132208,-0.08183962141312073,0.10909863525182559,-0.009143021276567647,0.06911229541437397,0.6248648434965056,-0.48978004326037705,-0.6003575541041059,-0.04111568936118935,0.15971243442387034,0.036869517452705586,-0.14068337508800016,0.029874451257132208,-0.08183962141312073,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.5833525,1.0,0.0,1.0,1.0,-0.24934888472682362,0.2989426575209526,0.5520152319228564,0.9294642876642603,-0.10949530500397818,-0.06349292131356839,0.34651921314975337,0.12083790330366388,-0.15308218597855752,-0.01882889647107376,0.696869671184657,0.015890224393031532,-0.7623880313283204,0.09318616916886324,0.002807953491830917,0.08791563147648777,0.3425424327317573,-0.48096468633392414,-0.8141534799202793,-0.039421525142548514,0.15700883758631298,0.0402146575931225,-0.12705319201699064,0.034470215163702723,-0.10112740754230802,0.09318616916886324,0.002807953491830917,0.08791563147648777,0.3425424327317573,-0.48096468633392414,-0.8141534799202793,-0.039421525142548514,0.15700883758631298,0.0402146575931225,-0.12705319201699064,0.034470215163702723,-0.10112740754230802,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6000192,1.0,0.0,1.0,1.0,-0.24641689134176173,0.29843265215839687,0.5524108614637054,0.9321616029598871,-0.10302321655152927,-0.06182490478225085,0.34152400203689337,0.08508385427361961,-0.11895880913451834,-0.016267476070743726,0.854480922162906,0.054464200884496994,-0.6218521037667245,0.061487588040430384,0.013633383230428226,0.08946772455472941,-0.00011953371704503788,-0.39615045592171577,-1.002990940725358,-0.04753502337557622,0.14252394267126067,0.06380009262607861,-0.1102418589066452,0.03616485207042944,-0.10775748123415538,0.061487588040430384,0.013633383230428226,0.08946772455472941,-0.00011953371704503788,-0.39615045592171577,-1.002990940725358,-0.04753502337557622,0.14252394267126067,0.06380009262607861,-0.1102418589066452,0.03616485207042944,-0.10775748123415538,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6166859,1.0,1.0,1.0,1.0,-0.24462114037115934,0.29774722120886543,0.5525450188035155,0.9345232699630314,-0.09588003665156677,-0.058862095395481026,0.33765149221490315,0.05314501462075232,-0.11536452505489304,-0.003218336116700391,0.9756301397818409,0.07685093204548499,-0.5921715582717599,0.0513242156438666,0.018202559007339598,0.09481741246851651,-0.11045913012668145,-0.19208901091779784,-0.581020032043525,-0.05290484204463567,0.14356056123859676,0.07999965546551811,-0.10958799391389115,0.04047146984165656,-0.11558383732430214,0.0513242156438666,0.018202559007339598,0.09481741246851651,-0.11045913012668145,-0.19208901091779784,-0.581020032043525,-0.05290484204463567,0.14356056123859676,0.07999965546551811,-0.10958799391389115,0.04047146984165656,-0.11558383732430214,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6333526,1.0,1.0,1.0,1.0,-0.24265941589182977,0.2966577083993859,0.5532284772988267,0.9371195498632571,-0.08768098626752188,-0.05608294701681758,0.33312714834601814,0.048864717076635984,-0.12760823201439106,0.0104791460058977,1.0254524322282939,0.037841950055633705,-0.6195372489588568,0.0551864636377127,0.01972872575671826,0.10573300934551268,-0.006863410785583388,-0.08492769638533214,-0.10067726579468507,-0.050849731483380345,0.1504592578777427,0.08154637316237744,-0.11289960590664312,0.04580283573565399,-0.12486390197781365,0.0551864636377127,0.01972872575671826,0.10573300934551268,-0.006863410785583388,-0.08492769638533214,-0.10067726579468507,-0.050849731483380345,0.1504592578777427,0.08154637316237744,-0.11289960590664312,0.04580283573565399,-0.12486390197781365,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6500193,1.0,1.0,1.0,1.0,-0.2408072416331451,0.29558043205060863,0.5538207713585428,0.9394994108899795,-0.07949532870609119,-0.053485804366200346,0.3288778167991762,0.048683902064557354,-0.11558527696482912,0.022299341920591097,0.9311648338797388,-0.03955143477426559,-0.5791465350304451,0.055252910684805215,0.01878096948230949,0.1072733928675575,-0.006214362862284985,-0.07529650359968029,-0.08105262833559812,-0.03995714986733223,0.14002654159977343,0.06722300373083431,-0.10142442341438995,0.04594906851774117,-0.12110301747231796,0.055252910684805215,0.01878096948230949,0.1072733928675575,-0.006214362862284985,-0.07529650359968029,-0.08105262833559812,-0.03995714986733223,0.14002654159977343,0.06722300373083431,-0.10142442341438995,0.04594906851774117,-0.12110301747231796,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.666686,1.0,1.0,1.0,1.0,-0.23916236861011075,0.29478851438834536,0.5547474319040447,0.9415073586446647,-0.07237468196827002,-0.052364552924946434,0.32493653630348956,0.04907161200385126,-0.09737829758590458,0.03520554155110285,0.7604505840848729,-0.10919956014769644,-0.5560480798916563,0.06115697020398349,0.012960831145148203,0.10153253948300102,-0.003703185833451821,-0.07165516507096083,-0.05382364552300404,-0.026532448696385352,0.1284579771680791,0.04614934254407482,-0.09139260473380068,0.04384198095193428,-0.10920684246192192,0.06115697020398349,0.012960831145148203,0.10153253948300102,-0.003703185833451821,-0.07165516507096083,-0.05382364552300404,-0.026532448696385352,0.1284579771680791,0.04614934254407482,-0.09139260473380068,0.04384198095193428,-0.10920684246192192,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.6833527,1.0,1.0,1.0,1.0,-0.23773534450227862,0.2941871544306564,0.5556127415850105,0.9433416569777009,-0.06648878884064102,-0.051746880703662124,0.32094862440351934,0.03312354768222443,-0.07705379153784951,0.032239651189004966,0.621923671188393,-0.1041478003722307,-0.5218854060545248,0.062083979298345845,0.006198914918282432,0.08715996511892468,-0.0026887121381125663,-0.06934107679929852,-0.04115279658098743,-0.01952297682672525,0.11572324100331957,0.036269185880054226,-0.08429566826317117,0.04018324928571032,-0.09204357581984457,0.062083979298345845,0.006198914918282432,0.08715996511892468,-0.0026887121381125663,-0.06934107679929852,-0.04115279658098743,-0.01952297682672525,0.11572324100331957,0.036269185880054226,-0.08429566826317117,0.04018324928571032,-0.09204357581984457,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7000194,1.0,1.0,1.0,1.0,-0.23690480738836261,0.29354719010236385,0.5562750159872093,0.9449054685119751,-0.0615901836249317,-0.05125251468020425,0.31738538812643485,0.018591278203523916,-0.06685902580199991,0.023559671562872805,0.5760092973430408,-0.09467229684332812,-0.4868633338464559,0.05844454644628845,0.004177408432680636,0.08040047563357262,-0.003143262173145322,-0.06448368787562767,-0.0389448477131275,-0.01717901579184317,0.10747493538718751,0.034933014403905324,-0.07876682441126279,0.03881383907884841,-0.08441230894279646,0.05844454644628845,0.004177408432680636,0.08040047563357262,-0.003143262173145322,-0.06448368787562767,-0.0389448477131275,-0.01717901579184317,0.10747493538718751,0.034933014403905324,-0.07876682441126279,0.03881383907884841,-0.08441230894279646,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7166861,1.0,1.0,1.0,1.0,-0.23602784446349195,0.2928658920785421,0.556755682740725,0.946426621456223,-0.05650059185533276,-0.05069162771268197,0.3138705022756922,0.015252555196943615,-0.06302552424584289,0.016737822174016093,0.5296660980444884,-0.09748724981495852,-0.42756941129127607,0.05087911664903376,0.004462874235635075,0.07480175195470574,-0.0033334361566248103,-0.05494455960676795,-0.03503817632663982,-0.014592067671055132,0.0956786234881657,0.03201381137807314,-0.06880462047670205,0.03627118964573437,-0.07782611690327242,0.05087911664903376,0.004462874235635075,0.07480175195470574,-0.0033334361566248103,-0.05494455960676795,-0.03503817632663982,-0.014592067671055132,0.0956786234881657,0.03201381137807314,-0.06880462047670205,0.03627118964573437,-0.07782611690327242,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7333528,1.0,1.0,1.0,1.0,-0.23533639057780556,0.2922205633186083,0.5571487988576318,0.9475659708576862,-0.052365213988041566,-0.05042345630276325,0.3111817640720623,0.01066264132652256,-0.058433800055914635,0.005550391076505011,0.49815339286238713,-0.08280901368318491,-0.3729386555808321,0.04301175863848087,0.004684301403657695,0.06812604041572402,-0.004004100344583508,-0.04641431105582729,-0.035152367607946974,-0.013764790212209967,0.08491888781801447,0.03234817825390822,-0.06078064919526102,0.033820275358501184,-0.07093022976974779,0.04301175863848087,0.004684301403657695,0.06812604041572402,-0.004004100344583508,-0.04641431105582729,-0.035152367607946974,-0.013764790212209967,0.08491888781801447,0.03234817825390822,-0.06078064919526102,0.033820275358501184,-0.07093022976974779,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7500195,1.0,1.0,1.0,1.0,-0.23462838363013055,0.2915300380526911,0.5572155438839395,0.9487238488750035,-0.047889217071958125,-0.049742092018672635,0.308472698541768,-0.0002950547229633189,-0.05714420510322067,-0.013657381567527521,0.5232706110031242,-0.035787363700352265,-0.34854564265210125,0.03707244220178401,0.004774216413844562,0.06261426725490596,-0.006036248829212952,-0.04268318687727945,-0.045552697982133614,-0.017125337991350166,0.0809594046190359,0.041245334292440865,-0.06023402902233381,0.033502001327889414,-0.06692163094459039,0.03707244220178401,0.004774216413844562,0.06261426725490596,-0.006036248829212952,-0.04268318687727945,-0.045552697982133614,-0.017125337991350166,0.0809594046190359,0.041245334292440865,-0.06023402902233381,0.033502001327889414,-0.06692163094459039,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7666862,1.0,1.0,1.0,1.0,-0.2341820561469885,0.2906537957717737,0.5569287952158358,0.949746656734342,-0.04361669065106477,-0.04857853036153172,0.30613558876174957,-0.013666638614907018,-0.0637770335028512,-0.03394571360560668,0.5714572687789768,0.030672893888305103,-0.2991287753858101,0.14508826619557366,0.09693884785821379,0.1235849741056296,-0.009186677054457255,-0.03415330802776326,-0.0614786375659141,-0.02266751947391021,0.07351723818624356,0.054821949154400626,-0.05744354334963212,0.032461052588814446,-0.06242647316013649,0.14508826619557366,0.09693884785821379,0.1235849741056296,-0.009186677054457255,-0.03415330802776326,-0.0614786375659141,-0.02266751947391021,0.07351723818624356,0.054821949154400626,-0.05744354334963212,0.032461052588814446,-0.06242647316013649,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.7833529,0.0,1.0,1.0,1.0,-0.23363456144366976,0.28948376841415224,0.5563031548725176,0.950686392750252,-0.03875513552585932,-0.04656130823537229,0.30417999060637824,-0.029614826092890085,-0.06835321807914126,-0.03932077207199069,0.6710813846091668,0.058407611827562,-0.2319595188342516,0.2836642655653168,0.19374617285277368,0.23084178850350348,-0.012523587881946532,-0.018919316877410025,-0.07685856215427916,-0.028264240961725057,0.0664115458662642,0.06866165979842166,-0.05087410548965498,0.03338203550581585,-0.06759634842169535,0.2836642655653168,0.19374617285277368,0.23084178850350348,-0.012523587881946532,-0.018919316877410025,-0.07685856215427916,-0.028264240961725057,0.0664115458662642,0.06866165979842166,-0.05087410548965498,0.03338203550581585,-0.06759634842169535,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.8000196,0.0,1.0,1.0,1.0,-0.23352578695319118,0.288169869922981,0.5557960342551634,0.951398528117714,-0.03309775685234208,-0.04440597918314937,0.30294139400150716,-0.05470435496711957,-0.04108018246891004,-0.04594726873867231,0.7921789821868492,0.06411687118423998,-0.0744371704654296,0.427977248953707,0.39650325177558204,0.3671240992433099,-0.016380412936895083,0.01464607442246621,-0.09134541839935906,-0.034230681576257284,0.046023535055584174,0.0823249106458565,-0.02986503568931882,0.03180469316921567,-0.07613302532977395,0.427977248953707,0.39650325177558204,0.3671240992433099,-0.016380412936895083,0.01464607442246621,-0.09134541839935906,-0.034230681576257284,0.046023535055584174,0.0823249106458565,-0.02986503568931882,0.03180469316921567,-0.07613302532977395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.816686299999999,0.0,1.0,1.0,1.0,-0.23417071967481293,0.2872570347736947,0.5547865435200887,0.9515393241452659,-0.026457211071839473,-0.041597995751981934,0.30354989266492743,-0.06980323489469178,-0.02670840595540399,-0.05558487434263219,0.7820458562713346,0.09740201873087036,0.016828399354760742,0.5416244751439477,0.72768421159959,0.5130388213240724,-0.018281725801799317,0.03035737138098174,-0.09583680635265807,-0.03590283206987793,0.029354412812861396,0.0865554644798244,-0.01813061310710243,0.027221420500099583,-0.06885103452735422,0.5416244751439477,0.72768421159959,0.5130388213240724,-0.018281725801799317,0.03035737138098174,-0.09583680635265807,-0.03590283206987793,0.029354412812861396,0.0865554644798244,-0.01813061310710243,0.027221420500099583,-0.06885103452735422,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.833352999999999,0.0,1.0,1.0,1.0,-0.23472694644213687,0.28604914751411836,0.5538726920771955,0.9517331214886834,-0.0212012170046614,-0.038895571316885126,0.3037132008834344,-0.06263557039095508,-0.03455400546247974,-0.06494778523407407,0.6486597300978826,0.14739255883872296,0.03639180138288173,0.4846475787716697,0.8871065333451775,0.515026257916715,-0.0179024667093156,0.027764345103190365,-0.08925201479401376,-0.032853908263484215,0.018284402398915788,0.08026826791166111,-0.015581796975698814,0.020261781610930903,-0.04851924561975852,0.4846475787716697,0.8871065333451775,0.515026257916715,-0.0179024667093156,0.027764345103190365,-0.08925201479401376,-0.032853908263484215,0.018284402398915788,0.08026826791166111,-0.015581796975698814,0.020261781610930903,-0.04851924561975852,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.850019699999999,0.0,1.0,1.0,1.0,-0.23501495356084373,0.285072088140779,0.5525761147679448,0.9516822137333474,-0.01693602504345897,-0.03596749613804751,0.30450036837561023,-0.04262763380312548,-0.022855885647523166,-0.06394948917626356,0.5646153119110539,0.14980580451858633,0.14767730454775546,0.32219344047552845,0.9524815733559516,0.44427084759213203,-0.017498544717411926,0.044779982593842006,-0.08090903565544025,-0.030249488521131195,-0.0036241960907817776,0.07288506456655813,0.0026592552916954657,0.012349339449734856,-0.037993287060088116,0.32219344047552845,0.9524815733559516,0.44427084759213203,-0.017498544717411926,0.044779982593842006,-0.08090903565544025,-0.030249488521131195,-0.0036241960907817776,0.07288506456655813,0.0026592552916954657,0.012349339449734856,-0.037993287060088116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.866686399999999,0.0,1.0,1.0,1.0,-0.2352721496106657,0.2845817151527569,0.551706403457007,0.951234738982806,-0.013090713348940637,-0.033617565869736334,0.30635104674429126,-0.02970835970678176,-0.012040027777019298,-0.0387237059452173,0.41887256816240004,0.09288483791155408,0.21022795107132594,0.054017279157799955,1.0091109770284945,0.3996080555170806,-0.013486740786062755,0.05214554412874579,-0.057174759469738407,-0.022065969052688095,-0.01853494713635561,0.05202109307618535,0.018144428139245192,0.005535016054498136,-0.02917141218822314,0.054017279157799955,1.0091109770284945,0.3996080555170806,-0.013486740786062755,0.05214554412874579,-0.057174759469738407,-0.022065969052688095,-0.01853494713635561,0.05202109307618535,0.018144428139245192,0.005535016054498136,-0.02917141218822314,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.883353099999999,0.0,1.0,1.0,1.0,-0.2354906565046706,0.28416263193863583,0.5512515515574091,0.9507590236901237,-0.010885733016572877,-0.03231317547195975,0.3080497336136053,-0.023954500437344456,-0.013207425213962287,-0.010329596839113725,0.20928437709681863,0.047549951359462536,0.1823245421933206,-0.1839157829178994,0.9837344514503936,0.36715665936910147,-0.007492821532905585,0.039997981436309706,-0.028678772709044804,-0.01156990587516225,-0.021738970445348362,0.026118542197901815,0.020810001510687105,-0.0004432522874022354,-0.013637178775635861,-0.1839157829178994,0.9837344514503936,0.36715665936910147,-0.007492821532905585,0.039997981436309706,-0.028678772709044804,-0.01156990587516225,-0.021738970445348362,0.026118542197901815,0.020810001510687105,-0.0004432522874022354,-0.013637178775635861,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.900019799999999,0.0,1.0,1.0,1.0,-0.2356363863812455,0.2837565690909875,0.5513370539399132,0.9503654224484677,-0.010115963839347287,-0.0317582503913977,0.3093455101048406,-0.0051361283436361805,-0.022598546838802056,0.0010263622687659757,0.10348088733486627,-0.006716396256424591,0.1744841869019802,-0.32325547374790825,0.9548274082993978,0.3307220997155458,-0.0034738389239995244,0.035857852832646905,-0.009577622277943733,-0.004803383605838488,-0.023309749126104184,0.009199958590425626,0.02471975987816838,-0.002755912996747769,-0.009561987616852289,-0.32325547374790825,0.9548274082993978,0.3307220997155458,-0.0034738389239995244,0.035857852832646905,-0.009577622277943733,-0.004803383605838488,-0.023309749126104184,0.009199958590425626,0.02471975987816838,-0.002755912996747769,-0.009561987616852289,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.916686499999999,0.0,1.0,1.0,1.0,-0.2351885930936689,0.28345288092687215,0.5513057095868531,0.9498732480122537,-0.00930335513044689,-0.031856742533483605,0.31086879587556526,0.010965597091987155,-0.030757833232348607,0.0035187272050986075,0.08557278937576852,-0.07539432035852982,0.16169499985061875,-0.4625258842610286,1.01491116944635,0.2522514267758073,-0.0009084824070710741,0.034873918330235745,0.0027345126632682022,-0.0005905708653509794,-0.01993968192745872,-0.0008888766147477286,0.026575838543281688,-0.0008005694844134574,-0.016201890510199907,-0.4625258842610286,1.01491116944635,0.2522514267758073,-0.0009084824070710741,0.034873918330235745,0.0027345126632682022,-0.0005905708653509794,-0.01993968192745872,-0.0008888766147477286,0.026575838543281688,-0.0008005694844134574,-0.016201890510199907,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.933353199999999,0.0,1.0,1.0,1.0,-0.23474514801768318,0.28314547781458643,0.5515125210899264,0.9495014210525353,-0.008455576167061258,-0.03248299318135882,0.3119621929094596,0.010981287184296223,-0.0166741799874451,0.02897757724811084,0.09868412800620924,-0.159390470841479,0.1965798032768769,-0.5986233857678788,1.0562671258300353,0.13385457741929285,0.0009579316877360946,0.04417208675183373,0.014300625922770227,0.0029338622578518733,-0.02236692711853244,-0.009884905440082822,0.03581459023972988,0.0010742327532951112,-0.027327601410292213,-0.5986233857678788,1.0562671258300353,0.13385457741929285,0.0009579316877360946,0.04417208675183373,0.014300625922770227,0.0029338622578518733,-0.02236692711853244,-0.009884905440082822,0.03581459023972988,0.0010742327532951112,-0.027327601410292213,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9500199,0.0,1.0,1.0,1.0,-0.23463028362041533,0.2832183213239313,0.5523102918522692,0.948775825402281,-0.0070191632170730255,-0.033838418553966416,0.3140543359193106,0.018171090576143314,0.0012169542197404894,0.049124967669777767,0.125309878584335,-0.20572878068793696,0.24828690579859716,-0.6781975959565598,0.9569282182529584,-0.025295173877143685,0.0011248711511638654,0.055913348962005595,0.018805634912327614,0.0040006498199440625,-0.028052589279874696,-0.013016254682335476,0.045475413182052234,0.0017591731015975333,-0.035055262728541356,-0.6781975959565598,0.9569282182529584,-0.025295173877143685,0.0011248711511638654,0.055913348962005595,0.018805634912327614,0.0040006498199440625,-0.028052589279874696,-0.013016254682335476,0.045475413182052234,0.0017591731015975333,-0.035055262728541356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9666866,0.0,1.0,1.0,1.0,-0.23439683087568497,0.28352629125866036,0.553180931377548,0.9481008437164611,-0.005537339758600938,-0.03505089257810586,0.31598348523619196,0.019260922443940294,-0.0018480089403856838,0.04622110720948966,0.1403739425574707,-0.16647144226907326,0.2355502676527471,-0.7485503945536235,0.7548239756649675,-0.2343830246569889,-0.0005622088922518886,0.053071888787256744,0.011470886262347336,0.0016984398074258405,-0.02663905683321691,-0.006866930566641475,0.04125215779176019,0.0019386293638790717,-0.031905740839272535,-0.7485503945536235,0.7548239756649675,-0.2343830246569889,-0.0005622088922518886,0.053071888787256744,0.011470886262347336,0.0016984398074258405,-0.02663905683321691,-0.006866930566641475,0.04125215779176019,0.0019386293638790717,-0.031905740839272535,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +9.9833533,0.0,1.0,1.0,1.0,-0.23418894455383094,0.2835360093599443,0.553889554616749,0.947451355720454,-0.004063002192922162,-0.0357079174522978,0.3178747633705354,0.004048939355450931,-0.0028897492451408066,0.03262472624737547,0.10232083275001946,-0.11070818619532297,0.25722991593162164,-0.8814900847299003,0.5823778286482186,-0.47719467617646694,-0.00180815206813296,0.05370486690263196,0.007031567977772413,0.0004238886276532281,-0.03335892724551823,-0.004026788309471416,0.042762081780292366,-0.002056531317467558,-0.021082343436991537,-0.8814900847299003,0.5823778286482186,-0.47719467617646694,-0.00180815206813296,0.05370486690263196,0.007031567977772413,0.0004238886276532281,-0.03335892724551823,-0.004026788309471416,0.042762081780292366,-0.002056531317467558,-0.021082343436991537,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.00002,0.0,1.0,1.0,1.0,-0.23430788442953185,0.28351445477278386,0.5542773271213784,0.9466793334799671,-0.0034886557531914764,-0.036241913266843444,0.32011340578882264,-0.005918135513317669,0.024795183102854473,0.013734993414933071,0.08092665448240319,-0.06119087292971841,0.3348710874253092,-1.087287696085609,0.49582766246151505,-0.664192136099278,-0.0039749724887618324,0.0653074241475888,0.0018860170135790357,-0.0013319478047137349,-0.04823486865243382,-0.0004238642046118573,0.0528496210624957,-0.0073007211700517535,-0.012110824644925142,-1.087287696085609,0.49582766246151505,-0.664192136099278,-0.0039749724887618324,0.0653074241475888,0.0018860170135790357,-0.0013319478047137349,-0.04823486865243382,-0.0004238642046118573,0.0528496210624957,-0.0073007211700517535,-0.012110824644925142,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0166867,0.0,1.0,1.0,1.0,-0.23487843538716238,0.28406589507502256,0.5543084420304332,0.9456299005264279,-0.0026637321513584885,-0.03622198609216648,0.3232104012635465,9.03883331427411e-05,0.06615215606462632,-0.005947735082243049,0.006465574357619816,0.01031920862030471,0.40562658984488686,-1.2017087015966323,0.31360227541835395,-0.7882190466745904,-0.00554955369879713,0.07279379362277823,-0.0012458401093012653,-0.001868947830138023,-0.06477716153979937,0.0006091559469381133,0.06217418873012717,-0.015129604438225292,0.004736279736955381,-1.2017087015966323,0.31360227541835395,-0.7882190466745904,-0.00554955369879713,0.07279379362277823,-0.0012458401093012653,-0.001868947830138023,-0.06477716153979937,0.0006091559469381133,0.06217418873012717,-0.015129604438225292,0.004736279736955381,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0333534,0.0,1.0,1.0,1.0,-0.2356390679156939,0.28526427901492657,0.5540170533261319,0.9444996462410096,-0.0036877643869724537,-0.036032627800370316,0.3265095226455639,0.011040789892297936,0.09393242358247633,-0.01804628353864649,-0.10887659684504325,0.07731357602790506,0.45366105926738054,-1.029082772413115,0.0363712097860583,-0.7214352041007543,-0.0059185787354991744,0.07456240050950118,0.0001296728220903217,-0.0003402330746466794,-0.07916768740439922,-0.002605425944012669,0.06924682721216203,-0.02350018440773544,0.025060414485678268,-1.029082772413115,0.0363712097860583,-0.7214352041007543,-0.0059185787354991744,0.07456240050950118,0.0001296728220903217,-0.0003402330746466794,-0.07916768740439922,-0.002605425944012669,0.06924682721216203,-0.02350018440773544,0.025060414485678268,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0500201,1.0,1.0,1.0,1.0,-0.23647778853120133,0.2867663481930397,0.5536371539610986,0.9431986715335354,-0.005071645986373048,-0.035570201046457445,0.3302806461509327,0.014431215249156023,0.11651757497453118,-0.0197531486183394,-0.15867297675153771,0.10314074605299033,0.5439124681698327,-0.4803188211311082,-0.029217498237757246,-0.3166817366174919,-0.007450845440094112,0.0878835296761098,0.001110283474667465,0.000969711004135069,-0.09636587356421487,-0.004296321745868353,0.08343901434359528,-0.028887048212567684,0.03426678318916376,-0.4803188211311082,-0.029217498237757246,-0.3166817366174919,-0.007450845440094112,0.0878835296761098,0.001110283474667465,0.000969711004135069,-0.09636587356421487,-0.004296321745868353,0.08343901434359528,-0.028887048212567684,0.03426678318916376,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0666868,1.0,1.0,1.0,1.0,-0.2376362485631565,0.2886097008400833,0.5532625638910202,0.9415481146331661,-0.007071295110280574,-0.03523965314645079,0.3349556858187534,0.014685527432069745,0.13651882524007133,-0.01963132016600101,-0.2501417261361588,0.115969603612464,0.6094090602203056,-0.09805209937697092,0.01896440645131,-0.04925624766773389,-0.007401289245265569,0.09544558861514238,0.008149066840249793,0.004903105584323172,-0.11079066450026,-0.011401971662025466,0.09555391571602602,-0.0343094823364093,0.04600334284596321,-0.09805209937697092,0.01896440645131,-0.04925624766773389,-0.007401289245265569,0.09544558861514238,0.008149066840249793,0.004903105584323172,-0.11079066450026,-0.011401971662025466,0.09555391571602602,-0.0343094823364093,0.04600334284596321,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.0833535,1.0,1.0,1.0,1.0,-0.23892086825653636,0.29061115372652246,0.5528466065241788,0.93983241477191,-0.010001411790142427,-0.03507934912825013,0.3396828567516221,0.01527261933779894,0.15171642388780576,-0.010748624851417539,-0.3012022497864278,0.0995141772383277,0.645534603237428,-0.10192231856582594,0.018092572701751717,-0.05248977704467957,-0.007349198007595522,0.10035623522163316,0.015211916924274975,0.008944809032064904,-0.11799956052485824,-0.01771960462355958,0.10351792959028866,-0.03573589800496016,0.04998208934540329,-0.10192231856582594,0.018092572701751717,-0.05248977704467957,-0.007349198007595522,0.10035623522163316,0.015211916924274975,0.008944809032064904,-0.11799956052485824,-0.01771960462355958,0.10351792959028866,-0.03573589800496016,0.04998208934540329,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1000202,1.0,1.0,1.0,1.0,-0.2404452739925001,0.2928260713846944,0.5527197434861785,0.9378992361875023,-0.012728165541306818,-0.03527590057604426,0.34487479960037953,0.02113673173809971,0.15281584775970614,-0.0019855382714395638,-0.3092497310303857,0.05405021499625898,0.6773036842555417,-0.10586561960179265,0.019497478489957372,-0.047067042680017546,-0.007612719831388417,0.10723520162538733,0.022380370868992958,0.01289172443970071,-0.12185874202839056,-0.023356754104876663,0.11114462421008912,-0.034121018892952285,0.046090659444130516,-0.10586561960179265,0.019497478489957372,-0.047067042680017546,-0.007612719831388417,0.10723520162538733,0.022380370868992958,0.01289172443970071,-0.12185874202839056,-0.023356754104876663,0.11114462421008912,-0.034121018892952285,0.046090659444130516,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1166869,1.0,1.0,1.0,1.0,-0.24167143163918536,0.2949481119788956,0.5525754831274269,0.9359046286762259,-0.01554215087044837,-0.03586869195790503,0.35007771209542154,0.024525864562278746,0.14292435656369917,-0.002431119840319943,-0.3170453492377304,-0.0033689569627966265,0.6605605438852902,-0.10118587999751896,0.019010975523868864,-0.03927670907350418,-0.006714739508721823,0.10594364441060879,0.031371407553423,0.01724083046280016,-0.11756588951084365,-0.030416009373824947,0.11171197095158314,-0.030633220624085418,0.04023210725309557,-0.10118587999751896,0.019010975523868864,-0.03927670907350418,-0.006714739508721823,0.10594364441060879,0.031371407553423,0.01724083046280016,-0.11756588951084365,-0.030416009373824947,0.11171197095158314,-0.030633220624085418,0.04023210725309557,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1333536,1.0,1.0,1.0,1.0,-0.24294044574596477,0.29695648760510407,0.5524267019554904,0.9339622552095184,-0.01804559510363341,-0.03700633302326014,0.35499210365510653,0.026503932354873583,0.1406267611368231,0.0005268948680253096,-0.35773480624817966,-0.06153974692228925,0.6068573560862064,-0.08862974592542562,0.0158166784315585,-0.03401070216180221,-0.004041035617989462,0.0969714256249071,0.04411986950005094,0.022711498657866085,-0.10861649579790716,-0.04089986975608831,0.10730020896529142,-0.027461748604528588,0.03723070190576317,-0.08862974592542562,0.0158166784315585,-0.03401070216180221,-0.004041035617989462,0.0969714256249071,0.04411986950005094,0.022711498657866085,-0.10861649579790716,-0.04089986975608831,0.10730020896529142,-0.027461748604528588,0.03723070190576317,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1500203,1.0,1.0,1.0,1.0,-0.24411655044760744,0.29903831370989337,0.5523615689647985,0.9321686488987091,-0.021116869040180217,-0.03876516381331011,0.35932290481796786,0.04396348925775577,0.13736977017733779,0.013258763125268403,-0.43647079362819113,-0.1049156671359336,0.586876028337497,-0.08068339744128299,0.012360571005674904,-0.0352908794427802,-0.0016664738988253582,0.0922347702304835,0.058361792608134816,0.02931603839854708,-0.10706345493064202,-0.053073066926348195,0.10833296194098639,-0.02718925570581843,0.04057960512456348,-0.08068339744128299,0.012360571005674904,-0.0352908794427802,-0.0016664738988253582,0.0922347702304835,0.058361792608134816,0.02931603839854708,-0.10706345493064202,-0.053073066926348195,0.10833296194098639,-0.02718925570581843,0.04057960512456348,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.166687,1.0,1.0,1.0,1.0,-0.24495643558280267,0.3013381803455419,0.5526427760109013,0.9302226133327064,-0.024575421217403234,-0.04104455997142083,0.3638643736520654,0.06392637002286204,0.12401327474185309,0.018970707800498608,-0.4360228581993499,-0.09885582982833677,0.5637183768692042,-0.07667338817047514,0.010261878978359576,-0.03633340015540336,-0.0022936511886549266,0.088110471549758,0.05705971038951632,0.02998098310535687,-0.10353823463260946,-0.051702256722570956,0.10436072008715709,-0.02568964206119771,0.04169085382235372,-0.07667338817047514,0.010261878978359576,-0.03633340015540336,-0.0022936511886549266,0.088110471549758,0.05705971038951632,0.02998098310535687,-0.10353823463260946,-0.051702256722570956,0.10436072008715709,-0.02568964206119771,0.04169085382235372,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.1833537,1.0,1.0,1.0,1.0,-0.24540671461280517,0.3035293247787111,0.5528031652610909,0.9285092569506908,-0.027664621045084367,-0.04271173120988218,0.36780556890341226,0.08050202251145194,0.10922480600160711,0.00963995964585314,-0.3667475973550525,-0.05482490793777422,0.5181766818282837,-0.07272771149389928,0.008600564675114223,-0.03608432324129176,-0.004778645929404456,0.08105634415638326,0.042998582559935876,0.025344410357719598,-0.09500738648472101,-0.03928752131882812,0.09329347592219776,-0.02255160700344282,0.03979538448239951,-0.07272771149389928,0.008600564675114223,-0.03608432324129176,-0.004778645929404456,0.08105634415638326,0.042998582559935876,0.025344410357719598,-0.09500738648472101,-0.03928752131882812,0.09329347592219776,-0.02255160700344282,0.03979538448239951,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2000204,1.0,1.0,1.0,1.0,-0.24551903857141746,0.3058339489179511,0.5528192389415593,0.9268406024639222,-0.030285609353549278,-0.04390068545807613,0.371647695145159,0.10442229522752919,0.11653749218573814,0.007272058768131334,-0.261520775632606,-0.04229999350410983,0.5351816345065974,-0.08072073628666117,0.012116624075882466,-0.028689975334044285,-0.009081735891219911,0.0873629832819677,0.02962195794124989,0.021125227190640226,-0.09394481684573036,-0.027164995425515637,0.09276422758606316,-0.018698457639639295,0.031146937849778535,-0.08072073628666117,0.012116624075882466,-0.028689975334044285,-0.009081735891219911,0.0873629832819677,0.02962195794124989,0.021125227190640226,-0.09394481684573036,-0.027164995425515637,0.09276422758606316,-0.018698457639639295,0.031146937849778535,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2166871,1.0,1.0,1.0,1.0,-0.24559192907715943,0.30874659455983255,0.5529042498558414,0.9250320356637378,-0.031836118313014035,-0.04470931387272806,0.37590327455289735,0.12645860198080153,0.13391273153190567,0.0149421615948905,-0.16134510073412678,-0.05578260838929598,0.5771914553589859,-0.09242391716084869,0.01732382567426034,-0.01820641462294898,-0.01352210046600172,0.09876492332436287,0.020655074093144828,0.018743437336286074,-0.09613060387653892,-0.01875102191339115,0.09764525403111972,-0.014689506226428055,0.020110466802702655,-0.09242391716084869,0.01732382567426034,-0.01820641462294898,-0.01352210046600172,0.09876492332436287,0.020655074093144828,0.018743437336286074,-0.09613060387653892,-0.01875102191339115,0.09764525403111972,-0.014689506226428055,0.020110466802702655,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2333538,1.0,1.0,1.0,1.0,-0.24565658248232064,0.31198327823219313,0.5531491380120213,0.923096518391776,-0.032854201477475135,-0.04546227646446885,0.38045578008084896,0.13017045948097403,0.13867424043675586,0.01814096363077619,-0.07318581160830663,-0.037497231908688214,0.6166477353580357,-0.10393658163348071,0.020436398167369342,-0.013658901768967594,-0.018432310130508653,0.10783714651887139,0.008154136168736677,0.015347771384988112,-0.09942911183940038,-0.007767724943818205,0.10085204288795768,-0.012028363487895846,0.01404531299388107,-0.10393658163348071,0.020436398167369342,-0.013658901768967594,-0.018432310130508653,0.10783714651887139,0.008154136168736677,0.015347771384988112,-0.09942911183940038,-0.007767724943818205,0.10085204288795768,-0.012028363487895846,0.01404531299388107,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2500205,1.0,1.0,1.0,1.0,-0.24582582992128105,0.3150973514684035,0.553320574294994,0.9210525587382855,-0.03319577056420067,-0.045408848587870185,0.3853547214297886,0.13728636324700386,0.13042849941376627,0.0058583311261866085,-0.06068447081407388,0.003598366186749913,0.6532824946666734,-0.11192900306732578,0.019418809644389745,-0.019463820880353717,-0.021972749392736978,0.11290641477533836,0.00017806445903555118,0.01447568143898857,-0.10592126415962931,-0.0012733902498141638,0.10443193511357904,-0.012433659028680691,0.018368495089570107,-0.11192900306732578,0.019418809644389745,-0.019463820880353717,-0.021972749392736978,0.11290641477533836,0.00017806445903555118,0.01447568143898857,-0.10592126415962931,-0.0012733902498141638,0.10443193511357904,-0.012433659028680691,0.018368495089570107,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2666872,1.0,1.0,1.0,1.0,-0.24555280091339993,0.31829748979246686,0.5531908805127586,0.9188681215562396,-0.03430275166673601,-0.04543926379110996,0.39043561533487164,0.15464153473526032,0.13150226126507464,-0.0026062620837195172,-0.08365470359757218,0.035595052779572284,0.647670464255531,-0.11065594054537715,0.015817577726037358,-0.02650032967817801,-0.022961774974799024,0.10958660454606799,-0.0025239115542920417,0.014960223947821262,-0.10684929549108053,0.0006522651561514151,0.10265438951839939,-0.013080268671039069,0.024628683280039046,-0.11065594054537715,0.015817577726037358,-0.02650032967817801,-0.022961774974799024,0.10958660454606799,-0.0025239115542920417,0.014960223947821262,-0.10684929549108053,0.0006522651561514151,0.10265438951839939,-0.013080268671039069,0.024628683280039046,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.2833539,1.0,1.0,1.0,1.0,-0.24538589431602303,0.32184632093474724,0.5530947733381216,0.9168191391336837,-0.0352014583736177,-0.045037144781647706,0.3951900543238133,0.1667082657668524,0.14467656875125573,0.00797616477185935,-0.09107412143732539,0.05021732931025645,0.6404658274306254,-0.10946260407157553,0.01347502589179746,-0.0292865951529857,-0.023935468092618126,0.10725679892048882,-0.00418280482222611,0.015612293276595331,-0.10629906544827249,0.0019545251434788433,0.10113942925554524,-0.012517292419566128,0.027058315474240098,-0.10946260407157553,0.01347502589179746,-0.0292865951529857,-0.023935468092618126,0.10725679892048882,-0.00418280482222611,0.015612293276595331,-0.10629906544827249,0.0019545251434788433,0.10113942925554524,-0.012517292419566128,0.027058315474240098,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3000206,1.0,1.0,1.0,1.0,-0.2452627692922416,0.32565385412786396,0.5532763637980195,0.9146323686361679,-0.036504375452603835,-0.04489786594568528,0.40012403383117556,0.18128528226425206,0.14344079877054722,0.012060779596336443,-0.12313858470395024,0.0397593719573001,0.6558524570147917,-0.11056370545566233,0.01189319609856642,-0.031147837823662566,-0.024670003093962892,0.1090927511103742,0.000254783561077487,0.01912650295415138,-0.10941267095980627,-0.0018785086632329515,0.10502020531584665,-0.012213115947993488,0.02952411272150377,-0.11056370545566233,0.01189319609856642,-0.031147837823662566,-0.024670003093962892,0.1090927511103742,0.000254783561077487,0.01912650295415138,-0.10941267095980627,-0.0018785086632329515,0.10502020531584665,-0.012213115947993488,0.02952411272150377,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3166873,1.0,1.0,1.0,1.0,-0.2448310458523258,0.3295391330459331,0.553322807366908,0.9124000654040657,-0.03783394608940123,-0.04485331453741324,0.40507146696474305,0.19141171948282673,0.13541865338251757,0.006243463630806734,-0.10974455309366445,0.03329118138183314,0.6659610181185883,-0.11299910722771381,0.011632486127878176,-0.029252358640065493,-0.02653328372291605,0.1112592973371984,-0.0006384333796046391,0.020207427957044104,-0.11007950186483492,-0.0009688114793608905,0.10667325146183769,-0.010452690655507194,0.02764511378109663,-0.11299910722771381,0.011632486127878176,-0.029252358640065493,-0.02653328372291605,0.1112592973371984,-0.0006384333796046391,0.020207427957044104,-0.11007950186483492,-0.0009688114793608905,0.10667325146183769,-0.010452690655507194,0.02764511378109663,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.333354,1.0,1.0,1.0,1.0,-0.24434656814581196,0.3334182588834033,0.5533340388117374,0.9100916822665134,-0.03889631472437279,-0.044710928427841815,0.41014770443011234,0.19782665903843674,0.13476307049914207,0.006946761835224528,-0.1066980705741011,0.029747405953957404,0.6711813098183375,-0.11410590963686146,0.010730928887465812,-0.028612007400993403,-0.027986046482582735,0.11213677751434696,-0.0007808520945739241,0.021572092965693804,-0.11043281377738069,-0.0007647516102465537,0.10769195611996754,-0.009026965150491223,0.02706640369617459,-0.11410590963686146,0.010730928887465812,-0.028612007400993403,-0.027986046482582735,0.11213677751434696,-0.0007808520945739241,0.021572092965693804,-0.11043281377738069,-0.0007647516102465537,0.10769195611996754,-0.009026965150491223,0.02706640369617459,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3500207,1.0,1.0,1.0,1.0,-0.24384592236088465,0.33746003990848583,0.5533962061183942,0.9077650169439254,-0.04015513725268593,-0.04469752678372615,0.41515342954675305,0.1933826003465388,0.04783877707371176,0.018900704848971158,-0.9668283931148237,-0.021397498320868295,0.32221813384007586,-0.007657789026453064,-0.027961965418170847,-0.09246648620081553,0.010370517720979359,0.02924163919226214,0.1022656342218327,0.05925003905083602,-0.08631706144654383,-0.09008442214384293,0.07727834579823263,-0.029113456836081693,0.10464769827879862,-0.007657789026453064,-0.027961965418170847,-0.09246648620081553,0.010370517720979359,0.02924163919226214,0.1022656342218327,0.05925003905083602,-0.08631706144654383,-0.09008442214384293,0.07727834579823263,-0.029113456836081693,0.10464769827879862,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3666874,1.0,1.0,1.0,1.0,-0.24141654386606845,0.33936233423834244,0.5540922595568842,0.9071045011567939,-0.05357343658208103,-0.05157891669909836,0.4142836301690152,0.04080438252810677,-0.10922684329218256,0.03258782710670549,-2.864680471639682,-0.09209580101793224,-0.2800163682851485,0.20246059509197417,-0.11600571425656336,-0.2364558796024474,0.07912707991388235,-0.12075583316006101,0.3255472860722064,0.14959250076473,-0.06754482582530867,-0.2753999082460788,0.02625898558652242,-0.07229494472871972,0.2866032574285517,0.20246059509197417,-0.11600571425656336,-0.2364558796024474,0.07912707991388235,-0.12075583316006101,0.3255472860722064,0.14959250076473,-0.06754482582530867,-0.2753999082460788,0.02625898558652242,-0.07229494472871972,0.2866032574285517,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.3833541,1.0,1.0,1.0,1.0,-0.24039339325332862,0.336178775432351,0.5550468254391495,0.9066726212004952,-0.0825309350737988,-0.06614980640073885,0.40835965255447637,-0.0638206375336238,-0.11885242700551338,0.004162495038456639,-3.0557773854547157,-0.020942803126496934,-0.2952001921632151,0.22125265097477576,-0.13445623155222494,-0.25782623954921197,0.07460523165440615,-0.12621363637431848,0.33808084236624597,0.16156998095400676,-0.0813256128414526,-0.2768869228135296,0.014922561633523896,-0.07308301766345038,0.3190201591019067,0.22125265097477576,-0.13445623155222494,-0.25782623954921197,0.07460523165440615,-0.12621363637431848,0.33808084236624597,0.16156998095400676,-0.0813256128414526,-0.2768869228135296,0.014922561633523896,-0.07308301766345038,0.3190201591019067,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4000208,1.0,1.0,1.0,1.0,-0.2399513636740692,0.33519059202688706,0.5549230590005504,0.9052480233121732,-0.09932866881314141,-0.07306225188778386,0.40659776092632194,0.12174663979850729,0.05457003910132399,-0.03911444333061565,-1.094927005087356,0.12536068196375252,0.346863347801674,0.002212291038040395,-0.04852771274366273,-0.12782678894664098,0.003546435652163879,0.027226435629528044,0.0886811241943895,0.06327926405394368,-0.1051994310683225,-0.06988192070169395,0.06461340866803636,-0.02944528269508926,0.14662599243932323,0.002212291038040395,-0.04852771274366273,-0.12782678894664098,0.003546435652163879,0.027226435629528044,0.0886811241943895,0.06327926405394368,-0.1051994310683225,-0.06988192070169395,0.06461340866803636,-0.02944528269508926,0.14662599243932323,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4166875,1.0,1.0,1.0,1.0,-0.23875518294191647,0.3402497813010532,0.5535564821377221,0.9028152916806991,-0.10037647842287274,-0.07101217997969574,0.4120756993338095,0.2724634700363212,0.1854130613845579,-0.06844660650761057,-0.012279873643433869,0.21452232151409587,0.8191173965202937,-0.14237138255681772,0.0033332250192581662,-0.06572131652349918,0.09973773914541358,0.23464722767683205,0.020476679985670553,0.00916164886407182,-0.13287439943008483,0.04507196901606431,0.11505014373008518,-0.00821874051056667,0.05481038206789968,-0.14237138255681772,0.0033332250192581662,-0.06572131652349918,0.09973773914541358,0.23464722767683205,0.020476679985670553,0.00916164886407182,-0.13287439943008483,0.04507196901606431,0.11505014373008518,-0.00821874051056667,0.05481038206789968,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4333542,1.0,0.0,1.0,1.0,-0.2380744420069107,0.34575464564879504,0.5516418194833783,0.8998472154112236,-0.10195542629263149,-0.06854978428564557,0.41854630214654415,0.2703684638332275,0.2140009828027333,-0.06275039787585616,0.08319549949906463,0.18788777779467936,0.9260690051321654,-0.1669302618335622,0.008769094051230298,-0.05745216305816752,0.3030609776141012,0.5269113887379289,0.10554536892897406,0.009901628290566409,-0.14416074348520297,0.05354098631253701,0.13180627497091554,-0.0041324910227374815,0.04438930828506893,-0.1669302618335622,0.008769094051230298,-0.05745216305816752,0.3030609776141012,0.5269113887379289,0.10554536892897406,0.009901628290566409,-0.14416074348520297,0.05354098631253701,0.13180627497091554,-0.0041324910227374815,0.04438930828506893,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4500209,1.0,0.0,1.0,1.0,-0.23782213082082151,0.35138635889059444,0.5501523867870197,0.8967106040633983,-0.1014957478061434,-0.06602445593603617,0.4257340448635482,0.2861168737304405,0.18889004564154832,-0.028993884788193897,0.1992266038487649,0.08850561659052153,0.8713942967744879,-0.16441001411683662,0.016571521532170144,-0.03002064954456214,0.32501041718387497,0.977209504268071,0.1765787523634845,0.009376393061614065,-0.1278733312066347,0.05043050146942224,0.1273048858383368,0.0023534549020432526,0.017416986889597624,-0.16441001411683662,0.016571521532170144,-0.03002064954456214,0.32501041718387497,0.977209504268071,0.1765787523634845,0.009376393061614065,-0.1278733312066347,0.05043050146942224,0.1273048858383368,0.0023534549020432526,0.017416986889597624,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4666876,1.0,0.0,1.0,1.0,-0.23660262931713555,0.35692696979226046,0.5495087256846457,0.8941100192550883,-0.10056294694813206,-0.06433586555273696,0.43164251826291744,0.3243754648432503,0.14454895361482992,-0.023175187623278352,0.20858979164588148,0.039122119600827704,0.7013598227529276,-0.13540009484048413,0.015597510001231671,-0.014730808771948925,0.23121113196106702,1.4111918388087388,0.22140018473747547,0.008056477972799316,-0.09989913160715042,0.04096233170683114,0.10345292352116217,0.004889404581933642,0.00444796496089102,-0.13540009484048413,0.015597510001231671,-0.014730808771948925,0.23121113196106702,1.4111918388087388,0.22140018473747547,0.008056477972799316,-0.09989913160715042,0.04096233170683114,0.10345292352116217,0.004889404581933642,0.00444796496089102,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.4833543,1.0,0.0,1.0,1.0,-0.2346290133227023,0.3627015527683901,0.5485730805240558,0.8920636248443757,-0.09942313242296046,-0.0627632852103366,0.4363465365948553,0.3563042020540438,0.11864698689697381,-0.0330911454780699,0.20932915089183535,0.06453858823798159,0.5671997909872819,-0.11213481292842699,0.011281679262169933,-0.012778691495677782,-0.00440659784591461,1.7369595382254752,0.11464182407118166,0.003291270932185711,-0.07979249420788384,0.04053104294629854,0.08103867042637616,0.004740435976063297,0.0027192248008823584,-0.11213481292842699,0.011281679262169933,-0.012778691495677782,-0.00440659784591461,1.7369595382254752,0.11464182407118166,0.003291270932185711,-0.07979249420788384,0.04053104294629854,0.08103867042637616,0.004740435976063297,0.0027192248008823584,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.500021,1.0,0.0,1.0,1.0,-0.2321523327905445,0.3685567410056558,0.5478174610609834,0.8904026222607611,-0.09851667280301257,-0.06091449304090498,0.44018979995969276,0.3656867082314948,0.09813215378311772,-0.02462119872819451,0.24006369978419928,0.08492346948818597,0.4906651153295753,-0.10066045997461136,0.009703443126051049,-0.009803717942656122,-0.17136773348792708,1.890168067485706,0.11836411062515673,-0.0015042769546797475,-0.06720408387760186,0.0436412950397563,0.06724059183909477,0.0050376648656749795,-0.0009407172787799851,-0.10066045997461136,0.009703443126051049,-0.009803717942656122,-0.17136773348792708,1.890168067485706,0.11836411062515673,-0.0015042769546797475,-0.06720408387760186,0.0436412950397563,0.06724059183909477,0.0050376648656749795,-0.0009407172787799851,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5166877,1.0,0.0,1.0,1.0,-0.2296184748646667,0.3742431307251376,0.5472901577203526,0.8889451381442338,-0.09698303431772454,-0.05893321933945621,0.4437315721047398,0.3711539416477447,0.08593446110516742,-0.016193040663770912,0.2738977157986779,0.031032198244274556,0.47189308410058467,-0.09935018229554994,0.013390619858595085,0.0022364227580522703,-0.17987725800508408,2.192039913455445,0.2759645935005226,-0.0005223036311823576,-0.06147677853735904,0.039546539111758844,0.06648577827489899,0.007479008703592167,-0.01205691249291136,-0.09935018229554994,0.013390619858595085,0.0022364227580522703,-0.17987725800508408,2.192039913455445,0.2759645935005226,-0.0005223036311823576,-0.06147677853735904,0.039546539111758844,0.06648577827489899,0.007479008703592167,-0.01205691249291136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5333544,1.0,0.0,1.0,1.0,-0.22686246989648517,0.38007611093128113,0.5468793207302232,0.8873870471509416,-0.09514865631821214,-0.05766547185238403,0.44739876520349625,0.3748780924934134,0.07701443013995596,-0.008686573625752776,0.25790932196690564,-0.03517376505021086,0.4360202268080005,-0.09201986692191705,0.01565893505504997,0.012241854325356925,-0.19505022098130959,2.4911004515440704,0.3560294808724524,0.003235835997651518,-0.05497025729521864,0.02921596698330397,0.06467353658147923,0.00913770672780751,-0.019577317654637442,-0.09201986692191705,0.01565893505504997,0.012241854325356925,-0.19505022098130959,2.4911004515440704,0.3560294808724524,0.003235835997651518,-0.05497025729521864,0.02921596698330397,0.06467353658147923,0.00913770672780751,-0.019577317654637442,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5500211,1.0,0.0,1.0,1.0,-0.22416408783063357,0.38576144965615644,0.5466567880881021,0.8860720592630809,-0.0933247089968329,-0.05683790764404323,0.4504844689205022,0.36190724640680827,0.08134731949456259,0.0099232126324948,0.25038122933873314,-0.08981411972154348,0.3916657519817337,-0.08367516393149939,0.01760439667668731,0.02151635721265163,-0.1111062241405224,2.6411756466170333,0.4017042914155901,0.005349521135982685,-0.04704515427592514,0.020735515924395247,0.06063931179046545,0.010603474094272267,-0.026841776414671444,-0.08367516393149939,0.01760439667668731,0.02151635721265163,-0.1111062241405224,2.6411756466170333,0.4017042914155901,0.005349521135982685,-0.04704515427592514,0.020735515924395247,0.06063931179046545,0.010603474094272267,-0.026841776414671444,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5666878,1.0,0.0,1.0,1.0,-0.22197018126085366,0.3914363033405872,0.546815649636576,0.884751146999178,-0.09114608842960908,-0.056501539860219906,0.45355856781792236,0.36929775621504934,0.08193775719303462,0.008012458937127476,0.3063816370911232,-0.0922180893437776,0.35776273148819154,-0.08102645269020009,0.019242163147911703,0.0281569214165752,-0.015074053623023819,2.79223852417401,0.40149708746623947,0.0012199523203673943,-0.03965845511803681,0.024354796309859334,0.05406650503004955,0.011782829166166168,-0.03428572213201123,-0.08102645269020009,0.019242163147911703,0.0281569214165752,-0.015074053623023819,2.79223852417401,0.40149708746623947,0.0012199523203673943,-0.03965845511803681,0.024354796309859334,0.05406650503004955,0.011782829166166168,-0.03428572213201123,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.5833545,1.0,0.0,1.0,1.0,-0.2192101193965118,0.3973594164773549,0.5465501888141152,0.8837451354506556,-0.08844958288946085,-0.055335298458334306,0.4561898854627423,0.393132777968217,0.07163786957544097,-0.020416293726010778,0.47432977967061046,0.008410245363087293,0.32340636093979874,-0.08505430735207346,0.019392935818510305,0.0296259277508916,0.05606877826730798,2.691680376146211,0.2968448395313806,-0.014794731159305193,-0.030776401935620017,0.0502408131494359,0.03935626742630924,0.012067823672202464,-0.04148914325135807,-0.08505430735207346,0.019392935818510305,0.0296259277508916,0.05606877826730798,2.691680376146211,0.2968448395313806,-0.014794731159305193,-0.030776401935620017,0.0502408131494359,0.03935626742630924,0.012067823672202464,-0.04148914325135807,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6000212,1.0,0.0,1.0,1.0,-0.21618085777973434,0.40341548109211944,0.5458801987324884,0.8829905989522364,-0.08452666686940558,-0.05229014257216719,0.4587467555631341,0.4055040146145996,0.07417747385234982,-0.02043043966383753,0.4450480785775626,-0.0002622799404107812,0.2947331998524389,-0.07805509514053904,0.01822684964838471,0.029944962653079492,0.10599093662868866,2.4911732862296674,0.15619976243996384,-0.013505405145602908,-0.027311751013479962,0.04581548662125691,0.035623198016057595,0.011810898733435157,-0.04051465345842854,-0.07805509514053904,0.01822684964838471,0.029944962653079492,0.10599093662868866,2.4911732862296674,0.15619976243996384,-0.013505405145602908,-0.027311751013479962,0.04581548662125691,0.035623198016057595,0.011810898733435157,-0.04051465345842854,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6166879,1.0,0.0,1.0,1.0,-0.21332198155191362,0.4097569660658182,0.5455948383803404,0.8821294920558436,-0.08215066911296134,-0.05152466982703433,0.460916516528544,0.4013846941254289,0.08287772257300469,-0.007307530978044711,0.2783028314484463,-0.07040896832818666,0.26027107570139857,-0.06197211362646712,0.01520584586079654,0.027053341596039834,0.147371732418121,2.1768829700315684,-0.05148374020942616,-0.0013927149897693574,-0.02672656724289978,0.021862692635344058,0.03756230289789405,0.010599967389146677,-0.031957874245925645,-0.06197211362646712,0.01520584586079654,0.027053341596039834,0.147371732418121,2.1768829700315684,-0.05148374020942616,-0.0013927149897693574,-0.02672656724289978,0.021862692635344058,0.03756230289789405,0.010599967389146677,-0.031957874245925645,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6333546,1.0,0.0,1.0,1.0,-0.2107396791252721,0.41593642915392937,0.545312598766556,0.8813128085027464,-0.08011770732522179,-0.05083148279843728,0.46290932902509524,0.4053107353790349,0.08664514359536199,-0.006325539949173654,0.30015748574795487,-0.05634317260695587,0.25651383123783417,-0.06259685239377871,0.014855963065798627,0.027300501666221274,0.1383944669016459,1.8050284927534754,-0.3177315330914836,-0.0032994988333371485,-0.02584725992848361,0.02536786747195219,0.0355483061575514,0.010810976258308947,-0.03279879150183787,-0.06259685239377871,0.014855963065798627,0.027300501666221274,0.1383944669016459,1.8050284927534754,-0.3177315330914836,-0.0032994988333371485,-0.02584725992848361,0.02536786747195219,0.0355483061575514,0.010810976258308947,-0.03279879150183787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.6500213,1.0,0.0,1.0,1.0,-0.2079700725606337,0.4224840756324762,0.5450523647457143,0.8805015564663278,-0.0775251466282417,-0.04969287967693416,0.4650134174516449,0.4279161831011695,0.08613422299025202,-0.011640330958456433,0.3410682509917393,-0.04913757843415142,0.2857894102316933,-0.07013062720369433,0.01563405045249709,0.029367758126685104,0.03073950253531425,1.516301164468114,-0.46618788300231534,-0.0044598175275400755,-0.02904479799176844,0.030406596900339325,0.03856632498625586,0.01205258179228991,-0.03576887047317157,-0.07013062720369433,0.01563405045249709,0.029367758126685104,0.03073950253531425,1.516301164468114,-0.46618788300231534,-0.0044598175275400755,-0.02904479799176844,0.030406596900339325,0.03856632498625586,0.01205258179228991,-0.03576887047317157,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.666688,1.0,0.0,1.0,1.0,-0.20498210499330854,0.4292867938347167,0.5446262907635626,0.8794970661186534,-0.07496791333842949,-0.048540995714256116,0.4674489216945862,0.44690829747673905,0.09169354927648384,-0.010319229253260048,0.45424999132698196,-0.05022061298973132,0.3148418058280388,-0.08167009088489902,0.019331766708219414,0.03924508687472633,-0.13208035623913567,1.2420691356225038,-0.5489793834908798,-0.00924416630453887,-0.02943280330069765,0.04098196909066566,0.03989691761902578,0.015057730804228968,-0.047484718591682816,-0.08167009088489902,0.019331766708219414,0.03924508687472633,-0.13208035623913567,1.2420691356225038,-0.5489793834908798,-0.00924416630453887,-0.02943280330069765,0.04098196909066566,0.03989691761902578,0.015057730804228968,-0.047484718591682816,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.683354699999999,1.0,0.0,1.0,1.0,-0.20209094968107252,0.43649801069906563,0.5443999869620451,0.8785688917030712,-0.07073175315263962,-0.04649219115094121,0.47005552628341224,0.45516738554398056,0.10280093620138891,-0.013812538018361402,0.6411413864129816,-0.06037422222945778,0.31898392127802294,-0.09273569103977759,0.025989204663644544,0.058178984507181536,-0.17951891088416988,0.7535628594542807,-0.8576880581442874,-0.018719271837966657,-0.023214762796561948,0.056557689614572026,0.035493471904937415,0.019660211759590162,-0.06888634641020007,-0.09273569103977759,0.025989204663644544,0.058178984507181536,-0.17951891088416988,0.7535628594542807,-0.8576880581442874,-0.018719271837966657,-0.023214762796561948,0.056557689614572026,0.035493471904937415,0.019660211759590162,-0.06888634641020007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.700021399999999,1.0,0.0,1.0,1.0,-0.1993196431475595,0.44375920011382214,0.5438273863727969,0.8777017706443072,-0.06535474167552363,-0.04402269519147299,0.47268420944268086,0.4626012732397235,0.10162162160853525,-0.046778540074761524,0.821154067993329,-0.04348012012264388,0.3092845516143924,-0.10079941904644515,0.030520889352653884,0.07333877940623808,-0.12738414034432732,0.3121028796621894,-0.926152902265123,-0.029268270620909014,-0.016551188485022777,0.0748649089315341,0.02731604217267709,0.023291926332694668,-0.0864076821437287,-0.10079941904644515,0.030520889352653884,0.07333877940623808,-0.12738414034432732,0.3121028796621894,-0.926152902265123,-0.029268270620909014,-0.016551188485022777,0.0748649089315341,0.02731604217267709,0.023291926332694668,-0.0864076821437287,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.716688099999999,1.0,0.0,1.0,1.0,-0.19619563592784722,0.451112340376233,0.5425693801080285,0.8769829390221593,-0.05860704794307053,-0.0403172390147157,0.4752269550790281,0.4702653741757366,0.10886766801315509,-0.030579848428579425,0.8216140333493733,-0.04941463684223432,0.34481180968058417,-0.10640526929533327,0.029731262014882395,0.07495088360426162,-0.25112755349101235,0.15802421154021964,-0.38022931264108295,-0.02646150527308309,-0.02215788061202301,0.07470581299001954,0.03209069836355952,0.024907257367010053,-0.08687133369121923,-0.10640526929533327,0.029731262014882395,0.07495088360426162,-0.25112755349101235,0.15802421154021964,-0.38022931264108295,-0.02646150527308309,-0.02215788061202301,0.07470581299001954,0.03209069836355952,0.024907257367010053,-0.08687133369121923,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.733354799999999,1.0,0.0,1.0,1.0,-0.1936542270856762,0.45879850330356575,0.5425415954200099,0.875750631104403,-0.05318061440383001,-0.03790943587730767,0.47832575619898976,0.46597210559825025,0.1484813404561385,0.015147770333042923,0.5467562390999259,-0.132743770951398,0.4066815422673863,-0.10111726595250947,0.023502754068165616,0.061814582009729446,-0.23349666096428676,-0.03320357522393058,-0.07514366006197062,-0.05244663236996505,0.09079644104139449,0.2335304261833697,0.05285819616408725,0.023799840273537636,-0.0669914000011161,-0.10111726595250947,0.023502754068165616,0.061814582009729446,-0.23349666096428676,-0.03320357522393058,-0.07514366006197062,-0.05244663236996505,0.09079644104139449,0.2335304261833697,0.05285819616408725,0.023799840273537636,-0.0669914000011161,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.750021499999999,1.0,1.0,0.0,1.0,-0.1920011454944859,0.46687317538546347,0.5426706008000048,0.8741539966421349,-0.049818362819598574,-0.03754468584495749,0.4816257026419591,0.46531663468247286,0.20118066531945134,0.016284490467076182,0.21470605747631258,-0.25641041704998085,0.4633805109697077,-0.09182740800219004,0.017663659790439313,0.048867218660692435,-0.06237976060033108,-0.04079964207995041,-0.04729432856985937,-0.02619296597155572,0.3023419423017654,0.4185726498288651,0.07685414670612002,0.022898184568868944,-0.046150647068259026,-0.09182740800219004,0.017663659790439313,0.048867218660692435,-0.06237976060033108,-0.04079964207995041,-0.04729432856985937,-0.02619296597155572,0.3023419423017654,0.4185726498288651,0.07685414670612002,0.022898184568868944,-0.046150647068259026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.766688199999999,1.0,1.0,0.0,1.0,-0.19106641918708855,0.47550619240453795,0.5425273772079565,0.8720523470117161,-0.0482753110536593,-0.03954587322929063,0.4854176782159493,0.46519099844571965,0.23825745451970803,-0.00947897260965841,-0.06233125904331338,-0.34934212543323134,0.49528422671047023,-0.08167287919793673,0.012449639275528756,0.03629710477939749,-0.03113321218303365,0.09715618648045811,0.050844703912901926,0.12300039517475542,0.5282071189801066,0.4950220061763544,0.09430200166552902,0.021687283642853314,-0.027467658805742996,-0.08167287919793673,0.012449639275528756,0.03629710477939749,-0.03113321218303365,0.09715618648045811,0.050844703912901926,0.12300039517475542,0.5282071189801066,0.4950220061763544,0.09430200166552902,0.021687283642853314,-0.027467658805742996,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.783354899999999,1.0,1.0,0.0,1.0,-0.19050766957636922,0.48420811765999683,0.5417262614971474,0.8698676419626867,-0.04821904398843105,-0.04273412799375505,0.48905930475529263,0.44442143834042236,0.24608939130265595,-0.022438880940145435,-0.24485610252460485,-0.33916109763461416,0.49630294517811036,-0.07205797049189375,0.005464945938877366,0.017412156055902284,-0.026692459872284597,0.09235550929467051,0.06867046132425934,0.2895444752174467,0.8133358812510925,0.5796154935387412,0.09965529751148085,0.018155856442238414,-0.006369016826783566,-0.07205797049189375,0.005464945938877366,0.017412156055902284,-0.026692459872284597,0.09235550929467051,0.06867046132425934,0.2895444752174467,0.8133358812510925,0.5796154935387412,0.09965529751148085,0.018155856442238414,-0.006369016826783566,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.800021599999999,1.0,1.0,0.0,1.0,-0.19024757580687718,0.49238096174994,0.54115728775624,0.8675691773783207,-0.04941366840536371,-0.046065168183816625,0.49270682166784086,0.4208027983158283,0.24571268490263792,-0.011991937951672,-0.3233390235743939,-0.27650961453592665,0.5048497390970949,-0.06978944684209819,-0.0008058577530697712,8.197923021629776e-05,-0.026605104271565847,0.08858168585390018,0.06731220867127113,0.46343515296830573,1.1745083030871926,0.5333832859619951,0.10066456281415556,0.015050866925329537,0.010394103229482674,-0.06978944684209819,-0.0008058577530697712,8.197923021629776e-05,-0.026605104271565847,0.08858168585390018,0.06731220867127113,0.46343515296830573,1.1745083030871926,0.5333832859619951,0.10066456281415556,0.015050866925329537,0.010394103229482674,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8166883,1.0,1.0,0.0,1.0,-0.19026412155077663,0.5004213709748495,0.5406942910409249,0.8652447863171108,-0.05101315638963842,-0.048973494004388406,0.496337299133589,0.4183170155020431,0.25301648136878635,-0.002878712128337839,-0.4025230674979424,-0.21371616055642095,0.49801591364152575,-0.06432362563429042,-0.006805846264559622,-0.016854440595086614,-0.025265049613093827,0.08242895416396234,0.06622148952965731,0.573704469346297,1.6375472764725414,0.2951538511216489,0.09907575826214965,0.011599688450397957,0.026916335084819318,-0.06432362563429042,-0.006805846264559622,-0.016854440595086614,-0.025265049613093827,0.08242895416396234,0.06622148952965731,0.573704469346297,1.6375472764725414,0.2951538511216489,0.09907575826214965,0.011599688450397957,0.026916335084819318,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.833355,1.0,1.0,0.0,1.0,-0.19042952640160662,0.5086579682722628,0.5403833614503428,0.862932144678435,-0.0538554007190679,-0.052059030877127356,0.49973749789084226,0.42512950123136783,0.2513888091775118,-0.002088213999197279,-0.48038884810101173,-0.10103075528536891,0.4628234128448553,-0.13333844722883237,0.1496706773436022,0.04814253878158993,-0.02170375387139585,0.06931118153941258,0.057870389244132486,0.5868479092853616,2.0799461021990973,-0.04761168737929421,0.09070185979877876,0.005469709758266904,0.04880004324142026,-0.13333844722883237,0.1496706773436022,0.04814253878158993,-0.02170375387139585,0.06931118153941258,0.057870389244132486,0.5868479092853616,2.0799461021990973,-0.04761168737929421,0.09070185979877876,0.005469709758266904,0.04880004324142026,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8500217,0.0,1.0,0.0,1.0,-0.19041826823545344,0.5168657971676919,0.5399210295731905,0.860875620605083,-0.05748534465274192,-0.05401711810652196,0.5026636568814524,0.43407105717032124,0.2402745685380717,0.003716591941607769,-0.49067157217088436,0.03304120213869816,0.3888744105313407,-0.1667198831343681,0.3756451564214818,0.0923292715918908,-0.016772687057922817,0.050514647995126886,0.03989731723203526,0.6564894199922334,2.4440462953278663,-0.3280555082888598,0.0732695015224134,-0.001083943071277799,0.06503653445366528,-0.1667198831343681,0.3756451564214818,0.0923292715918908,-0.016772687057922817,0.050514647995126886,0.03989731723203526,0.6564894199922334,2.4440462953278663,-0.3280555082888598,0.0732695015224134,-0.001083943071277799,0.06503653445366528,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8666884,0.0,1.0,0.0,1.0,-0.19025728852629917,0.5251846523070556,0.5397875494881998,0.859237129505305,-0.0615231468907614,-0.055327770918688485,0.5048418519113791,0.4473847485398523,0.24163472986433404,0.008612988633514666,-0.4023711610661133,0.09960304492767452,0.3222078062778549,-0.08242798782150552,0.5968890870644505,0.026058392759693384,-0.01454461186794383,0.03823016621744343,0.021428560481706826,0.7338938978075927,2.694990105125027,-0.4819834121203058,0.057101568059678975,-0.003014467584197921,0.06255855721438942,-0.08242798782150552,0.5968890870644505,0.026058392759693384,-0.01454461186794383,0.03823016621744343,0.021428560481706826,0.7338938978075927,2.694990105125027,-0.4819834121203058,0.057101568059678975,-0.003014467584197921,0.06255855721438942,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.8833551,0.0,1.0,0.0,1.0,-0.19017630050893494,0.5338073042013939,0.5393942090501117,0.8578499337148557,-0.06438535547958738,-0.05564429963898002,0.5068054154632448,0.4497514578104563,0.2718719523286497,0.004856769051245206,-0.2713202697298216,0.1079290674065082,0.2883617672005957,-0.06435649353118454,0.9899293462287152,-0.038425924913481124,-0.015785737079458573,0.03499975559191738,0.006654444676145371,0.7219942376963363,2.7473964841368916,-0.5251622186984695,0.047577865513440724,-0.0011849263846443361,0.0489525387430283,-0.06435649353118454,0.9899293462287152,-0.038425924913481124,-0.015785737079458573,0.03499975559191738,0.006654444676145371,0.7219942376963363,2.7473964841368916,-0.5251622186984695,0.047577865513440724,-0.0011849263846443361,0.0489525387430283,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9000218,0.0,1.0,0.0,1.0,-0.1909007845007453,0.5426684239410471,0.5388877325482966,0.8566124754094168,-0.0665819687127797,-0.05576616229122545,0.5085981159605201,0.4544901847978584,0.2982326720574601,-0.02213980523843305,-0.20174553300637613,0.07146407939233432,0.23158614742573116,-0.01699382390809178,1.3757309793219803,-0.10893104384330733,-0.013254281860667861,0.029216303601025558,0.00574967882796754,0.6950141585378476,2.753348118853868,-0.5142318559021866,0.03835459978051568,0.00022324569016512162,0.03582838018915361,-0.01699382390809178,1.3757309793219803,-0.10893104384330733,-0.013254281860667861,0.029216303601025558,0.00574967882796754,0.6950141585378476,2.753348118853868,-0.5142318559021866,0.03835459978051568,0.00022324569016512162,0.03582838018915361,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9166885,0.0,1.0,0.0,1.0,-0.19142623604555847,0.5517880678765752,0.5373908150841362,0.855731274811906,-0.06808634570052885,-0.056077210799934975,0.5098466252382554,0.4452017434899898,0.2912693388094412,-0.06510334605792784,-0.4441160414221422,-0.012881973225287335,0.09946906327899831,0.2887250112708642,1.5598894682771256,-0.1210175826164195,0.003920624316409289,0.008551753774399491,0.047417977942871704,0.6354304385544424,2.594984662008546,-0.5560519258767593,0.028183758118511232,-0.004584813215192818,0.048517005446790315,0.2887250112708642,1.5598894682771256,-0.1210175826164195,0.003920624316409289,0.008551753774399491,0.047417977942871704,0.6354304385544424,2.594984662008546,-0.5560519258767593,0.028183758118511232,-0.004584813215192818,0.048517005446790315,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9333552,0.0,1.0,0.0,1.0,-0.19190803216389613,0.5601735702399719,0.535458805017866,0.8552358549024802,-0.0728930609814849,-0.059617246183788435,0.5096116345879821,0.3965554873125875,0.3020581835919342,-0.10605696877077139,-0.6947879765464857,-0.08760560959550812,-0.036263817955604974,0.5572264692696824,1.8859735905878385,-0.0009732125098551607,0.021209868950095957,-0.013228381102219487,0.08880378950231546,0.5527662430687402,2.1829667843810765,-0.4235773757531029,0.01694656644819366,-0.010116002695318274,0.06325935024221022,0.5572264692696824,1.8859735905878385,-0.0009732125098551607,0.021209868950095957,-0.013228381102219487,0.08880378950231546,0.5527662430687402,2.1829667843810765,-0.4235773757531029,0.01694656644819366,-0.010116002695318274,0.06325935024221022,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9500219,0.0,1.0,1.0,1.0,-0.19323339708771683,0.5679311826112755,0.5324169797141002,0.8551083108586268,-0.07720718047044631,-0.06327474793677995,0.508748596320272,0.30888479732828966,0.3305088212683909,-0.11616344820393884,-0.7799187963279276,-0.14604710917651653,-0.20442744555152903,0.8847413843833256,3.0694977882240715,0.18040589731724146,0.03553535686445622,-0.037791553453308625,0.11153889880730823,0.28277708453360084,0.994379984693793,-0.17395118198503162,-0.004887568411174314,-0.014131714095495592,0.060941236756864074,0.8847413843833256,3.0694977882240715,0.18040589731724146,0.03553535686445622,-0.037791553453308625,0.11153889880730823,0.28277708453360084,0.994379984693793,-0.17395118198503162,-0.004887568411174314,-0.014131714095495592,0.060941236756864074,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9666886,0.0,1.0,1.0,1.0,-0.19577882294720822,0.5741532811930289,0.5298052011958807,0.8557963334602149,-0.08254691564540033,-0.06858163415168311,0.5060584964315574,0.21224046870521734,0.32887762531721443,-0.08232275257733282,-1.0340486673574887,-0.24137853025231626,-0.4290042786078485,0.9201399048567671,1.8539999785947014,0.27546162104588484,0.05689700821046141,-0.0722920173001164,0.16018976280923589,0.05336876757741226,0.03896704855482032,-0.12847396180841564,-0.029829213070964703,-0.02125318987690519,0.07043304679146677,0.9201399048567671,1.8539999785947014,0.27546162104588484,0.05689700821046141,-0.0722920173001164,0.16018976280923589,0.05336876757741226,0.03896704855482032,-0.12847396180841564,-0.029829213070964703,-0.02125318987690519,0.07043304679146677,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +10.9833553,0.0,1.0,1.0,1.0,-0.1986687856032225,0.5791401851708393,0.5276656621784748,0.8570014290983471,-0.08942430239343183,-0.0760317748622198,0.50176788844658,0.18818101475793042,0.34639486889635535,-0.03838000281160148,-1.0130051342305804,-0.24655820780679472,-0.514058910483389,0.8467218810586977,0.9480869664959384,0.32420608626085734,0.060252659642574306,-0.08514585709913244,0.16227039299768756,0.04954481659330765,0.05172114481495304,-0.12869295160494726,-0.044313574822380936,-0.02266442465956916,0.06429756185917318,0.8467218810586977,0.9480869664959384,0.32420608626085734,0.060252659642574306,-0.08514585709913244,0.16227039299768756,0.04954481659330765,0.05172114481495304,-0.12869295160494726,-0.044313574822380936,-0.02266442465956916,0.06429756185917318,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.000022,0.0,1.0,1.0,1.0,-0.20222903723689972,0.5850825288907053,0.5261648709346889,0.858295880060934,-0.09429753356639295,-0.08134984346079434,0.49781357997007886,0.21125390028860908,0.3342682599872605,0.025481309876677294,-0.9248715149569048,-0.13522735882233922,-0.5618153930751382,1.0570604932546808,2.1879572561481395,0.3601324020374545,0.05958991280415922,-0.09772638447755168,0.13903654798785606,0.03770276284572551,0.057004803586060554,-0.10851630084240747,-0.06099616464300323,-0.025626747067223715,0.06544830174421652,1.0570604932546808,2.1879572561481395,0.3601324020374545,0.05958991280415922,-0.09772638447755168,0.13903654798785606,0.03770276284572551,0.057004803586060554,-0.10851630084240747,-0.06099616464300323,-0.025626747067223715,0.06544830174421652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0166887,0.0,1.0,1.0,1.0,-0.20475933434647728,0.5907560549568371,0.5261048533299277,0.8600188195215962,-0.10076220033062061,-0.08652101860447252,0.49267506776054415,0.2372580033511575,0.24718364249055585,0.10934921860572687,-1.039466481875762,-0.00020583342984903386,-0.6304302266305504,1.02622812196424,2.1150701158022978,0.3447614233092927,0.0652097883671627,-0.11832568840049743,0.13538405328907235,0.036300260718585546,0.057856108559343665,-0.10368928208342747,-0.07836308048721483,-0.0328153529029166,0.09057916520141222,1.02622812196424,2.1150701158022978,0.3447614233092927,0.0652097883671627,-0.11832568840049743,0.13538405328907235,0.036300260718585546,0.057856108559343665,-0.10368928208342747,-0.07836308048721483,-0.0328153529029166,0.09057916520141222,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0333554,0.0,1.0,1.0,1.0,-0.20602108922363838,0.5963155701484972,0.5279425396703249,0.8617279846408059,-0.10828030054667993,-0.09094209960920628,0.4872676795346527,0.2951102080793585,0.18603900656540767,0.18468339528675587,-0.7500867867963905,0.16764381405874293,-0.5805715724437879,0.9114209961654035,1.9144241324634328,0.29073800191640314,0.056350636196905536,-0.11545124436324113,0.07886265141593017,0.011279947510504137,0.05465663137362589,-0.05901961654132179,-0.0748994602558911,0.1059982806636053,0.22720951146442686,0.9114209961654035,1.9144241324634328,0.29073800191640314,0.056350636196905536,-0.11545124436324113,0.07886265141593017,0.011279947510504137,0.05465663137362589,-0.05901961654132179,-0.0748994602558911,0.1059982806636053,0.22720951146442686,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0500221,0.0,1.0,1.0,0.0,-0.206456352835928,0.6029251541981534,0.5308116997992363,0.8636724774749263,-0.11200098816408943,-0.09127103719917962,0.4829029178532437,0.3466116323065776,0.171697815254649,0.21992592465218902,-0.26688769324831607,0.2520880166312666,-0.4828058643718861,0.7938386807986999,1.5477039116581717,0.18430060044795005,0.04133203238941922,-0.09713983162641959,0.010544434646352598,-0.020704064210499036,0.05441015542368724,-0.006867072218351641,-0.09056569622756881,0.2973669367010845,0.3568415741749079,0.7938386807986999,1.5477039116581717,0.18430060044795005,0.04133203238941922,-0.09713983162641959,0.010544434646352598,-0.020704064210499036,0.05441015542368724,-0.006867072218351641,-0.09056569622756881,0.2973669367010845,0.3568415741749079,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0666888,0.0,1.0,1.0,0.0,-0.20665414484996603,0.6098716749444031,0.5339273449395804,0.8655089055864531,-0.11341188852532362,-0.09037143369408333,0.4794424698164899,0.3562966829520386,0.17134862745205243,0.25152113062957493,0.04047071666757996,0.25424244998392376,-0.43684649374159185,0.6905670177301643,1.0277999027966915,0.014837104250986643,0.032652434101707574,-0.08539978898874795,-0.025107331717801433,-0.038949332276951486,0.05909995781759081,0.0196764377678875,-0.10504139265830022,0.45570657303492385,0.32648803675096233,0.6905670177301643,1.0277999027966915,0.014837104250986643,0.032652434101707574,-0.08539978898874795,-0.025107331717801433,-0.038949332276951486,0.05909995781759081,0.0196764377678875,-0.10504139265830022,0.45570657303492385,0.32648803675096233,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.0833555,0.0,1.0,1.0,0.0,-0.20708023833598843,0.6168835646434967,0.5377932330675208,0.8676232930539163,-0.11278524092650764,-0.088113774166284,0.4761777751865379,0.33722206221146944,0.16832819410396405,0.29364942946389827,0.22757818483866943,0.2625367600989692,-0.4093907215307742,0.4822322464546767,0.6162594521039161,-0.29721436704160714,0.027284848991836697,-0.07877161588595752,-0.04808511526963501,-0.05025405246774774,0.06205562190833482,0.036890408924718225,-0.08191535787849082,0.5969005885093086,0.3100809745659926,0.4822322464546767,0.6162594521039161,-0.29721436704160714,0.027284848991836697,-0.07877161588595752,-0.04808511526963501,-0.05025405246774774,0.06205562190833482,0.036890408924718225,-0.08191535787849082,0.5969005885093086,0.3100809745659926,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1000222,0.0,1.0,1.0,0.0,-0.20775824749588015,0.6234011459877722,0.5422570064173439,0.8695722186957904,-0.11160112025510097,-0.085541001013616,0.4733625286985394,0.3459601579487838,0.15037810672980553,0.28120279849789426,0.22235107015626054,0.2295968147193344,-0.37331507639377337,0.1055065695844526,0.3419799535599826,-0.6767023226913623,0.02384020182159872,-0.07118116995733703,-0.044228798890122566,-0.045694719786686155,0.057706878894431476,0.033949825350964226,-0.04302222339640149,0.6790722558643812,0.3174368229157188,0.1055065695844526,0.3419799535599826,-0.6767023226913623,0.02384020182159872,-0.07118116995733703,-0.044228798890122566,-0.045694719786686155,0.057706878894431476,0.033949825350964226,-0.04302222339640149,0.6790722558643812,0.3174368229157188,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1166889,0.0,1.0,1.0,0.0,-0.2073007215408185,0.6302990158174537,0.545914347969334,0.8713116210719212,-0.11084427268435082,-0.08372541074293009,0.47065875301966487,0.36322709404135395,0.14449435963123294,0.20752891581362592,0.1819655987057672,0.17557791039507475,-0.3474358628894123,-0.3513604436993131,0.12228254360015721,-0.9619498042990758,0.02161721679010099,-0.06447045587152543,-0.03295443895667205,-0.03813837168997679,0.054119606986870746,0.025259893632889583,-0.0026350108535227357,0.7929981792544781,0.28268895808229666,-0.3513604436993131,0.12228254360015721,-0.9619498042990758,0.02161721679010099,-0.06447045587152543,-0.03295443895667205,-0.03813837168997679,0.054119606986870746,0.025259893632889583,-0.0026350108535227357,0.7929981792544781,0.28268895808229666,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1333556,0.0,1.0,1.0,0.0,-0.20677661551754498,0.6369115473208423,0.5481009477495025,0.8728801365595604,-0.10985158687446048,-0.0822068604583994,0.46824665311617486,0.34617291074807555,0.15786243558394863,0.13867692135663662,0.12805108419847927,0.10948773340770644,-0.37421404048520607,-0.40688460649688135,-0.07695997956533628,-0.5455190072236588,0.023118338099460355,-0.0658991641174529,-0.01656423086119455,-0.03148741345210771,0.05811952993469056,0.012447478279220641,-0.04929986019270883,0.9360231102537667,0.221244456885027,-0.40688460649688135,-0.07695997956533628,-0.5455190072236588,0.023118338099460355,-0.0658991641174529,-0.01656423086119455,-0.03148741345210771,0.05811952993469056,0.012447478279220641,-0.04929986019270883,0.9360231102537667,0.221244456885027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1500223,0.0,1.0,1.0,0.0,-0.20632297012747006,0.6432982683774485,0.549417563749416,0.8746158817927084,-0.1093272842932534,-0.08181630613312925,0.46518888236473943,0.3628796164735477,0.16003264517063256,0.09261672613121766,0.06502389122838452,0.04904453441781445,-0.4544640733219829,-0.0981724074084545,-0.2450028617270409,0.06722444770224317,0.028254431784448662,-0.07663007830952656,0.0019688666119107847,-0.02687256041355421,0.06966412151983604,-0.002076629378524688,-0.1692132241913415,1.0918599905309916,0.16085587800151804,-0.0981724074084545,-0.2450028617270409,0.06722444770224317,0.028254431784448662,-0.07663007830952656,0.0019688666119107847,-0.02687256041355421,0.06966412151983604,-0.002076629378524688,-0.1692132241913415,1.0918599905309916,0.16085587800151804,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.166689,0.0,1.0,1.0,0.0,-0.2050788853460541,0.6502243050478447,0.5501476143027508,0.8765871087013806,-0.10866563471213977,-0.08181588365623098,0.46161995393690675,0.3702329515438604,0.16678301661606612,0.0657525754922057,0.02735527038115423,-0.021310788143073467,-0.4505603421574251,-0.0662016112578304,-0.06948752569785784,0.025254912488885905,0.027554101508561732,-0.07263209135062419,0.016121054768417076,-0.019636392550974525,0.06973166217435754,-0.013209908886776206,-0.2492451720007971,1.2373152572505537,0.12635536629125452,-0.0662016112578304,-0.06948752569785784,0.025254912488885905,0.027554101508561732,-0.07263209135062419,0.016121054768417076,-0.019636392550974525,0.06973166217435754,-0.013209908886776206,-0.2492451720007971,1.2373152572505537,0.12635536629125452,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.1833557,1.0,1.0,1.0,0.0,-0.20434135303685827,0.6568161696751117,0.5505812148359984,0.8781049611366187,-0.10815329851076935,-0.08273326476527203,0.45868262246326386,0.34996992391156334,0.18530408480105617,0.03764021884887729,-0.09133595692686346,-0.07692192160900553,-0.3826762559894833,-0.04005772534241862,0.09251951004228556,-0.045691403660385155,0.024310275408253694,-0.060347928160479396,0.034761281018626085,-0.005369605368962143,0.056433428590968795,-0.027453616028028687,-0.2879801879874878,1.4133275174552313,0.08990659308352174,-0.04005772534241862,0.09251951004228556,-0.045691403660385155,0.024310275408253694,-0.060347928160479396,0.034761281018626085,-0.005369605368962143,0.056433428590968795,-0.027453616028028687,-0.2879801879874878,1.4133275174552313,0.08990659308352174,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2000224,1.0,1.0,1.0,0.0,-0.20365351450905428,0.6634066071612235,0.5502513049075558,0.879242864063711,-0.10888932287998565,-0.08432575657321804,0.4560309947077449,0.3347869338334891,0.20016438999840297,0.028565941151620852,-0.2502460306610144,-0.07574599942129215,-0.394953237867273,0.08444767399202385,-0.006351004124403122,0.008304565180052115,0.026946421450976876,-0.06536411507752002,0.05254535024261441,0.004863047054048097,0.051948137581754074,-0.04073307119568026,-0.2950086987191716,1.6002116566813427,0.03345766233051135,0.08444767399202385,-0.006351004124403122,0.008304565180052115,0.026946421450976876,-0.06536411507752002,0.05254535024261441,0.004863047054048097,0.051948137581754074,-0.04073307119568026,-0.2950086987191716,1.6002116566813427,0.03345766233051135,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2166891,1.0,1.0,1.0,0.0,-0.20344586403598386,0.6698181382084606,0.5502530528226462,0.8805428531101571,-0.11068958935848991,-0.08645905845947098,0.4526775119823989,0.3205686922945859,0.21903660617076046,0.05781686699245859,-0.36037253568047073,-0.07933419380403417,-0.4610502547694708,0.10297565984542642,-0.011370650766438593,0.0033278555946589946,0.03166934900849421,-0.07819744145998032,0.06772785989374105,0.010260807194709695,0.057563719334712854,-0.05208211770528675,-0.31703381635788297,1.7791889804053116,0.010392267455654207,0.10297565984542642,-0.011370650766438593,0.0033278555946589946,0.03166934900849421,-0.07819744145998032,0.06772785989374105,0.010260807194709695,0.057563719334712854,-0.05208211770528675,-0.31703381635788297,1.7791889804053116,0.010392267455654207,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2333558,1.0,1.0,1.0,0.0,-0.20367436689338592,0.676484626259749,0.5506639000025251,0.8819389785821286,-0.11291548620116568,-0.08905838336942659,0.44889011504497445,0.3121920885286988,0.23839829275642344,0.06321994556739628,-0.4236473796470083,-0.06989135597737589,-0.4162468336611332,0.09935421090519382,-0.015029739985873914,-0.004706653889314371,0.029116685262256903,-0.07255598542087953,0.07191130376874873,0.016173781865107328,0.04776954764473397,-0.0547691923368774,-0.3395182376433332,1.941170158640739,-0.015290776832882226,0.09935421090519382,-0.015029739985873914,-0.004706653889314371,0.029116685262256903,-0.07255598542087953,0.07191130376874873,0.016173781865107328,0.04776954764473397,-0.0547691923368774,-0.3395182376433332,1.941170158640739,-0.015290776832882226,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2500225,1.0,1.0,1.0,0.0,-0.20407523178899023,0.6830597941072689,0.5506349218883737,0.8827595918612754,-0.11577840366800962,-0.09143440984633236,0.44606122104152346,0.3483452565503494,0.26103311441807614,0.026414623135609293,-0.37077454824764905,-0.029435736789776845,-0.3646853260538145,0.08722202357131044,-0.015590651000050288,-0.008024816124730312,0.024961931118902575,-0.06550196132481706,0.05868051450553047,0.012803721030948062,0.04092116888666022,-0.044343212776250404,-0.3500076047986751,2.077035792871922,-0.10080058333873396,0.08722202357131044,-0.015590651000050288,-0.008024816124730312,0.024961931118902575,-0.06550196132481706,0.05868051450553047,0.012803721030948062,0.04092116888666022,-0.044343212776250404,-0.3500076047986751,2.077035792871922,-0.10080058333873396,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2666892,1.0,1.0,1.0,0.0,-0.20377894252764323,0.6909883675009447,0.5496928203213468,0.8838926590183697,-0.1175930540779132,-0.09295595248959976,0.44301786855929004,0.35891479588775027,0.27012107720135076,0.012742368815480548,-0.44413486671029084,0.02330593671919215,-0.37056906136412343,0.09360606662826264,-0.022575391765850685,-0.020822510107266764,0.025862588337757474,-0.07095774787411774,0.059493439083388965,0.014548182093347982,0.03710526836041716,-0.04418032707217266,-0.3682901359734024,2.271126069090932,-0.17699793506504496,0.09360606662826264,-0.022575391765850685,-0.020822510107266764,0.025862588337757474,-0.07095774787411774,0.059493439083388965,0.014548182093347982,0.03710526836041716,-0.04418032707217266,-0.3682901359734024,2.271126069090932,-0.17699793506504496,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.2833559,1.0,1.0,1.0,0.0,-0.20398312727503248,0.6979649522659597,0.5491466708154646,0.8846552855740878,-0.12192027591800234,-0.09508756546262942,0.4398622817658926,0.3208584931163583,0.2582517934471942,0.04732822734196361,-0.5646998838229719,0.13124233529120422,-0.41722859000285134,0.11076007252661275,-0.035370403355383495,-0.04290447271395833,0.029967235944443556,-0.08732450279480852,0.0595615951767718,0.014560123285748048,0.036257584935867726,-0.04308298043904883,-0.37827867958453315,2.4002127888052396,-0.206862335138198,0.11076007252661275,-0.035370403355383495,-0.04290447271395833,0.029967235944443556,-0.08732450279480852,0.0595615951767718,0.014560123285748048,0.036257584935867726,-0.04308298043904883,-0.37827867958453315,2.4002127888052396,-0.206862335138198,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3000226,1.0,1.0,1.0,0.0,-0.20435022390470753,0.7047897489072255,0.5492701725246721,0.8860123932515052,-0.12621340713976037,-0.09601352883936573,0.4356989983265116,0.40033510954603474,0.2488014500461107,0.05509893611600683,-0.4603057510174316,0.17531040202509518,-0.5227613899087875,0.12238693357583388,-0.03549710430210653,-0.034746335266773704,0.03366312424610493,-0.10591242830598639,0.04642513433097121,0.001977861974995075,0.05550304449550825,-0.03321198765882927,-0.37407339350035684,2.4276784319821565,-0.25965526983343523,0.12238693357583388,-0.03549710430210653,-0.034746335266773704,0.03366312424610493,-0.10591242830598639,0.04642513433097121,0.001977861974995075,0.05550304449550825,-0.03321198765882927,-0.37407339350035684,2.4276784319821565,-0.25965526983343523,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3166893,1.0,1.0,1.0,0.0,-0.20266766977772127,0.7137288268200722,0.5491449643611677,0.8877642259811533,-0.1291536777452364,-0.09694974920412026,0.43103915451177005,0.4014397688095476,0.240046164764495,0.039650975866017,-0.5444823118025632,0.24833615997280908,-0.5790375513999826,0.13828887500337353,-0.04607253229766327,-0.0480839869609353,0.2143261152359687,0.08088491104366481,0.15511830687373984,0.0015055712274680748,0.058483987021383396,-0.03333692550160849,-0.3283158408404758,2.4277297550462316,-0.2740368756245322,0.13828887500337353,-0.04607253229766327,-0.0480839869609353,0.2143261152359687,0.08088491104366481,0.15511830687373984,0.0015055712274680748,0.058483987021383396,-0.03333692550160849,-0.3283158408404758,2.4277297550462316,-0.2740368756245322,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.333356,1.0,0.0,1.0,0.0,-0.20249085058574467,0.7203198432952054,0.5488328324255677,0.8893901820037761,-0.1351135401951952,-0.09748210866912761,0.4257072631523122,0.3334829808584731,0.23836024961246594,0.013644567921950193,-0.6762583090041718,0.40257655793960256,-0.6282214302284221,0.15696932417446968,-0.06443467932367151,-0.07664780318036453,0.4315147721549403,0.27050499012804086,0.330510128843475,-0.000556414969602348,0.0565630499678873,-0.028286632780200008,-0.28776219764121325,2.374718842398881,-0.2124074247571871,0.15696932417446968,-0.06443467932367151,-0.07664780318036453,0.4315147721549403,0.27050499012804086,0.330510128843475,-0.000556414969602348,0.0565630499678873,-0.028286632780200008,-0.28776219764121325,2.374718842398881,-0.2124074247571871,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3500227,1.0,0.0,1.0,0.0,-0.20173031948542036,0.7272862215585616,0.5476542768599647,0.8913515527430641,-0.14100810611118478,-0.09719953312429731,0.419715825522322,0.3494562359575564,0.22912843899489946,0.00500495256817661,-0.6081985401700983,0.5289553565558411,-0.6944964643029335,0.1647681818520253,-0.07308523329348418,-0.08440716591488552,0.7068840850683896,0.2536087466933569,0.43933380489172336,-0.014556967616448565,0.0674835340028896,-0.01149520367052738,-0.25527594614523935,2.278127906393619,-0.1267780548413658,0.1647681818520253,-0.07308523329348418,-0.08440716591488552,0.7068840850683896,0.2536087466933569,0.43933380489172336,-0.014556967616448565,0.0674835340028896,-0.01149520367052738,-0.25527594614523935,2.278127906393619,-0.1267780548413658,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3666894,1.0,0.0,1.0,0.0,-0.20072043387303334,0.7340262643421649,0.5470864289444051,0.8936759395192602,-0.14671462013713016,-0.09551547516115784,0.4131524287319676,0.36171128618679765,0.21779181185440744,0.023909753930261908,-0.26729617201906775,0.6261334024869623,-0.6755028525146953,0.13961185732114972,-0.0649845238740665,-0.07219097428011972,0.9774841345021817,0.2226571654087574,0.38341990781462487,-0.04199255286544282,0.08029877423603961,0.025716364876204312,-0.1948266385862665,2.0810091236673767,-0.0650998071987369,0.13961185732114972,-0.0649845238740665,-0.07219097428011972,0.9774841345021817,0.2226571654087574,0.38341990781462487,-0.04199255286544282,0.08029877423603961,0.025716364876204312,-0.1948266385862665,2.0810091236673767,-0.0650998071987369,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.3833561,1.0,0.0,1.0,0.0,-0.19939957215853044,0.7411425700762355,0.5465224052786501,0.8963676557149545,-0.14820893138867985,-0.09139195237223754,0.4076844974809481,0.3685511541828508,0.21213351009516626,0.020156062913173997,0.15974353341934944,0.617887294711027,-0.6044324292186186,0.09859599570970844,-0.04387731383209949,-0.04254580975440105,0.960457500473354,0.22823165450792252,0.2732226868469126,-0.06620165073953928,0.09162890189235844,0.06007883681381573,-0.09732231208774991,1.7698520769953354,-0.02438591966921589,0.09859599570970844,-0.04387731383209949,-0.04254580975440105,0.960457500473354,0.22823165450792252,0.2732226868469126,-0.06620165073953928,0.09162890189235844,0.06007883681381573,-0.09732231208774991,1.7698520769953354,-0.02438591966921589,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4000228,1.0,0.0,1.0,0.0,-0.19789210525490747,0.7478762528394478,0.5458400522210827,0.8991236627140329,-0.1476003277167154,-0.08670450934228274,0.40283136728081914,0.3285640063363517,0.1710945895948189,0.01229680983357747,0.2842468937622571,0.5487143206084155,-0.700734231881065,0.10564350181928676,-0.03634388701171787,-0.018844147137252343,1.0415910372522492,0.2961434236167261,0.2879388152185171,-0.06967943846637877,0.1146032404522741,0.058430672706730934,-0.04651181839142239,1.36996674920094,0.02529036126097104,0.10564350181928676,-0.03634388701171787,-0.018844147137252343,1.0415910372522492,0.2961434236167261,0.2879388152185171,-0.06967943846637877,0.1146032404522741,0.058430672706730934,-0.04651181839142239,1.36996674920094,0.02529036126097104,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4166895,1.0,0.0,1.0,0.0,-0.19626456291886252,0.7530404188286838,0.5454013706303074,0.9025559444422768,-0.14663358587272074,-0.08298463122606256,0.3962384504642268,0.2736862844457232,0.1485919592366582,0.019257157067792137,0.4770278453180164,0.40011012608735397,-0.7565353229655077,0.10211876930602709,-0.0184698033545152,0.01997884285745133,1.1962518301049658,0.3611468128715925,0.32860806840695506,-0.0706093259296863,0.1363832496968448,0.054649291325503425,-0.10225001706065275,0.9459044681556937,-0.01125230566246656,0.10211876930602709,-0.0184698033545152,0.01997884285745133,1.1962518301049658,0.3611468128715925,0.32860806840695506,-0.0706093259296863,0.1363832496968448,0.054649291325503425,-0.10225001706065275,0.9459044681556937,-0.01125230566246656,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4333562,1.0,0.0,1.0,0.0,-0.19535245445089489,0.7579359242020385,0.5451152170337664,0.9058424459069218,-0.14201610281201688,-0.07941306583638533,0.3911194890438446,0.2512975829669569,0.14156591223732473,0.007442083544283891,0.6632649056773818,0.21257322534555467,-0.8044980043268697,0.09801385572450622,0.0007232770323017177,0.062431580136293005,1.1736870216932211,0.3992303675722166,0.39332197090627946,-0.0680164761361006,0.15659470993913358,0.04744531449067861,-0.18530218150956043,0.41968396245361445,-0.1235199696430781,0.09801385572450622,0.0007232770323017177,0.062431580136293005,1.1736870216932211,0.3992303675722166,0.39332197090627946,-0.0680164761361006,0.15659470993913358,0.04744531449067861,-0.18530218150956043,0.41968396245361445,-0.1235199696430781,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4500229,1.0,0.0,1.0,0.0,-0.19385695972309464,0.7622981063841033,0.5444036501797769,0.9096452220133168,-0.13695462357776816,-0.07735017016965108,0.38445539705373055,0.22863780791084082,0.11639650191035432,0.007009413651915989,0.6181429865842272,0.07959605864436026,-0.9192641388111891,0.12041903101884434,0.002071491414704435,0.08322904309481906,1.0451126536616044,0.3817597307813031,0.4175980245789411,-0.05583235306474112,0.17422030645028688,0.02620178567606559,-0.3004541693360807,-0.07412076776556993,-0.29847206062504306,0.12041903101884434,0.002071491414704435,0.08322904309481906,1.0451126536616044,0.3817597307813031,0.4175980245789411,-0.05583235306474112,0.17422030645028688,0.02620178567606559,-0.3004541693360807,-0.07412076776556993,-0.29847206062504306,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4666896,1.0,0.0,1.0,0.0,-0.19276433225954626,0.76605971195251,0.544409750497436,0.9132498085635891,-0.13197791382539553,-0.07634364969913202,0.3777939445934526,0.20673243727908677,0.10185464270853442,0.030287853432084608,0.49936789372965595,-0.003516854571795014,-0.9989635023687419,0.14117233683240313,-0.004162850505159639,0.08899243133032839,0.9042703418656358,0.23370630640469317,0.32524494640081586,-0.04172537293629919,0.1819558522500871,0.006495281260751044,-0.43286613496698806,-0.31050213842138025,-0.29654960063371943,0.14117233683240313,-0.004162850505159639,0.08899243133032839,0.9042703418656358,0.23370630640469317,0.32524494640081586,-0.04172537293629919,0.1819558522500871,0.006495281260751044,-0.43286613496698806,-0.31050213842138025,-0.29654960063371943,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.4833563,1.0,0.0,1.0,1.0,-0.1915291399303622,0.7696849545290456,0.5446257502497597,0.9170266071886443,-0.12806981785580424,-0.07644203826844738,0.36988773735801284,0.1843727149135738,0.09261216296135832,0.058950023456312624,0.2934780505092781,-0.04689714948812462,-1.1176694716550692,0.1731881548652804,-0.01958025805367619,0.08423348749347565,0.8470973672034983,0.008495954199986869,0.15200847825344932,-0.025344888822842755,0.1906279598529164,-0.017198631793829196,-0.3304614264459096,-0.17721101218561255,-0.12829952419978558,0.1731881548652804,-0.01958025805367619,0.08423348749347565,0.8470973672034983,0.008495954199986869,0.15200847825344932,-0.025344888822842755,0.1906279598529164,-0.017198631793829196,-0.3304614264459096,-0.17721101218561255,-0.12829952419978558,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.500023,1.0,0.0,1.0,1.0,-0.1908675494770879,0.7728408111594973,0.5456670040913102,0.9207065750113635,-0.12578878198844495,-0.0776193950504041,0.3611811381685336,0.1664919158884078,0.10772629312508501,0.09169901890294224,0.18948757415212336,-0.050412970543416424,-1.1139983934867004,0.17802714025327737,-0.028184785709028753,0.07641808961479817,0.8513660104212685,-0.17377682674762487,-0.0852076796133681,-0.015875464761029443,0.18507093105406497,-0.024617382189297765,-0.1688863125365229,0.025783184663041487,-0.072401315398787,0.17802714025327737,-0.028184785709028753,0.07641808961479817,0.8513660104212685,-0.17377682674762487,-0.0852076796133681,-0.015875464761029443,0.18507093105406497,-0.024617382189297765,-0.1688863125365229,0.025783184663041487,-0.072401315398787,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.5166897,1.0,0.0,1.0,1.0,-0.19052696124311586,0.7765613650324916,0.5468046817176895,0.924070624024466,-0.1234157401943121,-0.07841346016762882,0.35314779647034994,0.18202380067495338,0.12494951440475471,0.11672656720280569,0.20165079923909912,0.04080396866621111,-1.1012611877711544,0.17418688564672066,-0.03620792141387268,0.06343540990192369,0.854765408937564,-0.3282098562850293,-0.3434819238849504,-0.019260266096633578,0.18300804978688476,-0.01131027744636857,-0.17257673181715333,0.028126679995442473,-0.06266310838217978,0.17418688564672066,-0.03620792141387268,0.06343540990192369,0.854765408937564,-0.3282098562850293,-0.3434819238849504,-0.019260266096633578,0.18300804978688476,-0.01131027744636857,-0.17257673181715333,0.028126679995442473,-0.06266310838217978,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.533356399999999,1.0,0.0,1.0,1.0,-0.18992884709094243,0.7805895226261885,0.5485612634912026,0.9276520307165695,-0.12147303695823161,-0.07806333514580087,0.3444011133917591,0.20199235121734302,0.12408102834699249,0.12749078654394885,0.16809365358149247,0.22081153065624318,-1.1638046571443876,0.18498317139881515,-0.05505949165326825,0.03702867858069256,0.7574721828437491,-0.5072775595606501,-0.575075130743933,-0.026234401958822148,0.18916947079763627,0.006065801466391142,-0.1932941772057475,0.03035764054844796,-0.04038812197241512,0.18498317139881515,-0.05505949165326825,0.03702867858069256,0.7574721828437491,-0.5072775595606501,-0.575075130743933,-0.026234401958822148,0.18916947079763627,0.006065801466391142,-0.1932941772057475,0.03035764054844796,-0.04038812197241512,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.550023099999999,1.0,0.0,1.0,1.0,-0.18900861052221468,0.7847533528338936,0.5501344388423842,0.9313730503158488,-0.12055722838141456,-0.0763791576403384,0.33492748485081836,0.21519675237933017,0.1280666783272177,0.09968254548910446,0.09951554680481346,0.3717750282371682,-1.1786550040872998,0.18924429943663437,-0.07224487339326796,0.00948045709018385,0.5026218049426618,-0.6839201769282359,-0.7957462780008269,-0.02890587572008724,0.18641640799616585,0.018147041807901842,-0.20446855275116452,0.03154233906756777,-0.01544013230063076,0.18924429943663437,-0.07224487339326796,0.00948045709018385,0.5026218049426618,-0.6839201769282359,-0.7957462780008269,-0.02890587572008724,0.18641640799616585,0.018147041807901842,-0.20446855275116452,0.03154233906756777,-0.01544013230063076,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.566689799999999,1.0,0.0,1.0,1.0,-0.187774400189272,0.7889601525155284,0.5510128931579017,0.9349053933364798,-0.12049713534800037,-0.07409641097977768,0.3254874310372115,0.24054599342473695,0.1170501140890989,0.0791280269224636,0.03056340225429998,0.4549298369691868,-1.1922924727597646,0.19297076334372482,-0.08574130116835299,-0.008287352964469598,0.07049136327462796,-0.7876925643325897,-0.9629400604404843,-0.026807079207803706,0.1843419715247011,0.02201849426958054,-0.21081514432615392,0.03400577594641857,0.001833266127044643,0.19297076334372482,-0.08574130116835299,-0.008287352964469598,0.07049136327462796,-0.7876925643325897,-0.9629400604404843,-0.026807079207803706,0.1843419715247011,0.02201849426958054,-0.21081514432615392,0.03400577594641857,0.001833266127044643,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.583356499999999,1.0,0.0,1.0,1.0,-0.18565458733545215,0.7932051373079759,0.5520811571644734,0.9384580867830326,-0.1210740543307873,-0.07151220372950456,0.31547344965493607,0.2770981299754499,0.09312629630016334,0.0773211570934533,0.010609819176365387,0.5266043073455136,-1.2397458664576484,0.19929388597381886,-0.09777745977408818,-0.018673920200188963,-0.149843279142794,-0.7040478966800712,-0.7790456180497685,-0.02609785722790133,0.19062667566047112,0.027384308498668998,-0.22176657199757932,0.03920182714621395,0.011018324487005102,0.19929388597381886,-0.09777745977408818,-0.018673920200188963,-0.149843279142794,-0.7040478966800712,-0.7790456180497685,-0.02609785722790133,0.19062667566047112,0.027384308498668998,-0.22176657199757932,0.03920182714621395,0.011018324487005102,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.600023199999999,1.0,0.0,1.0,1.0,-0.18279790793479833,0.7974539905271216,0.553177026132216,0.9420676429077026,-0.12161619703027274,-0.06830586658341595,0.3050448580069952,0.28736289184431457,0.09149920330724626,0.07821537615800339,0.17383488761543925,0.5529616107099248,-1.2554983587827226,0.19163387835770623,-0.09492138163070643,-0.008990030793765999,-0.046454699718975936,-0.1513191662823084,-0.30760620324034604,-0.031065899123169722,0.20314767623957608,0.04343448145296825,-0.22628156143347422,0.048044999427149675,-0.00370147271664072,0.19163387835770623,-0.09492138163070643,-0.008990030793765999,-0.046454699718975936,-0.1513191662823084,-0.30760620324034604,-0.031065899123169722,0.20314767623957608,0.04343448145296825,-0.22628156143347422,0.048044999427149675,-0.00370147271664072,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.616689899999999,1.0,1.0,1.0,1.0,-0.18017911780949186,0.8017505536249412,0.5542829627991638,0.9458225305405887,-0.11971942408045796,-0.06451794766315277,0.2948295009814573,0.29124618429868493,0.10791224939522515,0.058187790900317435,0.26245014464841937,0.5010075865723813,-1.2557221243863768,0.18563464074814068,-0.09108982812744149,0.0043455142017235155,-0.004815613944708234,0.026778309113975964,-0.059097798706709066,-0.027380381926565958,0.2090419762268131,0.04550585601255434,-0.22253743877974624,0.05524613430448528,-0.01793745689587492,0.18563464074814068,-0.09108982812744149,0.0043455142017235155,-0.004815613944708234,0.026778309113975964,-0.059097798706709066,-0.027380381926565958,0.2090419762268131,0.04550585601255434,-0.22253743877974624,0.05524613430448528,-0.01793745689587492,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.633356599999999,1.0,1.0,1.0,1.0,-0.17718248064113168,0.8062524517751397,0.5545929130737909,0.9493034191767225,-0.11860088959719492,-0.06161573951194574,0.2845353193727173,0.31182847750808756,0.12121991220958878,0.028822328876998093,0.12400382912184844,0.4259420823312477,-1.255577133627601,0.19095782195159028,-0.09926083714030069,0.0028622835386869702,-0.012883709297437256,-0.2432686823269927,-0.0334649111165869,-0.011402398231666255,0.20141825982254896,0.02585003672781604,-0.21524392948066548,0.057410414635860295,-0.010477157927459495,0.19095782195159028,-0.09926083714030069,0.0028622835386869702,-0.012883709297437256,-0.2432686823269927,-0.0334649111165869,-0.011402398231666255,0.20141825982254896,0.02585003672781604,-0.21524392948066548,0.057410414635860295,-0.010477157927459495,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.650023299999999,1.0,1.0,1.0,1.0,-0.17384782484613687,0.8109730679920192,0.5546722734955942,0.9524620606957357,-0.11849862957396692,-0.05966175953629315,0.2742527523532955,0.32001860248805936,0.12182110752825918,0.012840798380909466,-0.05470200367527524,0.35356273605611416,-1.2450991191613439,0.1960768125805856,-0.10956825824874361,-0.002266969932244204,-0.015538921049105127,-0.24100967331313508,-0.003826812294386118,0.005359616704603146,0.18920969904900214,0.0030220700915689677,-0.20625611692507592,0.057768283984630645,0.0014622277294303843,0.1960768125805856,-0.10956825824874361,-0.002266969932244204,-0.015538921049105127,-0.24100967331313508,-0.003826812294386118,0.005359616704603146,0.18920969904900214,0.0030220700915689677,-0.20625611692507592,0.057768283984630645,0.0014622277294303843,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.66669,1.0,1.0,1.0,1.0,-0.17033627731857492,0.8153946468881874,0.5544753655746015,0.9552390730036928,-0.11985796508762261,-0.05869640181078632,0.264021048453654,0.2978241841106697,0.11370362666344208,0.008388108990656,-0.23740623914062947,0.33172047437997254,-1.2152036365788963,0.1971310884520976,-0.12167779602427684,-0.015212281756743962,-0.018571340241220872,-0.23826092512051542,0.018690457382826417,0.017889924826328105,0.17314279219139778,-0.014108776666054663,-0.19781250386698537,0.056559663095182504,0.019793962473512387,0.1971310884520976,-0.12167779602427684,-0.015212281756743962,-0.018571340241220872,-0.23826092512051542,0.018690457382826417,0.017889924826328105,0.17314279219139778,-0.014108776666054663,-0.19781250386698537,0.056559663095182504,0.019793962473512387,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.6833567,1.0,1.0,1.0,1.0,-0.16728025848227973,0.8193284361991046,0.554441498749107,0.9576604536946622,-0.1225501836507657,-0.05783803448949607,0.25401312895771616,0.2598165613988616,0.1178220700051558,0.016356778608867608,-0.4473626740506016,0.3122685224629287,-1.139459897217104,0.1917897733939502,-0.13233457383953098,-0.03226195397325598,-0.02050363958016507,-0.22800987071706577,0.04281670436396598,0.02930860515076151,0.1474780540127045,-0.032193405549058925,-0.18298480782334045,0.051802757135183015,0.04288525278815637,0.1917897733939502,-0.13233457383953098,-0.03226195397325598,-0.02050363958016507,-0.22800987071706577,0.04281670436396598,0.02930860515076151,0.1474780540127045,-0.032193405549058925,-0.18298480782334045,0.051802757135183015,0.04288525278815637,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7000234,1.0,1.0,1.0,1.0,-0.1648006769326421,0.8231455164087407,0.554383522595731,0.9594510367859113,-0.12723100983204075,-0.05791044414673455,0.24477001165642656,0.2402800006935767,0.13377283718694383,0.004693519455503734,-0.6074165987136312,0.24576295873494758,-1.0848459507294097,0.18863875099913666,-0.13854987839515523,-0.03630427562732977,-0.021932269256895332,-0.21737359942541828,0.06981142002014709,-0.00864988437778111,0.32886948632964325,0.06689506299363622,-0.16877992489744004,0.04895333753963662,0.053554601678164435,0.18863875099913666,-0.13854987839515523,-0.03630427562732977,-0.021932269256895332,-0.21737359942541828,0.06981142002014709,-0.00864988437778111,0.32886948632964325,0.06689506299363622,-0.16877992489744004,0.04895333753963662,0.053554601678164435,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7166901,1.0,1.0,0.0,1.0,-0.1623401632968925,0.8270225591957193,0.5537679342514109,0.9610326549510929,-0.13222514060787893,-0.058682838022743274,0.23556118702043582,0.23658904648477702,0.14312800458404776,-0.033114419271545056,-0.5683076621644891,0.16935967503031682,-1.0876953704760257,0.18659879996060183,-0.13545310279177014,-0.01966958670239234,-0.02516893016078237,-0.2116907120555536,0.07827538623896389,-0.07963041629739125,0.5511946592577535,0.20317636531480582,-0.16351521041837372,0.05315243490953423,0.03879041329771754,0.18659879996060183,-0.13545310279177014,-0.01966958670239234,-0.02516893016078237,-0.2116907120555536,0.07827538623896389,-0.07963041629739125,0.5511946592577535,0.20317636531480582,-0.16351521041837372,0.05315243490953423,0.03879041329771754,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7333568,1.0,1.0,0.0,1.0,-0.15973669342154384,0.8306631766068324,0.5523797350338383,0.9626382981139372,-0.13593899326603892,-0.05983782538427016,0.2264233463391091,0.22123766410274304,0.15211739729230828,-0.05610425363438783,-0.4668251267187037,0.08824494467680075,-1.0519956467398215,0.1763863639850058,-0.12436898721021519,0.00044093669634655383,-0.02735069211273564,-0.19777065451841613,0.07843812275362776,-0.09629031143593228,0.6093427438795588,0.23328276342003235,-0.15270539537757846,0.05569847184770846,0.01841637881552204,0.1763863639850058,-0.12436898721021519,0.00044093669634655383,-0.02735069211273564,-0.19777065451841613,0.07843812275362776,-0.09629031143593228,0.6093427438795588,0.23328276342003235,-0.15270539537757846,0.05569847184770846,0.01841637881552204,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7500235,1.0,1.0,0.0,1.0,-0.1575718701519594,0.834281821553887,0.5509114336268863,0.9640396116041625,-0.1390045630473662,-0.061415669510908995,0.21802172884516158,0.2107648855549914,0.1598507920103222,-0.051185848724157455,-0.4437553186355969,0.054350919531591296,-0.9994400834408003,0.16606261106948758,-0.11935057935571271,0.0062984736792010155,-0.029178965178516612,-0.18540097696221192,0.07939873793287075,-0.0987095637249094,0.7131489020601292,0.24080341194495256,-0.14230379536370974,0.055325122333853415,0.012917700285112103,0.16606261106948758,-0.11935057935571271,0.0062984736792010155,-0.029178965178516612,-0.18540097696221192,0.07939873793287075,-0.0987095637249094,0.7131489020601292,0.24080341194495256,-0.14230379536370974,0.055325122333853415,0.012917700285112103,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7666902,1.0,1.0,0.0,1.0,-0.15527549486574221,0.8379407132903521,0.5495876739244273,0.9652989561810136,-0.14224300766805223,-0.06289033588082243,0.2097847888150844,0.23304979612295293,0.16738056048836716,-0.03829176567753732,-0.3078900464105585,0.053388991360353286,-0.9337423233719311,0.14932262142328914,-0.10654744158590325,0.015385288820834564,-0.030554427288186425,-0.17052139117755216,0.06253688173999469,-0.1145375452638903,0.9310605818865649,0.22417331050181394,-0.13242374152069172,0.05591347955094054,-0.0004691040564178223,0.14932262142328914,-0.10654744158590325,0.015385288820834564,-0.030554427288186425,-0.17052139117755216,0.06253688173999469,-0.1145375452638903,0.9310605818865649,0.22417331050181394,-0.13242374152069172,0.05591347955094054,-0.0004691040564178223,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.7833569,1.0,1.0,0.0,1.0,-0.15247746740676932,0.8421127252930305,0.5484969724335935,0.9666420395154287,-0.14316492450784213,-0.0638639003908005,0.20255461993988216,0.23752436270082314,0.16163594094183636,-0.03065680902431059,-0.18005283469906871,0.09024871294986457,-0.8883208644532116,0.13534124973308997,-0.09803124135367013,0.01857155969646892,-0.03283103747542731,-0.16178418332292158,0.04117252552512136,-0.12155232370203008,1.2561992822603232,0.2088533360812543,-0.12811668403310142,0.05784466626657328,-0.0089761991004658,0.13534124973308997,-0.09803124135367013,0.01857155969646892,-0.03283103747542731,-0.16178418332292158,0.04117252552512136,-0.12155232370203008,1.2561992822603232,0.2088533360812543,-0.12811668403310142,0.05784466626657328,-0.0089761991004658,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8000236,1.0,1.0,0.0,1.0,-0.14989817589771193,0.8456544515811122,0.5475037171580321,0.967963537255587,-0.14449751763347057,-0.0641608563269173,0.19506522615990152,0.2208518861615168,0.15840908091889605,-0.0257413681507324,-0.1481719111820084,0.14854356670038665,-0.8506363841558072,0.12613261913988635,-0.09757515469978924,0.011138073683575559,-0.03495626507712851,-0.1575739684884544,0.027772699659198225,-0.09086535494242047,1.532985545486794,0.200091110386753,-0.12613039173665955,0.05826993637447487,-0.004568094417607053,0.12613261913988635,-0.09757515469978924,0.011138073683575559,-0.03495626507712851,-0.1575739684884544,0.027772699659198225,-0.09086535494242047,1.532985545486794,0.200091110386753,-0.12613039173665955,0.05826993637447487,-0.004568094417607053,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8166903,1.0,1.0,0.0,1.0,-0.1474777271198165,0.8494686849789512,0.5465719565763433,0.9692156698223507,-0.14512627654141513,-0.06400255347518283,0.18831628282411772,0.2236844094291252,0.18153979280963142,-0.00628487014638791,-0.13723757922716118,0.18313066728643768,-0.7899582224829741,0.11481416426622708,-0.0949080507984247,0.004021263071233796,-0.03554696938372379,-0.14846975336335125,0.019121686711720032,-0.02926840155038754,1.7445827361369768,0.2242748707568501,-0.11951791584826453,0.056346556960140494,0.0006750676538716263,0.11481416426622708,-0.0949080507984247,0.004021263071233796,-0.03554696938372379,-0.14846975336335125,0.019121686711720032,-0.02926840155038754,1.7445827361369768,0.2242748707568501,-0.11951791584826453,0.056346556960140494,0.0006750676538716263,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.833357,1.0,1.0,0.0,1.0,-0.14509104837544368,0.8538281017480389,0.5459740424461442,0.9703073105250812,-0.14644452809214714,-0.06353921799352709,0.1817154124179428,0.23697617658450648,0.19904542903035632,0.011493822534210121,-0.1219236092597366,0.25291230763904665,-0.7702662578924464,0.10875635476517541,-0.09747441929513005,-0.0056629909732324015,-0.03820945701189122,-0.14834329945033392,0.006685514265682622,0.05724882503341263,1.9254380403532951,0.2425852922651581,-0.12088435913006025,0.0577793298013493,0.007594960973354588,0.10875635476517541,-0.09747441929513005,-0.0056629909732324015,-0.03820945701189122,-0.14834329945033392,0.006685514265682622,0.05724882503341263,1.9254380403532951,0.2425852922651581,-0.12088435913006025,0.0577793298013493,0.007594960973354588,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8500237,1.0,1.0,0.0,1.0,-0.1424478327040133,0.8584134078978964,0.5454503667616565,0.9715192878031024,-0.14704216775982007,-0.06216668506119396,0.1751119002111165,0.25014250890229356,0.19783418807484732,0.021102364281004437,-0.03182425770821373,0.32234885129216223,-0.7572022997597052,0.10100780699671821,-0.0951877898326626,-0.009346845503274725,-0.04109312190075499,-0.14784391284957418,-0.013804114280387334,0.1817597678925418,2.0768303565071067,0.13882416814869206,-0.12308024609457549,0.06117796614078052,0.006216827726691395,0.10100780699671821,-0.0951877898326626,-0.009346845503274725,-0.04109312190075499,-0.14784391284957418,-0.013804114280387334,0.1817597678925418,2.0768303565071067,0.13882416814869206,-0.12308024609457549,0.06117796614078052,0.006216827726691395,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8666904,1.0,1.0,0.0,1.0,-0.1395731560236308,0.8629081222467239,0.5451917085495634,0.9727737843657434,-0.14711243036598054,-0.06027182227065817,0.16863097201504557,0.26390988380994257,0.1958268618161132,0.03894892950680972,0.07426228001303561,0.3677060332275507,-0.7489765372551497,0.0940647833369315,-0.09063526223450048,-0.008191649209129593,-0.04372543593439993,-0.14639439567757892,-0.032436079128907946,0.36078235758050975,2.2640212841466947,-0.027723812127700156,-0.12416052584847884,0.06499364340529969,0.000308023835191116,0.0940647833369315,-0.09063526223450048,-0.008191649209129593,-0.04372543593439993,-0.14639439567757892,-0.032436079128907946,0.36078235758050975,2.2640212841466947,-0.027723812127700156,-0.12416052584847884,0.06499364340529969,0.000308023835191116,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.8833571,1.0,1.0,0.0,1.0,-0.136457507707757,0.867674524100436,0.5452771502755004,0.974174309704775,-0.14611546888520527,-0.05783979048154621,0.16213957783568028,0.27620045861403897,0.21879763773595745,0.051864584844564944,0.22302504262377695,0.4069530047563505,-0.7406179458198313,0.08605167108477749,-0.08241010121236188,-0.003004555053741966,-0.04625830249019631,-0.14357319151002723,-0.05510876486678399,0.5194565894375114,2.4200550025412157,-0.16879909597669962,-0.12474811158604988,0.06958053051269895,-0.010706918054530652,0.08605167108477749,-0.08241010121236188,-0.003004555053741966,-0.04625830249019631,-0.14357319151002723,-0.05510876486678399,0.5194565894375114,2.4200550025412157,-0.16879909597669962,-0.12474811158604988,0.06958053051269895,-0.010706918054530652,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9000238,1.0,1.0,0.0,1.0,-0.13336957200415234,0.8730302998334865,0.5452233623884645,0.9757086338209136,-0.14387283072871507,-0.05487371303021668,0.15582729569529993,0.27714661328616547,0.22791426030512418,0.07092437752935035,0.3515995340307103,0.398863285867721,-0.7510679323416902,0.08270500226740035,-0.07491626198944853,0.00816697452617657,-0.048716376841855105,-0.14141962821439982,-0.06817550091777956,0.5904110047568307,2.4633372120702934,-0.26485243927835384,-0.12461801879640111,0.07465040258295297,-0.025361975411384626,0.08270500226740035,-0.07491626198944853,0.00816697452617657,-0.048716376841855105,-0.14141962821439982,-0.06817550091777956,0.5904110047568307,2.4633372120702934,-0.26485243927835384,-0.12461801879640111,0.07465040258295297,-0.025361975411384626,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9166905,1.0,1.0,0.0,1.0,-0.13027293228984127,0.8781666062337466,0.5458413342917308,0.9773296783689556,-0.14074928678771617,-0.05224638839446027,0.14928714930535147,0.2716580524601256,0.20863343019445912,0.08123570884939789,0.48355937817489075,0.36931082716673835,-0.7763350040243332,0.08221556782279456,-0.06751795441154704,0.02356388997399712,-0.05147613522242982,-0.14009801765089477,-0.07815821981355903,0.6870012004836077,2.4489354523888514,-0.3055316351710521,-0.1249720614546848,0.0809048346720561,-0.04337180229578068,0.08221556782279456,-0.06751795441154704,0.02356388997399712,-0.05147613522242982,-0.14009801765089477,-0.07815821981355903,0.6870012004836077,2.4489354523888514,-0.3055316351710521,-0.1249720614546848,0.0809048346720561,-0.04337180229578068,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9333572,1.0,1.0,0.0,1.0,-0.12708474773365097,0.8828775361892047,0.5463315991231348,0.9790904174863592,-0.1362374789024473,-0.04948502380255009,0.14273239347798128,0.28568708055977665,0.19380472893141082,0.05897954759170629,0.6207713431520246,0.3364065588368343,-0.8239925563012415,0.08499975067293977,-0.06248150187877118,0.040717593645830025,-0.05553367531249212,-0.14192413974382628,-0.08779424037641392,0.7914954142127478,2.367393623853289,-0.30044180994536673,-0.12800972566017743,0.08961122787071177,-0.06282286343150507,0.08499975067293977,-0.06248150187877118,0.040717593645830025,-0.05553367531249212,-0.14192413974382628,-0.08779424037641392,0.7914954142127478,2.367393623853289,-0.30044180994536673,-0.12800972566017743,0.08961122787071177,-0.06282286343150507,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9500239,1.0,1.0,0.0,1.0,-0.12317011188646554,0.8874104751748456,0.5464624488802721,0.9809687386600514,-0.13074366763254974,-0.04715455603933168,0.13558346134551458,0.2896292048124702,0.1993299028698457,0.0251963078106595,0.6345326802656817,0.24113644263660827,-0.8986071747633034,0.09665187998857985,-0.06666170627954912,0.05813850910003785,-0.059389552424279936,-0.1475831398576172,-0.07408894612765109,0.8989713777181105,2.2653671957399575,-0.27204433210894874,-0.1302814348377051,0.09739427100258542,-0.07683371793292551,0.09665187998857985,-0.06666170627954912,0.05813850910003785,-0.059389552424279936,-0.1475831398576172,-0.07408894612765109,0.8989713777181105,2.2653671957399575,-0.27204433210894874,-0.1302814348377051,0.09739427100258542,-0.07683371793292551,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9666906,1.0,1.0,0.0,1.0,-0.1196212913775932,0.8919422906783465,0.5459006078354207,0.9826945861974835,-0.1257122365770117,-0.04606115215219101,0.128008414158503,0.25451255015289664,0.1978033792812752,0.02026263918937867,0.6021683040960033,0.18186624255686412,-0.9646699009526063,0.10705711678776374,-0.07555385709330557,0.0662392354340181,-0.06398282048358063,-0.15453944171272455,-0.06113814494696088,0.9183900086569593,2.105174307664991,-0.21216916776120315,-0.1333693892074349,0.10443578670047746,-0.0814064968198136,0.10705711678776374,-0.07555385709330557,0.0662392354340181,-0.06398282048358063,-0.15453944171272455,-0.06113814494696088,0.9183900086569593,2.105174307664991,-0.21216916776120315,-0.1333693892074349,0.10443578670047746,-0.0814064968198136,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +11.9833573,1.0,1.0,0.0,1.0,-0.116665723722777,0.895971015346599,0.5459018095955696,0.9844228867314818,-0.12052833618765502,-0.04491039610933469,0.11986474284123083,0.2297208822557856,0.1801773468418216,0.030182341725979,0.6274301244505811,0.1641007159722253,-1.0551869457538268,0.11769369129319507,-0.08606498923836649,0.07383762806666394,-0.07175919686758968,-0.16634689192097854,-0.060078316736187416,0.8118985513681961,1.8079760153720141,-0.16343411772832586,-0.1418943249431203,0.11630914004564408,-0.08815695094410651,0.11769369129319507,-0.08606498923836649,0.07383762806666394,-0.07175919686758968,-0.16634689192097854,-0.060078316736187416,0.8118985513681961,1.8079760153720141,-0.16343411772832586,-0.1418943249431203,0.11630914004564408,-0.08815695094410651,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.000024,1.0,1.0,0.0,1.0,-0.11368521633116374,0.8997190518097533,0.5458393450929304,0.9861763997036636,-0.11495998829935433,-0.044233020291985316,0.1108320787208343,0.21339406129379754,0.18639685739359477,0.004553305301746545,0.6248648474593417,0.09869432507478043,-1.1533557944357582,0.13096465214259176,-0.09800243981018912,0.08627393394437999,-0.07905183125736502,-0.1777627355526392,-0.04915637035920962,0.6647024460570324,1.4644949532265137,-0.12250680212216719,-0.1477863718972386,0.12806740164982075,-0.09757074106498427,0.13096465214259176,-0.09800243981018912,0.08627393394437999,-0.07905183125736502,-0.1777627355526392,-0.04915637035920962,0.6647024460570324,1.4644949532265137,-0.12250680212216719,-0.1477863718972386,0.12806740164982075,-0.09757074106498427,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0166907,1.0,1.0,1.0,1.0,-0.11106729543926308,0.9035275880629476,0.5450185729841701,0.987818908734187,-0.10959724715406817,-0.04433815232837833,0.10117497324712138,0.17273707259993298,0.1943706832844867,-0.002267417922633746,0.5718485517953127,0.07848215429617522,-1.2770304524087002,0.1461631616905904,-0.11938976820324605,0.08859778374802468,-0.09048218592247523,-0.19637300510785155,-0.0393148840582315,0.32704896956229085,0.7565452085586858,-0.02901341801518806,-0.15889300341808532,0.14238407505013048,-0.097037896939559,0.1461631616905904,-0.11938976820324605,0.08859778374802468,-0.09048218592247523,-0.19637300510785155,-0.0393148840582315,0.32704896956229085,0.7565452085586858,-0.02901341801518806,-0.15889300341808532,0.14238407505013048,-0.097037896939559,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0333574,1.0,1.0,1.0,1.0,-0.10929161969533818,0.9071009908081253,0.5446815564193719,0.989420837071889,-0.10473133864990282,-0.044296062547183074,0.09008669555144,0.1317265919272477,0.192424227493972,0.008840275040230942,0.5581647087862456,0.11040608532208451,-1.4013332361310056,0.3735775761366355,-0.08533570854234221,0.18811677707545899,-0.10467967635821077,-0.21578926032388207,-0.04159447108530024,0.0902480977872002,0.23401398875789844,0.03343148174944133,-0.17249767213196734,0.1594391696082432,-0.09461428330078359,0.3735775761366355,-0.08533570854234221,0.18811677707545899,-0.10467967635821077,-0.21578926032388207,-0.04159447108530024,0.0902480977872002,0.23401398875789844,0.03343148174944133,-0.17249767213196734,0.1594391696082432,-0.09461428330078359,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0500241,0.0,1.0,1.0,1.0,-0.10788021231192968,0.9105791353175046,0.5442271531282322,0.9909690231037381,-0.09952202303491156,-0.0441253231730121,0.07828612926143919,0.11427075100326059,0.18669011548256292,-0.004997804400634799,0.5613499117835027,0.18973492705575884,-1.4720008583724296,0.6762075138435382,0.013795495957122728,0.2977092240704274,-0.11780976824466122,-0.22692424096620553,-0.05478220954933843,0.09614233590159255,0.24258892390538586,0.044526867114531736,-0.18191123266698267,0.1730754997655154,-0.08623004929892858,0.6762075138435382,0.013795495957122728,0.2977092240704274,-0.11780976824466122,-0.22692424096620553,-0.05478220954933843,0.09614233590159255,0.24258892390538586,0.044526867114531736,-0.18191123266698267,0.1730754997655154,-0.08623004929892858,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0666908,0.0,1.0,1.0,1.0,-0.10643783990512884,0.9137172035716026,0.5435222097804113,0.9924067557997458,-0.09461196640960802,-0.04286446036989339,0.06587901708684474,0.15043577976239667,0.18521932232663332,-0.06555082812892898,0.5341419020519551,0.2555509020772162,-1.4528320779644537,0.9134191771946988,0.00778581237315703,0.3183769157909847,-0.123979222046823,-0.2237181918197649,-0.06433377730521639,0.09656752134431873,0.23635447025501394,0.05263830234556118,-0.17991127152018876,0.17630288807145633,-0.07295909978523825,0.9134191771946988,0.00778581237315703,0.3183769157909847,-0.123979222046823,-0.2237181918197649,-0.06433377730521639,0.09656752134431873,0.23635447025501394,0.05263830234556118,-0.17991127152018876,0.17630288807145633,-0.07295909978523825,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.0833575,0.0,1.0,1.0,1.0,-0.10347171226298124,0.9168873832573958,0.5412591199367494,0.9935995396415187,-0.08993030470272165,-0.04160423349075718,0.054236361196934646,0.14037991366491384,0.1765391396702325,-0.08877444527816382,0.3788371993417782,0.2951307408533791,-1.3194831664583053,1.142506709964918,-0.04695131306718235,0.4038707394764838,-0.12005752906243032,-0.20546672706835725,-0.05847868037266807,0.08999061992102493,0.20603677174466498,0.04787080774063672,-0.16421035970267184,0.16187838849678887,-0.04561434576002363,1.142506709964918,-0.04695131306718235,0.4038707394764838,-0.12005752906243032,-0.20546672706835725,-0.05847868037266807,0.08999061992102493,0.20603677174466498,0.04787080774063672,-0.16421035970267184,0.16187838849678887,-0.04561434576002363,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1000242,0.0,1.0,1.0,1.0,-0.10211891505758425,0.9194959222592907,0.5398841862349557,0.9943947814921289,-0.08768212480335226,-0.03959068187572966,0.04385705689858277,0.0802325586301071,0.15758372562549527,-0.03318826963069412,0.29271739844497524,0.41478439878121626,-1.1352378034713173,1.1997244082709766,0.014177131460100707,0.48926575350426765,-0.11327371105645782,-0.1801655550682061,-0.0715998448476409,0.07202823640610262,0.1757765360315723,0.05813396545120857,-0.14839819948249972,0.14405674707996144,-0.015532854928456278,1.1997244082709766,0.014177131460100707,0.48926575350426765,-0.11327371105645782,-0.1801655550682061,-0.0715998448476409,0.07202823640610262,0.1757765360315723,0.05813396545120857,-0.14839819948249972,0.14405674707996144,-0.015532854928456278,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1166909,0.0,1.0,1.0,1.0,-0.1011420396034553,0.9221019743596522,0.5394290977100692,0.9951405705547058,-0.08461649012328978,-0.03618733602854451,0.03501101464435325,0.07632049239212199,0.13910658659522723,-0.0010625067012454345,0.3405093670651952,0.5263000933304912,-0.9871900608691633,1.158128478511911,0.08108012414260207,0.49191944787538316,-0.10787569954248222,-0.15631140880273733,-0.09688948189867283,0.05466106838262832,0.1598199117299171,0.07857282705773476,-0.1364221191822273,0.13336912301861503,-0.0014775345062350669,1.158128478511911,0.08108012414260207,0.49191944787538316,-0.10787569954248222,-0.15631140880273733,-0.09688948189867283,0.05466106838262832,0.1598199117299171,0.07857282705773476,-0.1364221191822273,0.13336912301861503,-0.0014775345062350669,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1333576,0.0,1.0,1.0,1.0,-0.09987974284300205,0.9242420271953128,0.5392248719642202,0.9957735907033383,-0.08173763533449308,-0.03205614463744373,0.026950299046380966,0.08973755424125603,0.1329845422892071,-0.00957650174666811,0.27263069146078556,0.5405873648806766,-0.9174169729871207,1.1877785642687335,0.052423493268911714,0.45990674017935,-0.10555298325766246,-0.1460013227933952,-0.09328961708765471,0.05102609379868361,0.14511996407402256,0.07571461246955491,-0.12796680328077178,0.12542089092754222,0.0111190919131007,1.1877785642687335,0.052423493268911714,0.45990674017935,-0.10555298325766246,-0.1460013227933952,-0.09328961708765471,0.05102609379868361,0.14511996407402256,0.07571461246955491,-0.12796680328077178,0.12542089092754222,0.0111190919131007,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1500243,0.0,1.0,1.0,1.0,-0.09835418146986041,0.926593942685407,0.538563334937061,0.9962193214716392,-0.0798471704829159,-0.02833610226240873,0.01919786970039522,0.07487567126198644,0.14746313583850576,-0.020234868527529898,0.05514288335005246,0.47530156847339605,-0.8562562830996323,1.1825427947584544,0.07764860666583616,0.3157106029317269,-0.10075669787106524,-0.1405032864846107,-0.06134916727765643,0.05325851077343712,0.120647256432536,0.049417297397234154,-0.11666879635124515,0.11143037514962217,0.02937513746627567,1.1825427947584544,0.07764860666583616,0.3157106029317269,-0.10075669787106524,-0.1405032864846107,-0.06134916727765643,0.05325851077343712,0.120647256432536,0.049417297397234154,-0.11666879635124515,0.11143037514962217,0.02937513746627567,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.166691,0.0,1.0,1.0,1.0,-0.09751535707485082,0.9290913639565727,0.5379059687367038,0.9963544900873705,-0.08057300959778772,-0.02526747732482477,0.01213568278796684,0.08107728751149462,0.1549738020601007,-0.010205842216267278,-0.21747781072793831,0.36915043432527045,-0.775860901422843,1.1292333157865402,0.17740926807572174,0.13087621385335627,-0.0918905995000953,-0.1336129852162891,-0.017202279375053593,0.05535479320970879,0.08962592848949928,0.012924007694695155,-0.10169817972739112,0.09218255367285405,0.04825207930172654,1.1292333157865402,0.17740926807572174,0.13087621385335627,-0.0918905995000953,-0.1336129852162891,-0.017202279375053593,0.05535479320970879,0.08962592848949928,0.012924007694695155,-0.10169817972739112,0.09218255367285405,0.04825207930172654,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.1833577,0.0,1.0,1.0,1.0,-0.09574194253497054,0.9317130997476951,0.5375262006825379,0.9962434217628137,-0.08321242823826057,-0.023277955976494992,0.005733510841482548,0.0893637540088934,0.16579503407997442,0.03562814705742017,-0.39399816071601385,0.30019161272070005,-0.6894224405363847,1.141605700799992,0.239646014525318,0.024109703903114725,-0.0829368872820259,-0.12381884091147786,0.011173711856318413,0.052972188375943606,0.06511301004463164,-0.010426341748876437,-0.04762349354699478,0.3414094923243783,0.11280305883175525,1.141605700799992,0.239646014525318,0.024109703903114725,-0.0829368872820259,-0.12381884091147786,0.011173711856318413,0.052972188375943606,0.06511301004463164,-0.010426341748876437,-0.04762349354699478,0.3414094923243783,0.11280305883175525,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2000244,0.0,1.0,1.0,0.0,-0.09463792370945068,0.9347831357114451,0.5382933904969692,0.9959921941166021,-0.08687460101508591,-0.021268244539958556,0.00012137320551913745,0.059393660757668304,0.18281141884043062,0.0644210182268988,-0.4920301347235016,0.22830665829262936,-0.5938682551443427,1.0449383708993853,0.20460545194986762,-0.054876536362396,-0.07193335802332751,-0.10996744643865206,0.031456957471710754,0.04857676884053006,0.044402270256923435,-0.026807818591811108,0.02185392129842398,0.596121420578376,0.19362280029642853,1.0449383708993853,0.20460545194986762,-0.054876536362396,-0.07193335802332751,-0.10996744643865206,0.031456957471710754,0.04857676884053006,0.044402270256923435,-0.026807818591811108,0.02185392129842398,0.596121420578376,0.19362280029642853,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2166911,0.0,1.0,1.0,0.0,-0.09383391677468045,0.9380942369728349,0.5386684823406265,0.9956163906018648,-0.09117462387832063,-0.02034224406836272,-0.004624265544373618,0.03771922623596875,0.20301662092474587,0.05565970171995544,-0.6651694896802396,0.10366651843742486,-0.48381626013006457,0.8144511152865589,0.11261714955711809,-0.14357202062802452,-0.05697668807791326,-0.09493898344136367,0.06712787430105019,0.045335585505936866,0.015505533495623393,-0.05544606006365674,0.021711323015810028,0.6098832833868094,0.1951935265688416,0.8144511152865589,0.11261714955711809,-0.14357202062802452,-0.05697668807791326,-0.09493898344136367,0.06712787430105019,0.045335585505936866,0.015505533495623393,-0.05544606006365674,0.021711323015810028,0.6098832833868094,0.1951935265688416,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2333578,0.0,1.0,1.0,0.0,-0.0933678807183731,0.9417678410949253,0.538941007579788,0.9949719250176059,-0.097742211260157,-0.020216310063427292,-0.008284284649507645,0.016808968207127267,0.2199475864068063,0.06929694361883786,-0.7119753381655347,0.007024908908709604,-0.3709899034711973,0.5717152779018114,0.14737142810808126,-0.29970753274703654,-0.0419317720871129,-0.07614640253953305,0.08491080901575616,0.03960667511609182,-0.004621380837988456,-0.06925286536180136,-0.0003619229685714503,0.6093925308666381,0.16414968486075118,0.5717152779018114,0.14737142810808126,-0.29970753274703654,-0.0419317720871129,-0.07614640253953305,0.08491080901575616,0.03960667511609182,-0.004621380837988456,-0.06925286536180136,-0.0003619229685714503,0.6093925308666381,0.16414968486075118,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2500245,0.0,1.0,1.0,0.0,-0.09321349901043102,0.94572777692924,0.5395322576446652,0.9944188345273349,-0.10285851425717532,-0.020731281563167656,-0.0110236811842499,0.029346660954262513,0.23354811798690678,0.0772412510657305,-0.5585232382947606,-0.05416445081674451,-0.2909254364508881,0.22984009407381512,0.2649357717295851,-0.5290516421924614,-0.03062768246230393,-0.05706577091143656,0.07606628876833343,0.03446180609843104,-0.005938595117409681,-0.06137284813763977,0.06551467460673903,0.6251115935901641,0.1626816949869843,0.22984009407381512,0.2649357717295851,-0.5290516421924614,-0.03062768246230393,-0.05706577091143656,0.07606628876833343,0.03446180609843104,-0.005938595117409681,-0.06137284813763977,0.06551467460673903,0.6251115935901641,0.1626816949869843,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2666912,0.0,1.0,1.0,0.0,-0.09228717408322618,0.9498967823371705,0.5399125784632689,0.993948289127704,-0.10691002291784359,-0.021510307589694997,-0.013204249589167718,0.03989827300364156,0.24351249107487274,0.08052018634556629,-0.4623704890774077,-0.1110498774904621,-0.19795594908622488,-0.2157116962616646,0.3664215197155786,-0.7965347445465443,-0.01821190730516222,-0.03837448569516867,0.07194200366664365,0.02785615433471887,-0.012422507242655817,-0.05761151687692881,0.19326386880415103,0.7206447258209209,0.14728855680552785,-0.2157116962616646,0.3664215197155786,-0.7965347445465443,-0.01821190730516222,-0.03837448569516867,0.07194200366664365,0.02785615433471887,-0.012422507242655817,-0.05761151687692881,0.19326386880415103,0.7206447258209209,0.14728855680552785,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.2833579,0.0,1.0,1.0,0.0,-0.09174204315992535,0.9541996475032606,0.5404925697430831,0.9935145967993269,-0.11047387637909648,-0.022818463370554962,-0.014268367595975941,0.01933889913027595,0.25440094444990197,0.09764690606596993,-0.46696021763001827,-0.2005689155391712,-0.09129126279176326,-0.6517887031208245,0.2761149073652596,-0.9653616903753391,-0.0033795177641127412,-0.019699488409000196,0.08299478983605299,0.021989426380180664,-0.028531677926693498,-0.06604786898369269,0.3415344018379752,0.8438227874733922,0.11513484309662138,-0.6517887031208245,0.2761149073652596,-0.9653616903753391,-0.0033795177641127412,-0.019699488409000196,0.08299478983605299,0.021989426380180664,-0.028531677926693498,-0.06604786898369269,0.3415344018379752,0.8438227874733922,0.11513484309662138,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3000246,0.0,1.0,1.0,0.0,-0.09149761849008714,0.9588679814769001,0.5412599295685152,0.99298725530638,-0.11465670509368502,-0.024884836573690675,-0.014522247927320655,0.025503770677626658,0.2565012702955568,0.09516747388610342,-0.49586187714241253,-0.22462067165912183,-0.045568044061609116,-0.5521953443266339,0.02969548251811327,-0.5027259806859272,0.0020021457425388432,-0.012541200398596767,0.08857608550575793,0.018907580048846757,-0.037239445655397684,-0.07006520309446039,0.4774522023138093,0.9121311690112787,0.08176194990658486,-0.5521953443266339,0.02969548251811327,-0.5027259806859272,0.0020021457425388432,-0.012541200398596767,0.08857608550575793,0.018907580048846757,-0.037239445655397684,-0.07006520309446039,0.4774522023138093,0.9121311690112787,0.08176194990658486,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3166913,0.0,1.0,1.0,0.0,-0.09074415713105777,0.963226264697458,0.5416816211957943,0.9924641576474856,-0.11871572654609898,-0.026503111293420586,-0.014800579294990958,0.05512872558293026,0.2530270752355034,0.07221439463664156,-0.5526306677265395,-0.1976645206798233,0.016483227244018732,-0.22345353566689932,-0.13928021299368862,-0.0184450743166121,0.006641842386328413,-0.005251672410311365,0.08900156321867217,0.011310653867382817,-0.048583975573362234,-0.06977631588094604,0.5885025921490329,0.9723050601662335,0.041960197976033356,-0.22345353566689932,-0.13928021299368862,-0.0184450743166121,0.006641842386328413,-0.005251672410311365,0.08900156321867217,0.011310653867382817,-0.048583975573362234,-0.06977631588094604,0.5885025921490329,0.9723050601662335,0.041960197976033356,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.333358,1.0,1.0,1.0,0.0,-0.08948069450389073,0.9675874965311342,0.5417181294938762,0.9918054797400316,-0.12385476710632781,-0.02798105875863382,-0.014104870556967908,0.0562075447768972,0.25657902488309625,0.05853280084293665,-0.5476198635058542,-0.21074137880609248,0.13241793878014424,-0.10805564570341232,-0.10220918043102682,-0.02075596730784651,0.019203193127891465,0.012740033921328156,0.0868623021997886,0.00019949740500005363,-0.06297632787513863,-0.0675909072906889,0.6944971353684004,1.0051537389370262,-0.006534643958613875,-0.10805564570341232,-0.10220918043102682,-0.02075596730784651,0.019203193127891465,0.012740033921328156,0.0868623021997886,0.00019949740500005363,-0.06297632787513863,-0.0675909072906889,0.6944971353684004,1.0051537389370262,-0.006534643958613875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3500247,1.0,1.0,1.0,0.0,-0.08867715277258731,0.9719545683574957,0.541585878905589,0.9912704095747076,-0.1278810589481799,-0.02957886006653279,-0.01242983914008211,0.016519933878850063,0.24523968519607817,0.08247945150501462,-0.4913083293343052,-0.19052046404097597,0.1824758439834607,-0.007240493653984594,-0.0030755744462314417,-0.02096016819782523,0.02372209360536196,0.021300861630805246,0.07616205491536204,-0.005986501990815902,-0.06460724626111461,-0.05874598934750253,0.8769268097796168,1.057894267415029,-0.06912984704430875,-0.007240493653984594,-0.0030755744462314417,-0.02096016819782523,0.02372209360536196,0.021300861630805246,0.07616205491536204,-0.005986501990815902,-0.06460724626111461,-0.05874598934750253,0.8769268097796168,1.057894267415029,-0.06912984704430875,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.3666914,1.0,1.0,1.0,0.0,-0.08882035772648234,0.9761819242621358,0.5423402502303266,0.9907022389322575,-0.13210180090276735,-0.030639016472382246,-0.010928798765777238,-0.005525831574022158,0.21941877778508195,0.11798935158065402,-0.4746799233211547,-0.12426069561521377,0.16348166724871632,-0.008285863094532633,-0.007308703521838008,-0.028483347502007674,0.01886243464529263,0.017107480917363388,0.06504860257741504,-0.007674725999367848,-0.05938382977462691,-0.04962474634348384,1.027817517066176,1.0889242313858427,-0.10130629392415155,-0.008285863094532633,-0.007308703521838008,-0.028483347502007674,0.01886243464529263,0.017107480917363388,0.06504860257741504,-0.007674725999367848,-0.05938382977462691,-0.04962474634348384,1.027817517066176,1.0889242313858427,-0.10130629392415155,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.383358099999999,1.0,1.0,1.0,0.0,-0.08887078066334458,0.9800461036804086,0.5434529854771528,0.9901943048776211,-0.1358257825189428,-0.031184713293612228,-0.009700981797584829,0.06241680180027766,0.2053092415336309,0.03202890552746775,-0.39318321792544386,-0.16994257806641866,0.1668783611667358,-0.0070723475543285905,0.0011036422274967152,-0.01522824967255385,0.02161006776805612,0.021889982785942754,0.0625293760951357,-0.005517581522620234,-0.055589077469489566,-0.047629876547363496,1.1012168216944378,0.9981591463713027,-0.1432173042025324,-0.0070723475543285905,0.0011036422274967152,-0.01522824967255385,0.02161006776805612,0.021889982785942754,0.0625293760951357,-0.005517581522620234,-0.055589077469489566,-0.047629876547363496,1.1012168216944378,0.9981591463713027,-0.1432173042025324,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.400024799999999,1.0,1.0,1.0,0.0,-0.08661789938657144,0.9830372590395753,0.5416636681296157,0.9897517436690355,-0.13870362621900226,-0.03299943861582069,-0.00798918198840487,0.10183845822334642,0.1825470803742351,-0.03329440525232756,-0.3195597211958717,-0.24874602393627315,0.1868451231700381,-0.005990430478064815,0.012638611276756235,0.0014532620799098954,0.027275663602939343,0.029951814998013644,0.06529920377700514,-0.002966290477976056,-0.05530697959367106,-0.049881989591667016,1.1878378399392726,0.8733670231371504,-0.19207524344562585,-0.005990430478064815,0.012638611276756235,0.0014532620799098954,0.027275663602939343,0.029951814998013644,0.06529920377700514,-0.002966290477976056,-0.05530697959367106,-0.049881989591667016,1.1878378399392726,0.8733670231371504,-0.19207524344562585,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.416691499999999,1.0,1.0,1.0,1.0,-0.08526201525399019,0.9855681998371003,0.5409500662058703,0.9893445047685874,-0.14123330799707925,-0.03481276744490381,-0.006218908202241191,0.07911175256061964,0.1535866780718862,0.03506789181749579,-0.30896770141415075,-0.2509609905658469,0.20688670852637886,-0.007934470501774918,0.016394556487605134,0.001576921862079934,0.029181774287704163,0.03361330760347188,0.06368464174774431,-0.004557817448589979,-0.05724497625160975,-0.0484180057649274,0.6248476605857622,0.37765793497883327,-0.09399191837505214,-0.007934470501774918,0.016394556487605134,0.001576921862079934,0.029181774287704163,0.03361330760347188,0.06368464174774431,-0.004557817448589979,-0.05724497625160975,-0.0484180057649274,0.6248476605857622,0.37765793497883327,-0.09399191837505214,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.433358199999999,1.0,1.0,1.0,1.0,-0.0839525577537596,0.9882728445563317,0.5415409359477846,0.9888992326014225,-0.14394464354995762,-0.03661811039716033,-0.004166694677396832,0.05519332733621562,0.1494724632371084,0.07559916015593134,-0.28231074258018624,-0.290557742392064,0.2732461919450272,-0.013086046382376267,0.029655586652164615,0.006063518092341704,0.03742538235240766,0.045896112130337625,0.06410273705282679,-0.008717948282013829,-0.0647952771386069,-0.04864410010779147,0.04179348045275678,-0.048554751660423896,0.009395118852693613,-0.013086046382376267,0.029655586652164615,0.006063518092341704,0.03742538235240766,0.045896112130337625,0.06410273705282679,-0.008717948282013829,-0.0647952771386069,-0.04864410010779147,0.04179348045275678,-0.048554751660423896,0.009395118852693613,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.450024899999999,1.0,1.0,1.0,1.0,-0.08351312971173114,0.9910664034628698,0.5420773632208187,0.9885070171093077,-0.14607357815411906,-0.03892268218787367,-0.0011881507535989046,0.03111953256221507,0.14350772080895405,0.07455222666732063,-0.21818214621648058,-0.3612941884709265,0.33880386460840806,-0.017329236398785326,0.047025704644065455,0.018136821102530894,0.04691339233196758,0.06024719699805494,0.06503744922613204,-0.010943402837342324,-0.07043053412694966,-0.04947953876555784,0.0532992258933806,-0.057209041772953516,-0.0025789106419566972,-0.017329236398785326,0.047025704644065455,0.018136821102530894,0.04691339233196758,0.06024719699805494,0.06503744922613204,-0.010943402837342324,-0.07043053412694966,-0.04947953876555784,0.0532992258933806,-0.057209041772953516,-0.0025789106419566972,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.466691599999999,1.0,1.0,1.0,1.0,-0.08304311815832277,0.9935795447913955,0.5426116061621941,0.9881389718262481,-0.1477652518540867,-0.04173915875799917,0.0021553024934300447,0.029100500415623294,0.12723554689394967,0.06693169024906567,-0.11487042947845626,-0.4162857625325313,0.3654350997521687,-0.019112213318853474,0.06124437081090425,0.032868399042244735,0.05191272277910821,0.06915253301629813,0.060768487501693315,-0.010384619619181336,-0.06776563878261507,-0.046517738731555375,0.06064031647876536,-0.05985747657721787,-0.01861765027211678,-0.019112213318853474,0.06124437081090425,0.032868399042244735,0.05191272277910821,0.06915253301629813,0.060768487501693315,-0.010384619619181336,-0.06776563878261507,-0.046517738731555375,0.06064031647876536,-0.05985747657721787,-0.01861765027211678,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 +12.483358299999999,1.0,1.0,1.0,1.0,-0.08269770650626063,0.9957895698946749,0.5430433205513278,0.9879210782751356,-0.1482042949832062,-0.04487790467022323,0.005779595196418408,0.026170400249407574,0.11920784245068941,0.061548002760308834,-0.03858280100163257,-0.4374260311772683,0.37635696853364514,-0.020254807885991988,0.06962146318990584,0.04146242330340815,0.054062114184617684,0.07343029847857402,0.05516539930668395,-0.010373300927751043,-0.0639457689962513,-0.04247529963011317,0.0639436211428553,-0.060136933707589775,-0.028772323626844027,-0.020254807885991988,0.06962146318990584,0.04146242330340815,0.054062114184617684,0.07343029847857402,0.05516539930668395,-0.010373300927751043,-0.0639457689962513,-0.04247529963011317,0.0639436211428553,-0.060136933707589775,-0.028772323626844027,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testCsv.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testCsv.txt new file mode 100644 index 000000000..9b77681a1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testCsv.txt @@ -0,0 +1,3 @@ +t, x0,x1 +0.0, 1, 2.0 +1.0, 2.0,3.0 \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testMotion.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testMotion.txt new file mode 100644 index 000000000..0d8c2b03a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/data/testMotion.txt @@ -0,0 +1,4 @@ +time, contactflag_LF, contactflag_RF, contactflag_LH, contactflag_RH, base_positionInWorld_x, base_positionInWorld_y, base_positionInWorld_z, base_quaternion_w, base_quaternion_x, base_quaternion_y, base_quaternion_z, base_linearvelocityInBase_x, base_linearvelocityInBase_y, base_linearvelocityInBase_z, base_angularvelocityInBase_x, base_angularvelocityInBase_y, base_angularvelocityInBase_z, jointAngle_LF_HAA, jointAngle_LF_HFE, jointAngle_LF_KFE, jointAngle_RF_HAA, jointAngle_RF_HFE, jointAngle_RF_KFE, jointAngle_LH_HAA, jointAngle_LH_HFE, jointAngle_LH_KFE, jointAngle_RH_HAA, jointAngle_RH_HFE, jointAngle_RH_KFE, jointVelocity_LF_HAA, jointVelocity_LF_HFE, jointVelocity_LF_KFE, jointVelocity_RF_HAA, jointVelocity_RF_HFE, jointVelocity_RF_KFE, jointVelocity_LH_HAA, jointVelocity_LH_HFE, jointVelocity_LH_KFE, jointVelocity_RH_HAA, jointVelocity_RH_HFE, jointVelocity_RH_KFE, contactForcesInWorld_LF_x, contactForcesInWorld_LF_y, contactForcesInWorld_LF_z, contactForcesInWorld_RF_x, contactForcesInWorld_RF_y, contactForcesInWorld_RF_z, contactForcesInWorld_LH_x, contactForcesInWorld_LH_y, contactForcesInWorld_LH_z, contactForcesInWorld_RH_x, contactForcesInWorld_RH_y, contactForcesInWorld_RH_z +0.005, 1, 0, 1, 1, -4.48259e-07, 4.76863e-07, 0.57, 1.0, -7.51186e-06, -8.0022e-06, 0.1, -0.00285721, -0.00309111, 4.0385e-05, -0.000170639, 0.000181119, -8.49566e-06, -0.249992, 0.6, -0.849987, 0.250005, 0.599994, -0.849977, -0.249995, -0.600006, 0.850024, 0.250008, -0.6, 0.850013, 0.0028891, -1.29425e-05, 0.00511035, 0.00185568, -0.00221214, 0.00899715, 0.00190149, -0.00229026, 0.00909097, 0.00295002, -6.12432e-05, 0.00521847, 0.0109944, 0.0447733, 109.389, 0.00728233, 0.045991, 105.558, 0.0125948, 0.0486412, 112.733, 0.0090345, 0.0497471, 108.899 +0.0075, 1, 1, 1, 1, -9.60563e-07, 1.01966e-06, 0.57, 1.0, -1.6089e-05, -1.73971e-05, -0.1, -0.00397211, -0.00439988, 5.53082e-05, -0.000237226, 0.00025094, -2.11757e-05, -0.249984, 0.6, -0.849971, 0.25001, 0.599988, -0.849949, -0.249989, -0.600013, 0.850051, 0.250017, -0.6, 0.850029, 0.00403147, -1.14125e-05, 0.00727789, 0.00256888, -0.00306885, 0.0126809, 0.00262286, -0.00324445, 0.0129352, 0.0041237, -0.000146327, 0.00755207, 0.0279574, 0.0333893, 109.411, 0.0238772, 0.0347792, 105.134, 0.0298015, 0.0372923, 113.132, 0.0258976, 0.0385522, 108.852 +0.01, 1, 1, 1, 1, -1.62479e-06, 1.72103e-06, 0.57, 1.0, -2.72177e-05, 0.3, 3.80728e-07, -0.00490135, -0.00556399, 6.71298e-05, -0.000292297, 0.000308119, -3.88492e-05, -0.249972, 0.6, -0.849951, 0.250018, 0.599979, -0.849914, -0.249982, -0.600022, 0.850088, 0.250028, -0.600001, 0.850051, 0.00499491, -3.02358e-06, 0.00920744, 0.00315644, -0.00377577, 0.0158737, 0.00320995, -0.00408372, 0.0163522, 0.00511895, -0.000261837, 0.0097105, 0.0441173, 0.021736, 109.432, 0.0397086, 0.023289, 104.737, 0.0461933, 0.0256048, 113.506, 0.0419868, 0.0270083, 108.807 \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testLoadMotions.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testLoadMotions.cpp new file mode 100644 index 000000000..08c0f1700 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testLoadMotions.cpp @@ -0,0 +1,63 @@ +// +// Created by rgrandia on 05.10.21. +// + +#include + +#include + +#include "ocs2_anymal_commands/LoadMotions.h" + +using namespace switched_model; + +inline std::string getAbsolutePathToConfigurationFile(const std::string& fileName) { + const std::experimental::filesystem::path pathToTest = std::experimental::filesystem::path(__FILE__); + return std::string(pathToTest.parent_path()) + "/" + fileName; +} + +TEST(testLoadMotions, loadcsv) { + const auto file = getAbsolutePathToConfigurationFile("data/testCsv.txt"); + const auto result = readCsv(file); + const auto& header = result.header; + ASSERT_EQ(header[0], "t"); + ASSERT_EQ(header[1], "x0"); + ASSERT_EQ(header[2], "x1"); + + const auto& data = result.data; + ASSERT_EQ(data.size(), 2); + ASSERT_EQ(data[0].size(), 3); + ASSERT_EQ(data[1].size(), 3); + ASSERT_DOUBLE_EQ(data[0][0], 0.0); + ASSERT_DOUBLE_EQ(data[0][1], 1.0); + ASSERT_DOUBLE_EQ(data[0][2], 2.0); + ASSERT_DOUBLE_EQ(data[1][0], 1.0); + ASSERT_DOUBLE_EQ(data[1][1], 2.0); + ASSERT_DOUBLE_EQ(data[1][2], 3.0); +} + +TEST(testLoadMotions, loadmotion) { + const auto file = getAbsolutePathToConfigurationFile("data/testMotion.txt"); + const auto csvData = readCsv(file); + const auto result = readMotion(csvData); + const auto& gait = result.second; + + ASSERT_TRUE(isValidGait(gait)); +} + +TEST(testLoadMotions, loadAnimatedmotion) { + const auto file = getAbsolutePathToConfigurationFile("data/animatedMotion.txt"); + const auto csvData = readCsv(file); + const auto result = readMotion(csvData); + const auto& gait = result.second; + + ASSERT_TRUE(isValidGait(gait)); +} + +TEST(testLoadMotions, loadAnimatedCartesianMotion) { + const auto file = getAbsolutePathToConfigurationFile("data/cartesianMotion.txt"); + const auto csvData = readCsv(file); + const auto result = readCartesianMotion(csvData); + const auto& gait = result.second; + + ASSERT_TRUE(isValidGait(gait)); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testReferenceExtrapolation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testReferenceExtrapolation.cpp new file mode 100644 index 000000000..dbbd165d7 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testReferenceExtrapolation.cpp @@ -0,0 +1,78 @@ +// +// Created by rgrandia on 03.11.21. +// + +#include + +#include + +#include + +using namespace switched_model; + +TEST(TestReferenceExtrapolation, translationOnflatTerrain) { + TerrainPlane flatTerrain(vector3_t::Random(), matrix3_t::Identity()); + + BaseReferenceHorizon horizon; + horizon.dt = 0.1; + horizon.N = 5; + + BaseReferenceState initialState; + initialState.t0 = 0.42; + initialState.positionInWorld = vector3_t::Random(); + initialState.eulerXyz = vector3_t{0.0, 0.0, 5.0}; + + BaseReferenceCommand command; + command.headingVelocity = 0.3; + command.lateralVelocity = -0.1; + command.yawRate = 0.0; + command.baseHeight = 0.2; + + const auto baseRef = generateExtrapolatedBaseReference(horizon, initialState, command, flatTerrain); + + const vector3_t initialBasePosition(initialState.positionInWorld.x(), initialState.positionInWorld.y(), + command.baseHeight + flatTerrain.positionInWorld.z()); + vector3_t velocityCommand(command.headingVelocity, command.lateralVelocity, 0.0); + rotateInPlaceZ(velocityCommand, initialState.eulerXyz.z()); + + for (int k = 0; k < horizon.N; ++k) { + ASSERT_DOUBLE_EQ(baseRef.time[k], initialState.t0 + k * horizon.dt); + ASSERT_TRUE(baseRef.positionInWorld[k].isApprox(initialBasePosition + k * horizon.dt * velocityCommand)); + ASSERT_TRUE(baseRef.eulerXyz[k].isApprox(initialState.eulerXyz)); + ASSERT_TRUE(baseRef.linearVelocityInWorld[k].isApprox(velocityCommand)); + ASSERT_TRUE(baseRef.angularVelocityInWorld[k].norm() < 1e-12); + } +} + +TEST(TestReferenceExtrapolation, rotationOnflatTerrain) { + TerrainPlane flatTerrain(vector3_t::Random(), matrix3_t::Identity()); + + BaseReferenceHorizon horizon; + horizon.dt = 0.1; + horizon.N = 5; + + BaseReferenceState initialState; + initialState.t0 = 0.42; + initialState.positionInWorld = vector3_t::Random(); + initialState.eulerXyz = vector3_t{0.0, 0.0, 5.0}; + + BaseReferenceCommand command; + command.headingVelocity = 0.0; + command.lateralVelocity = 0.0; + command.yawRate = 0.4; + command.baseHeight = 0.2; + + const auto baseRef = generateExtrapolatedBaseReference(horizon, initialState, command, flatTerrain); + + const vector3_t initialBasePosition(initialState.positionInWorld.x(), initialState.positionInWorld.y(), + command.baseHeight + flatTerrain.positionInWorld.z()); + const auto angularRate = vector3_t(0.0, 0.0, command.yawRate); + + for (int k = 0; k < horizon.N; ++k) { + ASSERT_DOUBLE_EQ(baseRef.time[k], initialState.t0 + k * horizon.dt); + ASSERT_TRUE(baseRef.positionInWorld[k].isApprox(initialBasePosition)); + ASSERT_TRUE(baseRef.eulerXyz[k].isApprox(initialState.eulerXyz + k * horizon.dt * angularRate)); // Abuse that eulerXY is zero. + ASSERT_TRUE(baseRef.linearVelocityInWorld[k].norm() < 1e-12); + ASSERT_TRUE(baseRef.angularVelocityInWorld[k].isApprox(angularRate)); + } +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testTerrainAdaptation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testTerrainAdaptation.cpp new file mode 100644 index 000000000..2d199c842 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_commands/test/testTerrainAdaptation.cpp @@ -0,0 +1,91 @@ +// +// Created by rgrandia on 04.05.20. +// + +#include + +#include "ocs2_anymal_commands/TerrainAdaptation.h" + +using namespace switched_model; + +TerrainPlane getRandomTerrain() { + vector3_t eulerXYZ = vector3_t::Random(); + return {vector3_t::Random(), rotationMatrixOriginToBase(eulerXYZ)}; +} + +TEST(TestTerrainAdaptation, adaptDesiredOrientationToTerrain_flatTerrain) { + vector3_t eulerXYZ(0, 0, 0.3); + TerrainPlane flatTerrain = {vector3_t::Random(), rotationMatrixOriginToBase(eulerXYZ)}; + + vector3_t desiredEulerXYZ(0, 0, 0.0); + const auto adaptedEulerXYZ = alignDesiredOrientationToTerrain(desiredEulerXYZ, flatTerrain); + ASSERT_TRUE(desiredEulerXYZ.isApprox(adaptedEulerXYZ)); + + vector3_t desiredEulerXYZ_multipleRotations(0, 0, 10.0); + const auto adaptedEulerXYZ_multipleRotations = alignDesiredOrientationToTerrain(desiredEulerXYZ_multipleRotations, flatTerrain); + ASSERT_TRUE(desiredEulerXYZ_multipleRotations.isApprox(adaptedEulerXYZ_multipleRotations)); + + vector3_t desiredEulerXYZ_mixed(1.0, 2.0, 10.0); + const auto adaptedEulerXYZ_mixed = alignDesiredOrientationToTerrain(desiredEulerXYZ_mixed, flatTerrain); + ASSERT_TRUE(std::abs(adaptedEulerXYZ_mixed.x()) < 1e-9); + ASSERT_TRUE(std::abs(adaptedEulerXYZ_mixed.y()) < 1e-9); +} + +TEST(TestTerrainAdaptation, headingAngle) { + vector3_t desiredEulerXYZ(0, 0, -0.1); + const auto headingAngle = getHeadingAngleInWorld(desiredEulerXYZ); + ASSERT_DOUBLE_EQ(headingAngle, desiredEulerXYZ.z()); + + vector3_t desiredEulerXYZ_zero(0, 0, 0); + const auto headingAngle_zero = getHeadingAngleInWorld(desiredEulerXYZ_zero); + ASSERT_DOUBLE_EQ(headingAngle_zero, desiredEulerXYZ_zero.z()); + + vector3_t desiredEulerXYZ_multipleRotations(0, 0, 10.0); + const auto headingAngle_multipleRotations = getHeadingAngleInWorld(desiredEulerXYZ_multipleRotations); + ASSERT_DOUBLE_EQ(headingAngle_multipleRotations, desiredEulerXYZ_multipleRotations.z()); +} + +TEST(TestTerrainAdaptation, adaptDesiredOrientationToTerrain_randomTerrain) { + const auto randomTerrain = getRandomTerrain(); + TerrainPlane canonicalTerrain; + + { // Zero desired angle + const vector3_t desiredEulerXYZ(0, 0, 0.0); + const auto adaptedEulerXYZ = alignDesiredOrientationToTerrain(desiredEulerXYZ, randomTerrain); + const vector3_t adaptedXaxis = rotationMatrixBaseToOrigin(adaptedEulerXYZ).col(0); + const vector3_t projectedAdaptedXaxis = projectPositionInWorldOntoPlaneAlongGravity(adaptedXaxis, canonicalTerrain).normalized(); + ASSERT_DOUBLE_EQ(projectedAdaptedXaxis.x(), 1.0); + } + + { // Multi rotation desired angle + const vector3_t desiredEulerXYZ(0, 0, 10.0); + const vector3_t desiredXaxis = rotationMatrixBaseToOrigin(desiredEulerXYZ).col(0); + const auto adaptedEulerXYZ = alignDesiredOrientationToTerrain(desiredEulerXYZ, randomTerrain); + const vector3_t adaptedXaxis = rotationMatrixBaseToOrigin(adaptedEulerXYZ).col(0); + const vector3_t projectedAdaptedXaxis = projectPositionInWorldOntoPlaneAlongGravity(adaptedXaxis, canonicalTerrain).normalized(); + ASSERT_TRUE(desiredXaxis.isApprox(projectedAdaptedXaxis)); + } + + { // random + const vector3_t desiredEulerXYZ(0.1, 0.2, -5.0); + const vector3_t desiredXaxis = rotationMatrixBaseToOrigin(desiredEulerXYZ).col(0); + const vector3_t projectedDesiredXaxis = projectPositionInWorldOntoPlaneAlongGravity(desiredXaxis, canonicalTerrain).normalized(); + const auto adaptedEulerXYZ = alignDesiredOrientationToTerrain(desiredEulerXYZ, randomTerrain); + const vector3_t adaptedXaxis = rotationMatrixBaseToOrigin(adaptedEulerXYZ).col(0); + const vector3_t projectedAdaptedXaxis = projectPositionInWorldOntoPlaneAlongGravity(adaptedXaxis, canonicalTerrain).normalized(); + ASSERT_TRUE(projectedDesiredXaxis.isApprox(projectedAdaptedXaxis)); + } + + { // Debug : previously produced euler angles around pi, pi, pi + const vector3_t positionInWorld(-0.00807168, 0.00535307, 0.00841279); + const vector3_t surfaceNormal(-8.46512e-06, 2.99018e-05, 1); + TerrainPlane debugTerrain{positionInWorld, orientationWorldToTerrainFromSurfaceNormalInWorld(surfaceNormal)}; + const vector3_t desiredEulerXYZ(-0.000508991, -0.000493831, 0.000299875); + const vector3_t desiredXaxis = rotationMatrixBaseToOrigin(desiredEulerXYZ).col(0); + const vector3_t projectedDesiredXaxis = projectPositionInWorldOntoPlaneAlongGravity(desiredXaxis, canonicalTerrain).normalized(); + const auto adaptedEulerXYZ = alignDesiredOrientationToTerrain(desiredEulerXYZ, debugTerrain); + const vector3_t adaptedXaxis = rotationMatrixBaseToOrigin(adaptedEulerXYZ).col(0); + const vector3_t projectedAdaptedXaxis = projectPositionInWorldOntoPlaneAlongGravity(adaptedXaxis, canonicalTerrain).normalized(); + ASSERT_TRUE(projectedDesiredXaxis.isApprox(projectedAdaptedXaxis)); + } +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/CMakeLists.txt new file mode 100644 index 000000000..b74047744 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/CMakeLists.txt @@ -0,0 +1,122 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_anymal_loopshaping_mpc) + +## Find catkin macros and libraries +find_package(catkin REQUIRED COMPONENTS + roslib + ocs2_anymal_mpc + ocs2_quadruped_loopshaping_interface +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + roslib + ocs2_anymal_mpc + ocs2_quadruped_loopshaping_interface + DEPENDS +) + +########### +## Build ## +########### + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/AnymalLoopshapingInterface.cpp +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +add_executable(${PROJECT_NAME}_mpc_node + src/AnymalLoopshapingMpcNode.cpp +) +target_link_libraries(${PROJECT_NAME}_mpc_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +add_executable(${PROJECT_NAME}_dummy_mrt_node + src/AnymalLoopshapingDummyMrt.cpp +) +target_link_libraries(${PROJECT_NAME}_dummy_mrt_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +add_executable(${PROJECT_NAME}_perceptive_demo + src/PerceptiveMpcDemo.cpp + ) +target_link_libraries(${PROJECT_NAME}_perceptive_demo + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ) + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if (cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_mpc_node ${PROJECT_NAME}_dummy_mrt_node + SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include + CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include + CF_WERROR + ) +endif (cmake_clang_tools_FOUND) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(TARGETS ${PROJECT_NAME}_mpc_node ${PROJECT_NAME}_dummy_mrt_node ${PROJECT_NAME}_perceptive_demo + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY config launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +# Build unit tests +catkin_add_gtest(${PROJECT_NAME}_test + test/testProblemFormulation.cpp + test/testMotionTracking.cpp + test/testSensitivity.cpp +) +target_link_libraries(${PROJECT_NAME}_test + ${PROJECT_NAME} + ${catkin_LIBRARIES} + gtest_main +) \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/frame_declaration.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/frame_declaration.info new file mode 100644 index 000000000..73d1222e5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/frame_declaration.info @@ -0,0 +1,64 @@ +root base + +left_front { + root LF_HAA + tip LF_FOOT + joints { + [0] LF_HAA + [1] LF_HFE + [2] LF_KFE + } +} + +right_front { + root RF_HAA + tip RF_FOOT + joints { + [0] RF_HAA + [1] RF_HFE + [2] RF_KFE + } +} + +left_hind { + root LH_HAA + tip LH_FOOT + joints { + [0] LH_HAA + [1] LH_HFE + [2] LH_KFE + } +} + +right_hind { + root RH_HAA + tip RH_FOOT + joints { + [0] RH_HAA + [1] RH_HFE + [2] RH_KFE + } +} + +collisions { + collisionSpheres { + [0] "LF_KFE, 0.08" + [1] "RF_KFE, 0.08" + [2] "LH_KFE, 0.08" + [3] "RH_KFE, 0.08" + } + collisionOffsets { + (0,0) -0.055 + (0,1) 0.0 + (0,2) 0.0 + (1,0) -0.055 + (1,1) 0.0 + (1,2) 0.0 + (2,0) -0.055 + (2,1) 0.0 + (2,2) 0.0 + (3,0) -0.055 + (3,1) 0.0 + (3,2) 0.0 + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/loopshaping.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/loopshaping.info new file mode 100644 index 000000000..3aa376bd0 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/loopshaping.info @@ -0,0 +1,37 @@ +s_inv_filter +{ + numFilters 2; + + Filter0; Filter for forces + { + numRepeats 12; + numPoles 1; + numZeros 1; + scaling 4; + zeros + { + (0) 0.0; + } + poles + { + (0) -100.0; + } + } + + Filter1; Filter for joint velocities + { + numRepeats 12; + numPoles 1; + numZeros 1; + scaling 3; + zeros + { + (0) 0.0; + } + poles + { + (0) -50.0; + } + } +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/multiple_shooting.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/multiple_shooting.info new file mode 100644 index 000000000..f64bcd2cf --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/multiple_shooting.info @@ -0,0 +1,21 @@ +multiple_shooting +{ + dt 0.015 + alpha_min 1e-2 ; = 7 tries before terminating + sqpIteration 1 + deltaTol 1e-4 + g_max 1e-2 + g_min 1e-5 + inequalityConstraintMu 0.1 + inequalityConstraintDelta 5.0 + projectStateInputEqualityConstraints true + printSolverStatistics true + printSolverStatus false + printLinesearch false + enableLogging true + logSize 50000 + useFeedbackPolicy true + integratorType RK2 + nThreads 4 + threadPriority 50 +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/task.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/task.info new file mode 100644 index 000000000..8acca7a05 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/c_series/task.info @@ -0,0 +1,271 @@ +model_settings +{ + algorithm SQP + recompileLibraries false + robotName c_series + + analyticalInverseKinematics true + + frictionCoefficient 0.5 + gripperForce -25.0 ; [N] negative gripper force -> minimum force in normal direction + muFrictionCone 0.1 + deltaFrictionCone 5.0 + + muFootPlacement 0.1 ; magnitude scaling + deltaFootPlacement 0.005 ; [m] distance from constraint boundary where the barrier becomes quadratic. + + muSdf 2.5 + deltaSdf 0.005 + + muJointsPosition 0.1 + deltaJointsPosition 0.01 + muJointsVelocity 0.1 + deltaJointsVelocity 0.1 + muJointsTorque 1.0 + deltaJointsTorque 1.0 + + joint_lower_limits + { + (0,0) -0.72 ; LF_HAA + (1,0) -3.14 ; LF_HFE + (2,0) -2.70 ; LF_KFE + (3,0) -0.49 ; RF_HAA + (4,0) -3.14 ; RF_HFE + (5,0) -2.70 ; RF_KFE + (6,0) -0.72 ; LH_HAA + (7,0) -3.14 ; LH_HFE + (8,0) 0.00 ; LH_KFE + (9,0) -0.49 ; RH_HAA + (10,0) -3.14 ; RH_HFE + (11,0) 0.00 ; RH_KFE + } + + joint_upper_limits + { + (0,0) 0.49 ; LF_HAA + (1,0) 3.14 ; LF_HFE + (2,0) -0.00 ; LF_KFE + (3,0) 0.72 ; RF_HAA + (4,0) 3.14 ; RF_HFE + (5,0) -0.00 ; RF_KFE + (6,0) 0.49 ; LH_HAA + (7,0) 3.14 ; LH_HFE + (8,0) 2.70 ; LH_KFE + (9,0) 0.72 ; RH_HAA + (10,0) 3.14 ; RH_HFE + (11,0) 2.70 ; RH_KFE + } + + joint_velocity_limits + { + (0,0) 7.0 ; LF_HAA + (1,0) 7.0 ; LF_HFE + (2,0) 7.0 ; LF_KFE + (3,0) 7.0 ; RF_HAA + (4,0) 7.0 ; RF_HFE + (5,0) 7.0 ; RF_KFE + (6,0) 7.0 ; LH_HAA + (7,0) 7.0 ; LH_HFE + (8,0) 7.0 ; LH_KFE + (9,0) 7.0 ; RH_HAA + (10,0) 7.0 ; RH_HFE + (11,0) 7.0 ; RH_KFE + } + + joint_torque_limits + { + (0,0) 80.0 ; LF_HAA + (1,0) 80.0 ; LF_HFE + (2,0) 80.0 ; LF_KFE + (3,0) 80.0 ; RF_HAA + (4,0) 80.0 ; RF_HFE + (5,0) 80.0 ; RF_KFE + (6,0) 80.0 ; LH_HAA + (7,0) 80.0 ; LH_HFE + (8,0) 80.0 ; LH_KFE + (9,0) 80.0 ; RH_HAA + (10,0) 80.0 ; RH_HFE + (11,0) 80.0 ; RH_KFE + } + + swing_trajectory_settings + { + liftOffVelocity 0.2 + touchDownVelocity -0.4 + swingHeight 0.08 + errorGain 20.0 + swingTimeScale 0.15 + sdfMidswingMargin 0.04 + terrainMargin 0.04 + previousFootholdFactor 0.2 + previousFootholdDeadzone 0.025 + previousFootholdTimeDeadzone 0.30 + referenceExtensionAfterHorizon 1.0 + swingTrajectoryFromReference 0 + } +} + +terrainPlane +{ + position + { + x 0.0; + y 0.0; + z 0.0; + } + orientation + { + roll 0.0; + pitch 0.0; + yaw 0.0; + } +} + +defaultModeSequenceTemplate +{ + modeSequence + { + [0] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 1.0 + } +} + +; DDP settings +ddp +{ + algorithm SLQ + + nThreads 4 + threadPriority 50 + + maxNumIterations 1 + minRelCost 1e-1 + constraintTolerance 5e-3 + + displayInfo false + displayShortSummary false + checkNumericalStability false + debugPrintRollout false + + AbsTolODE 1e-5 + RelTolODE 1e-3 + maxNumStepsPerSecond 10000 + timeStep 0.015 + backwardPassIntegratorType ODE45 + + constraintPenaltyInitialValue 20.0 + constraintPenaltyIncreaseRate 2.0 + + preComputeRiccatiTerms true + + useFeedbackPolicy true + + strategy LINE_SEARCH + lineSearch + { + minStepLength 1e-4 + maxStepLength 1.0 + hessianCorrectionStrategy DIAGONAL_SHIFT + hessianCorrectionMultiple 1e-5 + } +} + +; Rollout settings +rollout +{ + AbsTolODE 1e-5 + RelTolODE 1e-3 + timeStep 0.015 + integratorType ODE45 + maxNumStepsPerSecond 10000 + checkNumericalStability false +} + +mpc +{ + timeHorizon 1.0 + solutionTimeWindow -1 ; [s] + coldStart false + + debugPrint false + + mpcDesiredFrequency 20 ; [Hz] + mrtDesiredFrequency 400 ; [Hz] +} + +; initial state +initialRobotState +{ + ; orientation + (0,0) 0.0 ; x + (1,0) 0.0 ; y + (2,0) 0.0 ; z + + ; position + (3,0) 0.0 ; x + (4,0) 0.0 ; y + (5,0) 0.57 ; z + + ; angular velocity + (6,0) 0.0 ; x + (7,0) 0.0 ; y + (8,0) 0.0 ; z + + ; translational velocity + (9,0) 0.0 ; x + (10,0) 0.0 ; y + (11,0) 0.0 ; z + + ; joint state + (12,0) -0.25 ; LF_HAA + (13,0) 0.60 ; LF_HFE + (14,0) -0.85 ; LF_KFE + (15,0) 0.25 ; RF_HAA + (16,0) 0.60 ; RF_HFE + (17,0) -0.85 ; RF_KFE + (18,0) -0.25 ; LH_HAA + (19,0) -0.60 ; LH_HFE + (20,0) 0.85 ; LH_KFE + (21,0) 0.25 ; RH_HAA + (22,0) -0.60 ; RH_HFE + (23,0) 0.85 ; RH_KFE +} + +tracking_cost_weights +{ + ; Base + roll 100.0; + pitch 300.0; + yaw 300.0; + base_position_x 1000.0; + base_position_y 1000.0; + base_position_z 1500.0; + base_angular_vel_x 10.0; + base_angular_vel_y 30.0; + base_angular_vel_z 30.0; + base_linear_vel_x 15.0; + base_linear_vel_y 15.0; + base_linear_vel_z 30.0; + + ; Per leg + joint_position_HAA 2.0; + joint_position_HFE 2.0; + joint_position_KFE 1.0; + foot_position_x 30.0; + foot_position_y 30.0; + foot_position_z 30.0; + joint_velocity_HAA 0.02; + joint_velocity_HFE 0.02; + joint_velocity_KFE 0.01; + foot_velocity_x 15.0; + foot_velocity_y 15.0; + foot_velocity_z 15.0; + contact_force_x 0.001; + contact_force_y 0.001; + contact_force_z 0.001; +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/rviz/demo_config.rviz b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/rviz/demo_config.rviz new file mode 100644 index 000000000..9a17623d9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/config/rviz/demo_config.rviz @@ -0,0 +1,975 @@ +Panels: + - Class: rviz/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /Grid1/Offset1 + - /Terrain1/FilteredMap1 + Splitter Ratio: 0.5038759708404541 + Tree Height: 727 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + - /CoGTrajectory1 + - /video_top1 + - /video_side1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 0.10000000149011612 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: false + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: world + Value: false + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + LF_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link Tree Style: Links in Alphabetic Order + RF_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_inertia: + Alpha: 1 + Show Axes: false + Show Trail: false + battery: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + body_top: + Alpha: 1 + Show Axes: false + Show Trail: false + bottom_shell: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_front_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_front_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_left_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_left_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_rear_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_rear_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_right_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_right_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + docking_hatch_cover: + Alpha: 1 + Show Axes: false + Show Trail: false + face_front: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + face_rear: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_handle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + handle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hatch: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + interface_hatch: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lidar: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + perception_head_cage: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + remote: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + top_shell: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_front_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_front_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + wide_angle_camera_rear_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_rear_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: "ANYmal " + Robot Description: /ocs2_anymal_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Group + Displays: + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredBaseTrajectory + Name: Base Position Trajectory + Namespaces: + "": true + Queue Size: 1 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredVelTrajectory + Name: Base Velocity Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredAngVelTrajectory + Name: Base Angular Velocity Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose Trajectory + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/desiredPoseTrajectory + Unreliable: false + Value: true + - Class: rviz/Group + Displays: + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/LF + Name: LF + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/RF + Name: RF + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/LH + Name: LH + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/RH + Name: RH + Namespaces: + {} + Queue Size: 1 + Value: true + Enabled: false + Name: Feet Position Trajectories + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/LF + Name: LF + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/RF + Name: RF + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/LH + Name: LH + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/RH + Name: RH + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: false + Name: Feet Velocity Trajectories + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/LF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/LH + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/RF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/RH + Unreliable: false + Value: true + Enabled: true + Name: Feet Pose Trajectories + Enabled: true + Name: Desired Trajectory + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose Trajectory + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/optimizedPoseTrajectory + Unreliable: false + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /ocs2_anymal/optimizedStateTrajectory + Name: State Trajectory + Namespaces: + Base Trajectory: true + EE Trajectories: true + Future footholds: true + Queue Size: 1 + Value: true + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/LF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/LH + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/RF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/RH + Unreliable: false + Value: true + Enabled: false + Name: Feet Pose Trajectories + Enabled: true + Name: Optimized Trajectory + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.10000000149011612 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/currentPose + Unreliable: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /ocs2_anymal/currentState + Name: State + Namespaces: + Center of Pressure: true + EE Forces: true + EE Positions: true + Support Polygon: true + Queue Size: 1 + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.10000000149011612 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Feet Poses + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/currentFeetPoses + Unreliable: false + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /ocs2_anymal/localTerrain + Name: LocalTerrain + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/currentCollisionSpheres + Name: Collisions + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Name: Current + - Class: rviz/Group + Displays: + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Signed distance + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.03999999910593033 + Style: Flat Squares + Topic: /signed_distance_field + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Class: grid_map_rviz_plugin/GridMap + Color: 200; 200; 200 + Color Layer: plane_classification + Color Transformer: "" + ColorMap: default + Enabled: true + Grid Cell Decimation: 1 + Grid Line Thickness: 0.10000000149011612 + Height Layer: elevation_before_postprocess + Height Transformer: GridMapLayer + History Length: 1 + Invert ColorMap: false + Max Color: 255; 255; 255 + Max Intensity: 10 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: FilteredMap + Show Grid Lines: true + Topic: /filtered_map + Unreliable: false + Use ColorMap: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /boundaries + Name: Boundaries + Namespaces: + "": true + Queue Size: 100 + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Class: grid_map_rviz_plugin/GridMap + Color: 200; 200; 200 + Color Layer: elevation + Color Transformer: GridMapLayer + ColorMap: default + Enabled: false + Grid Cell Decimation: 1 + Grid Line Thickness: 0.10000000149011612 + Height Layer: elevation + Height Transformer: GridMapLayer + History Length: 1 + Invert ColorMap: false + Max Color: 255; 255; 255 + Max Intensity: 10 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: ElevationMap + Show Grid Lines: true + Topic: /elevation_map + Unreliable: false + Use ColorMap: true + Value: false + Enabled: true + Name: Terrain + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 5.270549297332764 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 3.331205368041992 + Y: 1.1847355365753174 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.044797856360673904 + Target Frame: + Yaw: 1.556549310684204 + Saved: + - Angle: 3.140000104904175 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: CoGTrajectory + Near Clip Distance: 0.009999999776482582 + Scale: 582.8400268554688 + Target Frame: + X: 0.16045600175857544 + Y: 0.09311659634113312 + - Angle: 6.260000228881836 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: video_top + Near Clip Distance: 0.009999999776482582 + Scale: 266.7760009765625 + Target Frame: + X: 2.279409885406494 + Y: -0.7245129942893982 + - Class: rviz/Orbit + Distance: 3.5650899410247803 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 4.226150035858154 + Y: -1.1256200075149536 + Z: 0.17035800218582153 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: video_side + Near Clip Distance: 0.009999999776482582 + Pitch: 0.434798002243042 + Target Frame: + Yaw: 5.150000095367432 + - Class: rviz/Orbit + Distance: 1.7256799936294556 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0.09568200260400772 + Y: -0.16040100157260895 + Z: -0.31398600339889526 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: fixed_to_hyq + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3497979938983917 + Target Frame: base_link + Yaw: 5.114999771118164 +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001640000039efc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000039e000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012f00000432fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004300000432000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bf0000003efc0100000002fb0000000800540069006d00650000000000000003bf000004f300fffffffb0000000800540069006d00650100000000000004500000000000000000000005ce0000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1848 + X: 2632 + Y: 27 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/demo_terrain.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/demo_terrain.png new file mode 100644 index 000000000..a54c4bbef Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/demo_terrain.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/gaps.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/gaps.png new file mode 100644 index 000000000..cb81336ac Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/gaps.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/hurdles.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/hurdles.png new file mode 100644 index 000000000..1f551d83d Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/hurdles.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/side_gap.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/side_gap.png new file mode 100644 index 000000000..6df6beaee Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/side_gap.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/step.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/step.png new file mode 100644 index 000000000..811936745 Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/step.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/stepping_stones.png b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/stepping_stones.png new file mode 100644 index 000000000..25b3ba5c8 Binary files /dev/null and b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/data/stepping_stones.png differ diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/include/ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/include/ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h new file mode 100644 index 000000000..7da19e1bb --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/include/ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h @@ -0,0 +1,23 @@ +// +// Created by rgrandia on 13.02.20. +// + +#pragma once + +#include +#include + +namespace anymal { + +std::unique_ptr getAnymalLoopshapingInterface(const std::string& urdf, + const std::string& configFolder); + +std::unique_ptr getAnymalLoopshapingInterface( + const std::string& urdf, switched_model::QuadrupedInterface::Settings settings, const FrameDeclaration& frameDeclaration, + std::shared_ptr loopshapingDefinition); + +std::string getConfigFolderLoopshaping(const std::string& configName); + +std::string getTaskFilePathLoopshaping(const std::string& configName); + +} // end of namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/anymal_c.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/anymal_c.launch new file mode 100644 index 000000000..d5ebaca18 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/anymal_c.launch @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/camel.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/camel.launch new file mode 100644 index 000000000..f94593a6f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/camel.launch @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/mpc.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/mpc.launch new file mode 100644 index 000000000..aadfb6f32 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/mpc.launch @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/perceptive_mpc_demo.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/perceptive_mpc_demo.launch new file mode 100644 index 000000000..3dc7e6ca2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/launch/perceptive_mpc_demo.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/package.xml new file mode 100644 index 000000000..0a8730417 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/package.xml @@ -0,0 +1,16 @@ + + + ocs2_anymal_loopshaping_mpc + 0.0.0 + ocs2_anymal_loopshaping_mpc + + ruben + TODO + + catkin + + roslib + ocs2_anymal_mpc + ocs2_quadruped_loopshaping_interface + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingDummyMrt.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingDummyMrt.cpp new file mode 100644 index 000000000..f784a4895 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingDummyMrt.cpp @@ -0,0 +1,32 @@ +// +// Created by rgrandia on 13.02.20. +// + +#include +#include +#include + +#include "ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h" + +int main(int argc, char* argv[]) { + std::vector programArgs{}; + ::ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() < 3) { + throw std::runtime_error("No robot name and config folder specified. Aborting."); + } + const std::string descriptionName(programArgs[1]); + const std::string configName(programArgs[2]); + + // Initialize ros node + ros::init(argc, argv, "anymal_loopshaping_mrt"); + ros::NodeHandle nodeHandle; + + std::string urdfString; + nodeHandle.getParam(descriptionName, urdfString); + + auto anymalInterface = anymal::getAnymalLoopshapingInterface(urdfString, anymal::getConfigFolderLoopshaping(configName)); + const auto mpcSettings = ocs2::mpc::loadSettings(anymal::getTaskFilePathLoopshaping(configName)); + quadrupedLoopshapingDummyNode(nodeHandle, *anymalInterface, mpcSettings.mrtDesiredFrequency_, mpcSettings.mpcDesiredFrequency_); + + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingInterface.cpp new file mode 100644 index 000000000..eb72a91f1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingInterface.cpp @@ -0,0 +1,39 @@ +// +// Created by rgrandia on 13.02.20. +// + +#include "ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h" + +#include + +#include + +namespace anymal { + +std::unique_ptr getAnymalLoopshapingInterface(const std::string& urdf, + const std::string& configFolder) { + return getAnymalLoopshapingInterface(urdf, switched_model::loadQuadrupedSettings(configFolder + "/task.info"), + frameDeclarationFromFile(configFolder + "/frame_declaration.info"), + ocs2::loopshaping_property_tree::load(configFolder + "/loopshaping.info")); +} + +std::unique_ptr getAnymalLoopshapingInterface( + const std::string& urdf, switched_model::QuadrupedInterface::Settings settings, const FrameDeclaration& frameDeclaration, + std::shared_ptr loopshapingDefinition) { + auto quadrupedInterface = getAnymalInterface(urdf, std::move(settings), frameDeclaration); + loopshapingDefinition->costMatrix() = quadrupedInterface->nominalCostApproximation().dfduu; + loopshapingDefinition->print(); + + return std::unique_ptr( + new switched_model_loopshaping::QuadrupedLoopshapingInterface(std::move(quadrupedInterface), std::move(loopshapingDefinition))); +} + +std::string getConfigFolderLoopshaping(const std::string& configName) { + return ros::package::getPath("ocs2_anymal_loopshaping_mpc") + "/config/" + configName; +} + +std::string getTaskFilePathLoopshaping(const std::string& configName) { + return getConfigFolderLoopshaping(configName) + "/task.info"; +} + +} // end of namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingMpcNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingMpcNode.cpp new file mode 100644 index 000000000..c16cce2be --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/AnymalLoopshapingMpcNode.cpp @@ -0,0 +1,49 @@ +// +// Created by rgrandia on 13.02.20. +// + +#include + +#include +#include +#include +#include + +#include "ocs2_anymal_loopshaping_mpc/AnymalLoopshapingInterface.h" + +int main(int argc, char* argv[]) { + std::vector programArgs{}; + ::ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() < 3) { + throw std::runtime_error("No robot name and config folder specified. Aborting."); + } + const std::string descriptionName(programArgs[1]); + const std::string configName(programArgs[2]); + + // Initialize ros node + ros::init(argc, argv, "anymal_loopshaping_mpc"); + ros::NodeHandle nodeHandle; + + std::string urdfString; + nodeHandle.getParam(descriptionName, urdfString); + + auto anymalInterface = anymal::getAnymalLoopshapingInterface(urdfString, anymal::getConfigFolderLoopshaping(configName)); + const auto mpcSettings = ocs2::mpc::loadSettings(anymal::getTaskFilePathLoopshaping(configName)); + + switch (anymalInterface->modelSettings().algorithm_) { + case switched_model::Algorithm::DDP: { + const auto ddpSettings = ocs2::ddp::loadSettings(anymal::getTaskFilePathLoopshaping(configName)); + auto mpcPtr = getDdpMpc(*anymalInterface, mpcSettings, ddpSettings); + quadrupedLoopshapingMpcNode(nodeHandle, *anymalInterface, std::move(mpcPtr)); + break; + } + case switched_model::Algorithm::SQP: { + const auto sqpSettings = ocs2::sqp::loadSettings(anymal::getConfigFolderLoopshaping(configName) + "/multiple_shooting.info"); + auto mpcPtr = getSqpMpc(*anymalInterface, mpcSettings, sqpSettings); + quadrupedLoopshapingMpcNode(nodeHandle, *anymalInterface, std::move(mpcPtr)); + break; + } + } + + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/PerceptiveMpcDemo.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/PerceptiveMpcDemo.cpp new file mode 100644 index 000000000..64c3ac33e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/src/PerceptiveMpcDemo.cpp @@ -0,0 +1,363 @@ +// +// Created by rgrandia on 31.03.22. +// + +#include +#include + +#include + +// Plane segmentation +#include +#include +#include +#include + +// ocs2_dev +#include +#include +#include + +// ocs2_anymal +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace switched_model; + +int main(int argc, char* argv[]) { + const std::string path(__FILE__); + const std::string ocs2_anymal = path.substr(0, path.find_last_of("/")) + "/../../"; + const std::string taskFolder = ocs2_anymal + "ocs2_anymal_loopshaping_mpc/config/"; + const std::string terrainFolder = ocs2_anymal + "ocs2_anymal_loopshaping_mpc/data/"; + + const bool use_ros = false; + + std::string urdfString = getUrdfString(anymal::AnymalModel::Camel); + std::string configName = "c_series"; + const std::string robotName = "anymal"; + + ros::init(argc, argv, "anymal_perceptive_mpc_demo"); + ros::NodeHandle nodeHandle; + + ros::param::get("ocs2_anymal_description", urdfString); + nodeHandle.getParam("/config_name", configName); + + convex_plane_decomposition::PlaneDecompositionPipeline::Config perceptionConfig; + perceptionConfig.preprocessingParameters = + convex_plane_decomposition::loadPreprocessingParameters(nodeHandle, "/ocs2_anymal_loopshaping_mpc_perceptive_demo/preprocessing/"); + perceptionConfig.contourExtractionParameters = convex_plane_decomposition::loadContourExtractionParameters( + nodeHandle, "/ocs2_anymal_loopshaping_mpc_perceptive_demo/contour_extraction/"); + perceptionConfig.ransacPlaneExtractorParameters = convex_plane_decomposition::loadRansacPlaneExtractorParameters( + nodeHandle, "/ocs2_anymal_loopshaping_mpc_perceptive_demo/ransac_plane_refinement/"); + perceptionConfig.slidingWindowPlaneExtractorParameters = convex_plane_decomposition::loadSlidingWindowPlaneExtractorParameters( + nodeHandle, "/ocs2_anymal_loopshaping_mpc_perceptive_demo/sliding_window_plane_extractor/"); + perceptionConfig.postprocessingParameters = + convex_plane_decomposition::loadPostprocessingParameters(nodeHandle, "/ocs2_anymal_loopshaping_mpc_perceptive_demo/postprocessing/"); + + auto anymalInterface = anymal::getAnymalLoopshapingInterface(urdfString, taskFolder + configName); + const ocs2::vector_t initSystemState = anymalInterface->getInitialState().head(switched_model::STATE_DIM); + + // ====== Scenario settings ======== + ocs2::scalar_t forwardVelocity{0.0}; + nodeHandle.getParam("/forward_velocity", forwardVelocity); + ocs2::scalar_t gaitDuration{0.8}; + ocs2::scalar_t forwardDistance{3.0}; + + ocs2::scalar_t initTime = 0.0; + ocs2::scalar_t stanceTime = 1.0; + int numGaitCycles = std::ceil((forwardDistance / forwardVelocity) / gaitDuration); + ocs2::scalar_t walkTime = numGaitCycles * gaitDuration; + ocs2::scalar_t finalTime = walkTime + 2 * stanceTime; + ocs2::scalar_t f_mpc = 100; // hz + + // Load a map + const std::string elevationLayer{"elevation"}; + const std::string frameId{"world"}; + std::string terrainFile{""}; + nodeHandle.getParam("/terrain_name", terrainFile); + double heightScale{1.0}; + nodeHandle.getParam("/terrain_scale", heightScale); + auto gridMap = convex_plane_decomposition::loadGridmapFromImage(terrainFolder + "/" + terrainFile, elevationLayer, frameId, + perceptionConfig.preprocessingParameters.resolution, heightScale); + gridMap.get(elevationLayer).array() -= gridMap.atPosition(elevationLayer, {0., 0.}); + + // Gait + using MN = switched_model::ModeNumber; + switched_model::Gait stance; + stance.duration = stanceTime; + stance.eventPhases = {}; + stance.modeSequence = {MN::STANCE}; + + switched_model::Gait gait; + gait.duration = gaitDuration; + gait.eventPhases = {0.5}; + gait.modeSequence = {MN::LF_RH, MN::RF_LH}; + + GaitSchedule::GaitSequence gaitSequence{stance}; + for (int i = 0; i < numGaitCycles; ++i) { + gaitSequence.push_back(gait); + } + gaitSequence.push_back(stance); + + // Reference trajectory + bool adaptReferenceToTerrain = true; + nodeHandle.getParam("/adaptReferenceToTerrain", adaptReferenceToTerrain); + + const double dtRef = 0.1; + const BaseReferenceHorizon commandHorizon{dtRef, size_t(walkTime / dtRef) + 1}; + BaseReferenceCommand command; + command.baseHeight = getPositionInOrigin(getBasePose(initSystemState)).z(); + command.yawRate = 0.0; + command.headingVelocity = forwardVelocity; + command.lateralVelocity = 0.0; + + // ====== Run the perception pipeline ======== + convex_plane_decomposition::PlaneDecompositionPipeline planeDecompositionPipeline(perceptionConfig); + planeDecompositionPipeline.update(grid_map::GridMap(gridMap), elevationLayer); + auto& planarTerrain = planeDecompositionPipeline.getPlanarTerrain(); + auto terrainModel = std::unique_ptr(new SegmentedPlanesTerrainModel(planarTerrain)); + + // Read min-max from elevation map + const float heightMargin = 0.5; // Create SDF till this amount above and below the map. + const auto& elevationData = gridMap.get(elevationLayer); + const float minValue = elevationData.minCoeffOfFinites() - heightMargin; + const float maxValue = elevationData.maxCoeffOfFinites() + heightMargin; + terrainModel->createSignedDistanceBetween({-1e30, -1e30, minValue}, {1e30, 1e30, maxValue}); // will project XY range to map limits + + // ====== Generate reference trajectory ======== + const auto& baseToHipInBase = anymalInterface->getKinematicModel().baseToLegRootInBaseFrame(0); + const double nominalStanceWidthInHeading = 2.0 * (std::abs(baseToHipInBase.x()) + 0.15); + const double nominalStanceWidthLateral = 2.0 * (std::abs(baseToHipInBase.y()) + 0.10); + + BaseReferenceState initialBaseState{stanceTime, getPositionInOrigin(getBasePose(initSystemState)), + getOrientation(getBasePose(initSystemState))}; + + BaseReferenceTrajectory terrainAdaptedBaseReference; + if (adaptReferenceToTerrain) { + terrainAdaptedBaseReference = generateExtrapolatedBaseReference(commandHorizon, initialBaseState, command, planarTerrain.gridMap, + nominalStanceWidthInHeading, nominalStanceWidthLateral); + } else { + terrainAdaptedBaseReference = generateExtrapolatedBaseReference(commandHorizon, initialBaseState, command, TerrainPlane()); + } + + ocs2::TargetTrajectories targetTrajectories; + targetTrajectories.timeTrajectory.push_back(initTime); + targetTrajectories.timeTrajectory.push_back(stanceTime); + targetTrajectories.stateTrajectory.push_back(initSystemState); + targetTrajectories.stateTrajectory.push_back(initSystemState); + targetTrajectories.inputTrajectory.push_back(vector_t::Zero(INPUT_DIM)); + targetTrajectories.inputTrajectory.push_back(vector_t::Zero(INPUT_DIM)); + for (int k = 0; k < terrainAdaptedBaseReference.time.size(); ++k) { + targetTrajectories.timeTrajectory.push_back(terrainAdaptedBaseReference.time[k]); + + const auto R_WtoB = rotationMatrixOriginToBase(terrainAdaptedBaseReference.eulerXyz[k]); + + Eigen::VectorXd costReference(switched_model::STATE_DIM); + costReference << terrainAdaptedBaseReference.eulerXyz[k], terrainAdaptedBaseReference.positionInWorld[k], + R_WtoB * terrainAdaptedBaseReference.angularVelocityInWorld[k], R_WtoB * terrainAdaptedBaseReference.linearVelocityInWorld[k], + getJointPositions(initSystemState); + targetTrajectories.stateTrajectory.push_back(std::move(costReference)); + targetTrajectories.inputTrajectory.push_back(vector_t::Zero(INPUT_DIM)); + } + targetTrajectories.timeTrajectory.push_back(stanceTime + walkTime); + targetTrajectories.timeTrajectory.push_back(finalTime); + targetTrajectories.stateTrajectory.push_back(targetTrajectories.stateTrajectory.back()); + targetTrajectories.stateTrajectory.push_back(targetTrajectories.stateTrajectory.back()); + targetTrajectories.inputTrajectory.push_back(vector_t::Zero(INPUT_DIM)); + targetTrajectories.inputTrajectory.push_back(vector_t::Zero(INPUT_DIM)); + + // ====== Set the scenario to the correct interfaces ======== + auto referenceManager = anymalInterface->getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr(); + + // Register the terrain model + referenceManager->getTerrainModel().reset(std::move(terrainModel)); + + // Register the gait + referenceManager->getGaitSchedule()->setGaitSequenceAtTime(gaitSequence, initTime); + + // Register the target trajectory + referenceManager->setTargetTrajectories(targetTrajectories); + + // ====== Create MPC solver ======== + const auto mpcSettings = ocs2::mpc::loadSettings(taskFolder + configName + "/task.info"); + + std::unique_ptr mpcPtr; + const auto sqpSettings = ocs2::sqp::loadSettings(taskFolder + configName + "/multiple_shooting.info"); + switch (anymalInterface->modelSettings().algorithm_) { + case switched_model::Algorithm::DDP: { + const auto ddpSettings = ocs2::ddp::loadSettings(taskFolder + configName + "/task.info"); + mpcPtr = getDdpMpc(*anymalInterface, mpcSettings, ddpSettings); + break; + } + case switched_model::Algorithm::SQP: { + mpcPtr = getSqpMpc(*anymalInterface, mpcSettings, sqpSettings); + break; + } + } + ocs2::MPC_MRT_Interface mpcInterface(*mpcPtr); + + std::unique_ptr rollout(anymalInterface->getRollout().clone()); + + // ====== Execute the scenario ======== + ocs2::SystemObservation observation; + observation.time = initTime; + observation.state = anymalInterface->getInitialState(); + observation.input.setZero(switched_model_loopshaping::INPUT_DIM); + + // Wait for the first policy + mpcInterface.setCurrentObservation(observation); + while (!mpcInterface.initialPolicyReceived()) { + mpcInterface.advanceMpc(); + } + + // run MPC till final time + ocs2::PrimalSolution closedLoopSolution; + std::vector performances; + while (observation.time < finalTime) { + std::cout << "t: " << observation.time << "\n"; + try { + // run MPC at current observation + mpcInterface.setCurrentObservation(observation); + mpcInterface.advanceMpc(); + mpcInterface.updatePolicy(); + + performances.push_back(mpcInterface.getPerformanceIndices()); + + // Evaluate the optimized solution - change to optimal controller + ocs2::vector_t tmp; + mpcInterface.evaluatePolicy(observation.time, observation.state, tmp, observation.input, observation.mode); + observation.input = ocs2::LinearInterpolation::interpolate(observation.time, mpcInterface.getPolicy().timeTrajectory_, + mpcInterface.getPolicy().inputTrajectory_); + + closedLoopSolution.timeTrajectory_.push_back(observation.time); + closedLoopSolution.stateTrajectory_.push_back(observation.state); + closedLoopSolution.inputTrajectory_.push_back(observation.input); + if (closedLoopSolution.modeSchedule_.modeSequence.empty()) { + closedLoopSolution.modeSchedule_.modeSequence.push_back(observation.mode); + } else if (closedLoopSolution.modeSchedule_.modeSequence.back() != observation.mode) { + closedLoopSolution.modeSchedule_.modeSequence.push_back(observation.mode); + closedLoopSolution.modeSchedule_.eventTimes.push_back(observation.time - 0.5 / f_mpc); + } + + // perform a rollout + scalar_array_t timeTrajectory; + size_array_t postEventIndicesStock; + vector_array_t stateTrajectory, inputTrajectory; + const scalar_t finalTime = observation.time + 1.0 / f_mpc; + auto modeschedule = mpcInterface.getPolicy().modeSchedule_; + rollout->run(observation.time, observation.state, finalTime, mpcInterface.getPolicy().controllerPtr_.get(), modeschedule, + timeTrajectory, postEventIndicesStock, stateTrajectory, inputTrajectory); + + observation.time = finalTime; + observation.state = stateTrajectory.back(); + observation.input.setZero(switched_model_loopshaping::INPUT_DIM); // reset + } catch (std::exception& e) { + std::cout << "MPC failed\n"; + std::cout << e.what() << "\n"; + break; + } + } + const auto closedLoopSystemSolution = + ocs2::loopshapingToSystemPrimalSolution(closedLoopSolution, *anymalInterface->getLoopshapingDefinition()); + + // ====== Print result ========== + const auto totalCost = std::accumulate(performances.cbegin(), performances.cend(), 0.0, + [](double v, const ocs2::PerformanceIndex& p) { return v + p.cost; }); + const auto totalDynamics = + std::accumulate(performances.cbegin(), performances.cend(), 0.0, + [](double v, const ocs2::PerformanceIndex& p) { return v + std::sqrt(p.dynamicsViolationSSE); }); + const auto maxDynamics = std::sqrt(std::max_element(performances.cbegin(), performances.cend(), + [](const ocs2::PerformanceIndex& lhs, const ocs2::PerformanceIndex& rhs) { + return lhs.dynamicsViolationSSE < rhs.dynamicsViolationSSE; + }) + ->dynamicsViolationSSE); + const auto totalEquality = + std::accumulate(performances.cbegin(), performances.cend(), 0.0, + [](double v, const ocs2::PerformanceIndex& p) { return v + std::sqrt(p.equalityConstraintsSSE); }); + const auto maxEquality = std::sqrt(std::max_element(performances.cbegin(), performances.cend(), + [](const ocs2::PerformanceIndex& lhs, const ocs2::PerformanceIndex& rhs) { + return lhs.equalityConstraintsSSE < rhs.equalityConstraintsSSE; + }) + ->equalityConstraintsSSE); + + double achievedWalkTime = observation.time - stanceTime; + std::cout << "Speed: " << forwardVelocity << "\n"; + std::cout << "Scale: " << heightScale << "\n"; + std::cout << "Completed: " << std::min(1.0, (achievedWalkTime / walkTime)) * 100.0 << "\n"; + std::cout << "average Cost: " << totalCost / performances.size() << "\n"; + std::cout << "average Dynamics constr: " << totalDynamics / performances.size() << "\n"; + std::cout << "max Dynamics constr: " << maxDynamics << "\n"; + std::cout << "average Equality constr: " << totalEquality / performances.size() << "\n"; + std::cout << "max Equality constr: " << maxEquality << "\n"; + + // ====== Visualize ========== + QuadrupedVisualizer visualizer(anymalInterface->getKinematicModel(), anymalInterface->getJointNames(), anymalInterface->getBaseName(), + nodeHandle); + ros::Publisher elevationmapPublisher = nodeHandle.advertise("elevation_map", 1); + ros::Publisher filteredmapPublisher = nodeHandle.advertise("filtered_map", 1); + ros::Publisher boundaryPublisher = nodeHandle.advertise("boundaries", 1); + ros::Publisher insetPublisher = nodeHandle.advertise("insets", 1); + ros::Publisher distanceFieldPublisher = nodeHandle.advertise("signed_distance_field", 1, true); + + // Create pointcloud for visualization (terrain model ownership is now with the swing planner + const auto* sdfPtr = + dynamic_cast(referenceManager->getSwingTrajectoryPlanner().getSignedDistanceField()); + sensor_msgs::PointCloud2 pointCloud2Msg; + if (sdfPtr != nullptr) { + const auto& sdf = sdfPtr->asGridmapSdf(); + grid_map::GridMapRosConverter::toPointCloud(sdf, pointCloud2Msg, 1, [](float val) { return val <= 0.0F; }); + } + + // Grid map + grid_map_msgs::GridMap filteredMapMessage; + grid_map::GridMapRosConverter::toMessage(planarTerrain.gridMap, filteredMapMessage); + grid_map_msgs::GridMap elevationMapMessage; + grid_map::GridMapRosConverter::toMessage(gridMap, elevationMapMessage); + + // Segmentation + const double lineWidth = 0.005; // [m] RViz marker size + auto boundaries = convertBoundariesToRosMarkers(planarTerrain.planarRegions, planarTerrain.gridMap.getFrameId(), + planarTerrain.gridMap.getTimestamp(), lineWidth); + auto boundaryInsets = convertInsetsToRosMarkers(planarTerrain.planarRegions, planarTerrain.gridMap.getFrameId(), + planarTerrain.gridMap.getTimestamp(), lineWidth); + + while (ros::ok()) { + visualizer.publishOptimizedStateTrajectory(ros::Time::now(), closedLoopSystemSolution.timeTrajectory_, + closedLoopSystemSolution.stateTrajectory_, closedLoopSystemSolution.modeSchedule_); + visualizer.publishDesiredTrajectory(ros::Time::now(), targetTrajectories); + + filteredmapPublisher.publish(filteredMapMessage); + elevationmapPublisher.publish(elevationMapMessage); + boundaryPublisher.publish(boundaries); + insetPublisher.publish(boundaryInsets); + + if (sdfPtr != nullptr) { + distanceFieldPublisher.publish(pointCloud2Msg); + } + + // Visualize the individual execution + double speed = 1.0; + for (size_t k = 0; k < closedLoopSystemSolution.timeTrajectory_.size() - 1; k++) { + double frameDuration = speed * (closedLoopSystemSolution.timeTrajectory_[k + 1] - closedLoopSystemSolution.timeTrajectory_[k]); + double publishDuration = ocs2::timedExecutionInSeconds([&]() { + ocs2::SystemObservation observation; + observation.time = closedLoopSystemSolution.timeTrajectory_[k]; + observation.state = closedLoopSystemSolution.stateTrajectory_[k]; + observation.input = closedLoopSystemSolution.inputTrajectory_[k]; + observation.mode = closedLoopSystemSolution.modeSchedule_.modeAtTime(observation.time); + visualizer.publishObservation(ros::Time::now(), observation); + }); + if (frameDuration > publishDuration) { + ros::WallDuration(frameDuration - publishDuration).sleep(); + } + } + + ros::WallDuration(1.0).sleep(); + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testMotionTracking.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testMotionTracking.cpp new file mode 100644 index 000000000..52bb8129e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testMotionTracking.cpp @@ -0,0 +1,171 @@ +// +// Created by rgrandia on 02.12.21. +// + +#include + +#include +#include +#include +#include + +#include +#include +#include + +class TestAnymalLoopshapingMpc : public ::testing::Test { + public: + TestAnymalLoopshapingMpc() { + const auto model = anymal::AnymalModel::Camel; + const std::string configName("c_series"); + const std::string path(__FILE__); + const std::string dir = path.substr(0, path.find_last_of("/")); + const std::string configFolder = dir + "/../config/" + configName; + + // Get interface + anymalInterface = anymal::getAnymalLoopshapingInterface(anymal::getUrdfString(model), configFolder); + + problem = anymalInterface->getOptimalControlProblem(); + + // Cost desired + ocs2::scalar_t initTime = 0.0; + ocs2::scalar_t finalTime = 1.0; + const ocs2::vector_t systemState = anymalInterface->getInitialState().head(switched_model::STATE_DIM); + const ocs2::vector_t state = anymalInterface->getInitialState(); + const ocs2::vector_t input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + targetTrajectories = ocs2::TargetTrajectories{{initTime}, {systemState}, {input}}; + problem.targetTrajectoriesPtr = &targetTrajectories; + + const auto mpcSettings = ocs2::mpc::loadSettings(configFolder + "/task.info"); + const auto sqpSettings = ocs2::sqp::loadSettings(configFolder + "/multiple_shooting.info"); + mpcPtr = switched_model_loopshaping::getSqpMpc(*anymalInterface, mpcSettings, sqpSettings); + + // Initialize + anymalInterface->getReferenceManagerPtr()->preSolverRun(initTime, finalTime, state); + } + + std::unique_ptr mpcPtr; + std::unique_ptr anymalInterface; + ocs2::OptimalControlProblem problem; + ocs2::TargetTrajectories targetTrajectories; +}; + +TEST_F(TestAnymalLoopshapingMpc, trot_in_place) { + ocs2::scalar_t initTime = 0.0; + ocs2::scalar_t finalTime = 1.0; + ocs2::scalar_t f_mpc = 20; // hz + + ocs2::MPC_MRT_Interface mpcInterface(*mpcPtr); + + ocs2::SystemObservation observation; + observation.time = initTime; + observation.state = anymalInterface->getInitialState(); + observation.input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + mpcInterface.setCurrentObservation(observation); + + switched_model::Gait gait; + gait.duration = 1.0; + gait.eventPhases = {0.45, 0.5, 0.95}; + using MN = switched_model::ModeNumber; + gait.modeSequence = {MN::LF_RH, MN::STANCE, MN::RF_LH, MN::STANCE}; + anymalInterface->getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getGaitSchedule()->setGaitAtTime(gait, initTime); + + // Wait for the first policy + mpcInterface.setCurrentObservation(observation); + while (!mpcInterface.initialPolicyReceived()) { + mpcInterface.advanceMpc(); + } + + // run MPC for N iterations + auto time = initTime; + while (time < finalTime) { + std::cerr << time << "\n"; + + // run MPC + mpcInterface.advanceMpc(); + time += 1.0 / f_mpc; + + size_t mode; + ocs2::vector_t optimalState, optimalInput; + + mpcInterface.updatePolicy(); + std::cerr << mpcInterface.getPerformanceIndices() << "\n"; + mpcInterface.evaluatePolicy(time, ocs2::vector_t::Zero(switched_model_loopshaping::STATE_DIM), optimalState, optimalInput, mode); + + // use optimal state for the next observation: + observation.time = time; + observation.state = optimalState; + observation.input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + mpcInterface.setCurrentObservation(observation); + } + + // Check if base tracking was achieved + const switched_model::vector3_t finalBasePosition = observation.state.segment<3>(3); + const switched_model::vector3_t finalRefBasePosition = + ocs2::LinearInterpolation::interpolate(finalTime, targetTrajectories.timeTrajectory, targetTrajectories.stateTrajectory) + .segment<3>(3); + ASSERT_LT((finalBasePosition - finalRefBasePosition).norm(), 0.1); +} + +TEST_F(TestAnymalLoopshapingMpc, motion_tracking) { + const std::string path(__FILE__); + const std::string dir = path.substr(0, path.find_last_of("/")); + const std::string motionFilesPath = dir + "/../../ocs2_anymal_commands/config/motions/"; + const std::string motionName = "demo_motion"; + + const auto csvData = switched_model::readCsv(motionFilesPath + motionName + ".txt"); + const auto motionData = switched_model::readMotion(csvData); + + ocs2::scalar_t initTime = motionData.first.timeTrajectory.front(); + ocs2::scalar_t finalTime = motionData.first.timeTrajectory.back(); + ocs2::scalar_t f_mpc = 100; // hz + + ocs2::MPC_MRT_Interface mpcInterface(*mpcPtr); + + ocs2::SystemObservation observation; + observation.time = initTime; + observation.state = anymalInterface->getInitialState(); + observation.state.head(switched_model::STATE_DIM) = + ocs2::LinearInterpolation::interpolate(initTime, motionData.first.timeTrajectory, motionData.first.stateTrajectory); + observation.input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + mpcInterface.setCurrentObservation(observation); + + mpcInterface.getReferenceManager().setTargetTrajectories(motionData.first); + anymalInterface->getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getGaitSchedule()->setGaitAtTime(motionData.second, + initTime); + + // Wait for the first policy + mpcInterface.setCurrentObservation(observation); + while (!mpcInterface.initialPolicyReceived()) { + mpcInterface.advanceMpc(); + } + + // run MPC for N iterations + auto time = initTime; + while (time < finalTime) { + std::cerr << time << "\n"; + + // run MPC + mpcInterface.advanceMpc(); + time += 1.0 / f_mpc; + + size_t mode; + ocs2::vector_t optimalState, optimalInput; + + mpcInterface.updatePolicy(); + std::cerr << mpcInterface.getPerformanceIndices() << "\n"; + mpcInterface.evaluatePolicy(time, ocs2::vector_t::Zero(switched_model_loopshaping::STATE_DIM), optimalState, optimalInput, mode); + + // use optimal state for the next observation: + observation.time = time; + observation.state = optimalState; + observation.input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + mpcInterface.setCurrentObservation(observation); + } + + // Check if base tracking was achieved + const switched_model::vector3_t finalBasePosition = observation.state.segment<3>(3); + const switched_model::vector3_t finalRefBasePosition = + ocs2::LinearInterpolation::interpolate(finalTime, motionData.first.timeTrajectory, motionData.first.stateTrajectory).segment<3>(3); + ASSERT_LT((finalBasePosition - finalRefBasePosition).norm(), 0.25); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testProblemFormulation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testProblemFormulation.cpp new file mode 100644 index 000000000..438053e07 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testProblemFormulation.cpp @@ -0,0 +1,142 @@ +// +// Created by rgrandia on 15.03.21. +// + +#include + +#include + +#include +#include + +class TestAnymalLoopshapingModel : public ::testing::Test { + public: + TestAnymalLoopshapingModel() { + const auto model = anymal::AnymalModel::Camel; + const std::string configName("c_series"); + const std::string path(__FILE__); + const std::string dir = path.substr(0, path.find_last_of("/")); + const std::string configFolder = dir + "/../config/" + configName; + + // Get interface + anymalInterface = anymal::getAnymalLoopshapingInterface(anymal::getUrdfString(model), configFolder); + + problem = anymalInterface->getOptimalControlProblem(); + + // Cost desired + ocs2::scalar_t initTime = 0.0; + ocs2::scalar_t finalTime = 1.0; + const ocs2::vector_t systemState = anymalInterface->getInitialState().head(switched_model::STATE_DIM); + const ocs2::vector_t state = anymalInterface->getInitialState(); + const ocs2::vector_t input = ocs2::vector_t::Zero(switched_model::INPUT_DIM); + targetTrajectories = ocs2::TargetTrajectories{{initTime}, {systemState}, {input}}; + problem.targetTrajectoriesPtr = &targetTrajectories; + + // Initialize + anymalInterface->getReferenceManagerPtr()->preSolverRun(initTime, finalTime, state); + } + + std::unique_ptr anymalInterface; + ocs2::OptimalControlProblem problem; + ocs2::TargetTrajectories targetTrajectories; +}; + +TEST_F(TestAnymalLoopshapingModel, all) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.dynamicsPtr->linearApproximation(t, x, u); + } + timer.endTimer(); + std::cout << "Dynamics " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.equalityConstraintPtr->getLinearApproximation(t, x, u, *problem.preComputationPtr); + } + timer.endTimer(); + std::cout << "Constraints state-input " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + ocs2::approximateCost(problem, t, x, u); + } + timer.endTimer(); + std::cout << "Cost " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalLoopshapingModel, dynamics) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.dynamicsPtr->linearApproximation(t, x, u); + } + timer.endTimer(); + std::cout << "Dynamics " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalLoopshapingModel, precomputation) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.preComputationPtr->request(request, t, x, u); + } + timer.endTimer(); + std::cout << "Precomputation " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalLoopshapingModel, constraints_eq) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.equalityConstraintPtr->getLinearApproximation(t, x, u, *problem.preComputationPtr); + } + timer.endTimer(); + std::cout << "Constraints equality " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalLoopshapingModel, cost) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + ocs2::approximateCost(problem, t, x, u); + } + timer.endTimer(); + std::cout << "Cost " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testSensitivity.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testSensitivity.cpp new file mode 100644 index 000000000..cf4aff2c7 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_loopshaping_mpc/test/testSensitivity.cpp @@ -0,0 +1,232 @@ +// +// Created by rgrandia on 02.12.21. +// + +#include + +#include +#include +#include +#include + +#include +#include +#include + +TEST(TestAnymalLoopshapingMotionTracking, testSensitivity) { + const auto model = anymal::AnymalModel::Camel; + const std::string configName("c_series"); + const std::string motionName = "walking"; + const std::string path(__FILE__); + const std::string dir = path.substr(0, path.find_last_of("/")); + const std::string configFolder = dir + "/../config/" + configName; + const std::string motionFilesPath = dir + "/../../ocs2_anymal_commands/config/motions/"; + + const auto csvData = switched_model::readCsv(motionFilesPath + motionName + ".txt"); + const auto motionData = switched_model::readMotion(csvData, 0.05); + const auto mpcSettings = ocs2::mpc::loadSettings(configFolder + "/task.info"); + const auto sqpSettings = ocs2::sqp::loadSettings(configFolder + "/multiple_shooting.info"); + auto quadrupedSettings = switched_model::loadQuadrupedSettings(configFolder + "/task.info"); + const auto frameDecl = anymal::frameDeclarationFromFile(configFolder + "/frame_declaration.info"); + auto loopshapingDefinition = ocs2::loopshaping_property_tree::load(configFolder + "/loopshaping.info"); + + ocs2::scalar_t initTime = motionData.first.timeTrajectory.front(); + ocs2::scalar_t finalTime = motionData.first.timeTrajectory.back(); + ocs2::scalar_t f_mpc = 100; // hz + + auto pertubation = [](switched_model::vector3_t& weights, switched_model::scalar_t scale) { + weights += scale * weights.cwiseProduct(switched_model::vector3_t::Random()); + }; + + switched_model::scalar_t initPertubation = 0.0; + pertubation(quadrupedSettings.trackingWeights_.eulerXYZ, initPertubation); + pertubation(quadrupedSettings.trackingWeights_.comPosition, initPertubation); + pertubation(quadrupedSettings.trackingWeights_.comAngularVelocity, initPertubation); + pertubation(quadrupedSettings.trackingWeights_.comLinearVelocity, initPertubation); + for (size_t leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + pertubation(quadrupedSettings.trackingWeights_.jointPosition[leg], initPertubation); + pertubation(quadrupedSettings.trackingWeights_.footPosition[leg], initPertubation); + pertubation(quadrupedSettings.trackingWeights_.jointVelocity[leg], initPertubation); + pertubation(quadrupedSettings.trackingWeights_.footVelocity[leg], initPertubation); + pertubation(quadrupedSettings.trackingWeights_.contactForce[leg], initPertubation); + } + + // switched_model::vector_t fixedPertubation(72); + // fixedPertubation << -0.2637, 0.5929, 0.2175, 1.4130, 0.6363, 0.0801, 0.2722, 0.1047, 0.3784, -2.8149, 0.0432, 0.8614, 0.3006, -0.5959, + // 0.0476, -0.0116, 0.0550, 0.3269, 0.1988, -0.7673, -0.2221, 0.1776, -0.0030, -0.2777, -0.7968, -0.0891, -0.0418, -0.3855, 0.3938, + // 0.0153, 0.2518, 0.4857, 0.0738, -0.1309, 0.6136, -0.2562, 0.0193, 0.0311, 0.0934, -0.0002, 0.1328, -0.0119, -0.1210, -0.0163, + // -0.0230, 0.0221, -0.0103, -0.0037, -0.4827, -0.4070, 0.2466, 0.0855, 0.4314, 0.0678, 1.1602, 0.0036, -0.1345, -0.3520, 0.4472, + // -0.3660, -0.6880, 0.5961, 0.5977, -0.2640, 0.3858, -0.4024, -0.7835, -0.4275, 0.8153, -0.8321, 0.0672, 0.1678; + // fixedPertubation.array() += 1.0; + // fixedPertubation.setOnes(72); + // int idx = 0; + // quadrupedSettings.trackingWeights_.eulerXYZ.x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.eulerXYZ.y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.eulerXYZ.z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comPosition.x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comPosition.y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comPosition.z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comAngularVelocity.x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comAngularVelocity.y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comAngularVelocity.z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comLinearVelocity.x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comLinearVelocity.y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.comLinearVelocity.z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[0].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[0].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[0].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[1].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[1].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[1].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[2].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[2].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[2].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[3].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[3].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointPosition[3].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[0].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[0].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[0].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[1].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[1].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[1].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[2].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[2].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[2].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[3].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[3].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footPosition[3].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[0].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[0].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[0].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[1].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[1].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[1].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[2].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[2].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[2].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[3].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[3].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.jointVelocity[3].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[0].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[0].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[0].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[1].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[1].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[1].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[2].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[2].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[2].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[3].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[3].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.footVelocity[3].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[0].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[0].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[0].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[1].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[1].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[1].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[2].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[2].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[2].z() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[3].x() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[3].y() *= fixedPertubation[idx++]; + // quadrupedSettings.trackingWeights_.contactForce[3].z() *= fixedPertubation[idx++]; + + int Nruns = 1; + int dataSize = switched_model::STATE_DIM + switched_model::INPUT_DIM + 3 * 4 + switched_model::NUM_CONTACT_POINTS * 3 * 5; + ocs2::matrix_t results(dataSize, Nruns); + for (int run = 0; run < Nruns; ++run) { + auto quadrupedSettingsCopy = quadrupedSettings; + + switched_model::scalar_t runningPertubation = 0.0; + pertubation(quadrupedSettingsCopy.trackingWeights_.eulerXYZ, runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.comPosition, runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.comAngularVelocity, runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.comLinearVelocity, runningPertubation); + for (size_t leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + pertubation(quadrupedSettingsCopy.trackingWeights_.jointPosition[leg], runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.footPosition[leg], runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.jointVelocity[leg], runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.footVelocity[leg], runningPertubation); + pertubation(quadrupedSettingsCopy.trackingWeights_.contactForce[leg], runningPertubation); + } + + // Get interface + auto anymalInterface = anymal::getAnymalLoopshapingInterface(anymal::getUrdfString(model), quadrupedSettingsCopy, frameDecl, loopshapingDefinition); + + auto mpcPtr = switched_model_loopshaping::getSqpMpc(*anymalInterface, mpcSettings, sqpSettings); + ocs2::MPC_MRT_Interface mpcInterface(*mpcPtr); + + ocs2::SystemObservation observation; + observation.time = initTime; + observation.state = anymalInterface->getInitialState(); + observation.state.head(switched_model::STATE_DIM) = + ocs2::LinearInterpolation::interpolate(initTime, motionData.first.timeTrajectory, motionData.first.stateTrajectory); + observation.input = ocs2::vector_t::Zero(switched_model_loopshaping::INPUT_DIM); + mpcInterface.setCurrentObservation(observation); + + mpcInterface.getReferenceManager().setTargetTrajectories(motionData.first); + anymalInterface->getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getGaitSchedule()->setGaitAtTime(motionData.second, + initTime); + + // Wait for the first policy + mpcInterface.setCurrentObservation(observation); + while (!mpcInterface.initialPolicyReceived()) { + mpcInterface.advanceMpc(); + } + + // run MPC for N iterations + std::cout << run << "\n"; + auto time = initTime; + switched_model::comkino_state_t stateSSE = switched_model::comkino_state_t::Zero(); + switched_model::comkino_state_t inputSSE = switched_model::comkino_input_t::Zero(); + while (time < finalTime) { + // run MPC + mpcInterface.advanceMpc(); + time += 1.0 / f_mpc; + + size_t mode; + ocs2::vector_t optimalState, optimalInput; + + mpcInterface.updatePolicy(); + mpcInterface.evaluatePolicy(time, ocs2::vector_t::Zero(switched_model_loopshaping::STATE_DIM), optimalState, optimalInput, mode); + + // use optimal state for the next observation: + observation.time = time; + observation.state = optimalState; + observation.input = optimalInput; + mpcInterface.setCurrentObservation(observation); + + // Base tracking + const auto refState = ocs2::LinearInterpolation::interpolate(time, motionData.first.timeTrajectory, motionData.first.stateTrajectory); + const auto refInput = ocs2::LinearInterpolation::interpolate(time, motionData.first.timeTrajectory, motionData.first.inputTrajectory); + stateSSE += 1.0 / f_mpc * (observation.state.head() - refState).cwiseAbs2(); + inputSSE += 1.0 / f_mpc * (observation.input - refInput).cwiseAbs2(); + } + + stateSSE /= (finalTime - initTime); + stateSSE = stateSSE.cwiseSqrt(); + inputSSE /= (finalTime - initTime); + inputSSE = inputSSE.cwiseSqrt(); + + // Tracking performance vs. weights + ocs2::vector_t dataLine(dataSize); + dataLine << stateSSE, inputSSE, quadrupedSettingsCopy.trackingWeights_.eulerXYZ, quadrupedSettingsCopy.trackingWeights_.comPosition, + quadrupedSettingsCopy.trackingWeights_.comAngularVelocity, quadrupedSettingsCopy.trackingWeights_.comLinearVelocity, + quadrupedSettingsCopy.trackingWeights_.jointPosition[0], quadrupedSettingsCopy.trackingWeights_.jointPosition[1], + quadrupedSettingsCopy.trackingWeights_.jointPosition[2], quadrupedSettingsCopy.trackingWeights_.jointPosition[3], + quadrupedSettingsCopy.trackingWeights_.footPosition[0], quadrupedSettingsCopy.trackingWeights_.footPosition[1], + quadrupedSettingsCopy.trackingWeights_.footPosition[2], quadrupedSettingsCopy.trackingWeights_.footPosition[3], + quadrupedSettingsCopy.trackingWeights_.jointVelocity[0], quadrupedSettingsCopy.trackingWeights_.jointVelocity[1], + quadrupedSettingsCopy.trackingWeights_.jointVelocity[2], quadrupedSettingsCopy.trackingWeights_.jointVelocity[3], + quadrupedSettingsCopy.trackingWeights_.footVelocity[0], quadrupedSettingsCopy.trackingWeights_.footVelocity[1], + quadrupedSettingsCopy.trackingWeights_.footVelocity[2], quadrupedSettingsCopy.trackingWeights_.footVelocity[3], + quadrupedSettingsCopy.trackingWeights_.contactForce[0], quadrupedSettingsCopy.trackingWeights_.contactForce[1], + quadrupedSettingsCopy.trackingWeights_.contactForce[2], quadrupedSettingsCopy.trackingWeights_.contactForce[3]; + results.col(run) = dataLine; + } + + Eigen::IOFormat CommaFmt(Eigen::StreamPrecision, Eigen::DontAlignCols, ", ", "\n", "", "", "", ""); + std::cerr << results.transpose().format(CommaFmt); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/CMakeLists.txt new file mode 100644 index 000000000..ebaa1fa72 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/CMakeLists.txt @@ -0,0 +1,109 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_anymal_models) + +## Find catkin macros and libraries +find_package(catkin REQUIRED COMPONENTS + ocs2_switched_model_interface + ocs2_pinocchio_interface + ocs2_robotic_tools + ocs2_robotic_assets + roslib +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ocs2_switched_model_interface + ocs2_robotic_tools + ocs2_pinocchio_interface + roslib +# DEPENDS +) + +########### +## Build ## +########### + +# Resolve for the package path at compile time. +configure_file( + "${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}/package_path.h.in" + "${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}/package_path.h" @ONLY +) + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/AnymalModels.cpp + src/FrameDeclaration.cpp + src/QuadrupedPinocchioMapping.cpp + src/QuadrupedInverseKinematics.cpp + src/QuadrupedKinematics.cpp + src/QuadrupedCom.cpp +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + dl +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +# Build unit tests +catkin_add_gtest(${PROJECT_NAME}_switched_model_test + test/TestDynamicsHelpers.cpp +) +target_link_libraries(${PROJECT_NAME}_switched_model_test + ${PROJECT_NAME} + ${catkin_LIBRARIES} + gtest_main +) + +catkin_add_gtest(TestQuadrupedPinocchio + test/camel/AnymalCamelCom.cpp + test/camel/AnymalCamelKinematics.cpp + test/TestFrameDeclaration.cpp + test/TestInverseKinematics.cpp + test/TestQuadrupedPinocchioCom.cpp + test/TestQuadrupedPinocchioKinematics.cpp +) +target_link_libraries(TestQuadrupedPinocchio + ${PROJECT_NAME} + ${catkin_LIBRARIES} + gtest_main +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/config/visualize_urdf.rviz b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/config/visualize_urdf.rviz new file mode 100644 index 000000000..6ee6bb1fe --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/config/visualize_urdf.rviz @@ -0,0 +1,283 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /TF1 + Splitter Ratio: 0.5 + Tree Height: 549 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.5 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + body_bracket: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hip_bracket_f_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hip_bracket_f_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hip_bracket_h_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hip_bracket_h_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lowerleg_f_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lowerleg_f_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lowerleg_h_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lowerleg_h_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pelvis: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperleg_f_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperleg_f_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperleg_h_l: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperleg_h_r: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base: + Value: true + body_bracket: + Value: true + hip_bracket_f_l: + Value: true + hip_bracket_f_r: + Value: true + hip_bracket_h_l: + Value: true + hip_bracket_h_r: + Value: true + lowerleg_f_l: + Value: true + lowerleg_f_r: + Value: true + lowerleg_h_l: + Value: true + lowerleg_h_r: + Value: true + pelvis: + Value: true + torso: + Value: true + upperleg_f_l: + Value: true + upperleg_f_r: + Value: true + upperleg_h_l: + Value: true + upperleg_h_r: + Value: true + Marker Alpha: 1 + Marker Scale: 0.30000001192092896 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + base: + pelvis: + body_bracket: + torso: + hip_bracket_f_l: + upperleg_f_l: + lowerleg_f_l: + {} + hip_bracket_f_r: + upperleg_f_r: + lowerleg_f_r: + {} + hip_bracket_h_l: + upperleg_h_l: + lowerleg_h_l: + {} + hip_bracket_h_r: + upperleg_h_r: + lowerleg_h_r: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 211; 215; 207 + Default Light: true + Fixed Frame: base + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 1.0566951036453247 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.330398291349411 + Target Frame: + Yaw: 0.4453873336315155 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f30000003efc0100000002fb0000000800540069006d00650100000000000004f3000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000282000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1267 + X: 72 + Y: 27 \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/.gitignore b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/.gitignore new file mode 100644 index 000000000..2219a8a19 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/.gitignore @@ -0,0 +1,2 @@ +# Ignore generated file +package_path.h diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/AnymalModels.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/AnymalModels.h new file mode 100644 index 000000000..61b9b523f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/AnymalModels.h @@ -0,0 +1,39 @@ +// +// Created by rgrandia on 22.09.20. +// + +#pragma once + +#include +#include +#include + +#include "ocs2_anymal_models/FrameDeclaration.h" + +namespace anymal { + +enum class AnymalModel { Camel }; + +std::string toString(AnymalModel model); + +AnymalModel stringToAnymalModel(const std::string& name); + +std::string getUrdfPath(AnymalModel model); +std::string getUrdfString(AnymalModel model); + +std::unique_ptr getAnymalInverseKinematics(const FrameDeclaration& frameDeclaration, + const std::string& urdf); + +std::unique_ptr> getAnymalKinematics(const FrameDeclaration& frameDeclaration, + const std::string& urdf); + +std::unique_ptr> getAnymalKinematicsAd(const FrameDeclaration& frameDeclaration, + const std::string& urdf); + +std::unique_ptr> getAnymalComModel(const FrameDeclaration& frameDeclaration, + const std::string& urdf); + +std::unique_ptr> getAnymalComModelAd(const FrameDeclaration& frameDeclaration, + const std::string& urdf); + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/DynamicsHelpers.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/DynamicsHelpers.h new file mode 100644 index 000000000..ae7be93b2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/DynamicsHelpers.h @@ -0,0 +1,171 @@ +#pragma once + +#include + +namespace anymal { +/* + * Uses only upper triangular part of A + */ +template +switched_model::matrix3_s_t inv33sym(const switched_model::matrix3_s_t& A, SCALAR_T DinvMax = SCALAR_T(1e12)) { + // Analytical inverse of symmetrical 3x3 matrix + switched_model::matrix3_s_t Ainv; + Ainv(0, 0) = A(2, 2) * A(1, 1) - A(1, 2) * A(1, 2); + Ainv(0, 1) = A(0, 2) * A(1, 2) - A(2, 2) * A(0, 1); + Ainv(0, 2) = A(0, 1) * A(1, 2) - A(0, 2) * A(1, 1); + + Ainv(1, 1) = A(2, 2) * A(0, 0) - A(0, 2) * A(0, 2); + Ainv(1, 2) = A(0, 1) * A(0, 2) - A(0, 0) * A(1, 2); + + Ainv(2, 2) = A(0, 0) * A(1, 1) - A(0, 1) * A(0, 1); + + // Determinant + SCALAR_T D = A(0, 0) * Ainv(0, 0) + A(0, 1) * Ainv(0, 1) + A(0, 2) * Ainv(0, 2); + SCALAR_T Dinv = CppAD::CondExpGt(CppAD::abs(D), 1.0 / DinvMax, SCALAR_T(1.0) / D, DinvMax); + + // Scaling and copying to symmetric part. + Ainv(0, 0) = Ainv(0, 0) * Dinv; + Ainv(0, 1) = Ainv(0, 1) * Dinv; + Ainv(0, 2) = Ainv(0, 2) * Dinv; + + Ainv(1, 0) = Ainv(0, 1); + Ainv(1, 1) = Ainv(1, 1) * Dinv; + Ainv(1, 2) = Ainv(1, 2) * Dinv; + + Ainv(2, 0) = Ainv(0, 2); + Ainv(2, 1) = Ainv(1, 2); + Ainv(2, 2) = Ainv(2, 2) * Dinv; + return Ainv; +} + +/* + * Uses only upper triangular part of A + */ +template +switched_model::vector3_s_t solve33sym(const switched_model::matrix3_s_t& A, + const switched_model::vector3_s_t& b, SCALAR_T DinvMax = SCALAR_T(1e12)) { + // Analytical inverse of symmetrical 3x3 matrix, stored in a flat array + switched_model::vector6_s_t Ainv; + Ainv(0) = A(2, 2) * A(1, 1) - A(1, 2) * A(1, 2); + Ainv(1) = A(0, 2) * A(1, 2) - A(2, 2) * A(0, 1); + Ainv(2) = A(0, 1) * A(1, 2) - A(0, 2) * A(1, 1); + Ainv(3) = A(2, 2) * A(0, 0) - A(0, 2) * A(0, 2); + Ainv(4) = A(0, 1) * A(0, 2) - A(0, 0) * A(1, 2); + Ainv(5) = A(0, 0) * A(1, 1) - A(0, 1) * A(0, 1); + + // Determinant + SCALAR_T D = A(0, 0) * Ainv(0) + A(0, 1) * Ainv(1) + A(0, 2) * Ainv(2); + SCALAR_T Dinv = CppAD::CondExpGt(CppAD::abs(D), 1.0 / DinvMax, SCALAR_T(1.0) / D, DinvMax); + + switched_model::vector3_s_t c; + c(0) = Dinv * (Ainv(0) * b(0) + Ainv(1) * b(1) + Ainv(2) * b(2)); + c(1) = Dinv * (Ainv(1) * b(0) + Ainv(3) * b(1) + Ainv(4) * b(2)); + c(2) = Dinv * (Ainv(2) * b(0) + Ainv(4) * b(1) + Ainv(5) * b(2)); + return c; +} + +/** + * Solve c = inv(M) * b, where M is an inertia tensor with first linear and then angular components. + * + * i.e. M = [m * I_3x3, crossTerm'; + * crossTerm, Theta ] + * + * The implementation is compatible with auto-differentiation. + */ +template +switched_model::vector6_s_t inertiaTensorSolveLinearAngular(const switched_model::matrix6_s_t& M, + const switched_model::vector6_s_t& b, + SCALAR_T DinvMax = SCALAR_T(1e12)) { + /* + * Uses the schur-complement method plus the structure of the inertia tensor to efficiently construct the result of inv(M) * b + * + * M has the following structure: + * topLeft(3x3) = m * I_3x3 + * topRight(3x3) = m * [comVector]_x' + * bottomRight(3x3) = Theta = Theta_com + m * [comVector]_x * [comVector]_x' + */ + + // total mass + const SCALAR_T invm = SCALAR_T(1.0) / M(2, 2); + + // extract underlying vector for the crossterms s.t. M.upperRight = crossTerm' = [m * comVector]_x' + const switched_model::vector3_s_t scaledComVector{M(1, 5), M(2, 3), M(0, 4)}; // is actually m * comVector + const switched_model::vector3_s_t comVector = invm * scaledComVector; // store a version that is pre-multiplied by 1/m + + // prepare rhs for solve33sym, tmp = b.tail(3) - comVector x b.head(3) + switched_model::vector3_s_t tmp = b.template tail<3>() - comVector.template cross(b.template head<3>()); + + // prepare lhs for solve33sym, fill only upper triangular part + switched_model::matrix3_s_t centroidalInertia; // = theta_com = theta - 1/m * crossTerm * crossTerm' + const SCALAR_T v0v0 = comVector(0) * scaledComVector(0); + const SCALAR_T v1v1 = comVector(1) * scaledComVector(1); + const SCALAR_T v2v2 = comVector(2) * scaledComVector(2); + centroidalInertia(0, 0) = M(3, 3) - v1v1 - v2v2; + centroidalInertia(0, 1) = M(3, 4) + comVector(0) * scaledComVector(1); + centroidalInertia(0, 2) = M(3, 5) + comVector(0) * scaledComVector(2); + centroidalInertia(1, 1) = M(4, 4) - v0v0 - v2v2; + centroidalInertia(1, 2) = M(4, 5) + comVector(1) * scaledComVector(2); + centroidalInertia(2, 2) = M(5, 5) - v0v0 - v1v1; + + // Solve the linear system, only need to invert the 3x3 schur complement (= centroidalInertia) + switched_model::vector6_s_t c; + // angular acceleration + c.template tail<3>() = solve33sym(centroidalInertia, tmp, DinvMax); + // Linear acceleration + c.template head<3>() = invm * b.template head<3>() + comVector.template cross(c.template tail<3>()); + + return c; +} + +/** + * Solve c = inv(M) * b, where M is an inertia tensor with first angular, then linear components. + * + * i.e. M = [Theta, crossTerm; + * crossTerm', m * I_3x3 ] + * + * The implementation is compatible with auto-differentiation. + */ +template +switched_model::vector6_s_t inertiaTensorSolveAngularLinear(const switched_model::matrix6_s_t& M, + const switched_model::vector6_s_t& b, + SCALAR_T DinvMax = SCALAR_T(1e12)) { + /* + * Uses the schur complement method plus the structure of the interia tensor to efficiently construct the result of inv(M) * b + * + * M has the following structure: + * topLeft(3x3) = Theta = Theta_com + m * [comVector]_x * [comVector]_x' + * topRight(3x3) = m * [comVector]_x + * bottomRight(3x3) = m * I_3x3 + */ + + // total mass, bottom right block is m * I_3x3; + const SCALAR_T invm = SCALAR_T(1.0) / M(5, 5); + + // extract underlying vector for the crossterms s.t. M.upperRight = crossTerm = [m * comVector]_x + const switched_model::vector3_s_t scaledComVector{M(2, 4), M(0, 5), M(1, 3)}; // is actually m * comVector + const switched_model::vector3_s_t comVector = invm * scaledComVector; // store a version that is pre-multiplied by 1/m + + // prepare rhs for solve33sym, tmp = b.head(3) * crossTerm' * b.tail(3) + switched_model::vector3_s_t tmp = b.template head<3>() - comVector.template cross(b.template tail<3>()); + + // prepare lhs for solve33sym, fill only upper triangular part + switched_model::matrix3_s_t centroidalInertia; // = theta_com = theta - 1/m * crossTerm * crossTerm' + const SCALAR_T v0v0 = comVector(0) * scaledComVector(0); + const SCALAR_T v1v1 = comVector(1) * scaledComVector(1); + const SCALAR_T v2v2 = comVector(2) * scaledComVector(2); + centroidalInertia(0, 0) = M(0, 0) - v1v1 - v2v2; + centroidalInertia(0, 1) = M(0, 1) + comVector(0) * scaledComVector(1); + centroidalInertia(0, 2) = M(0, 2) + comVector(0) * scaledComVector(2); + centroidalInertia(1, 1) = M(1, 1) - v0v0 - v2v2; + centroidalInertia(1, 2) = M(1, 2) + comVector(1) * scaledComVector(2); + centroidalInertia(2, 2) = M(2, 2) - v0v0 - v1v1; + + // Solve the linear system, only need to invert the 3x3 schur complement (= centroidalInertia) + switched_model::vector6_s_t c; + c.template head<3>() = solve33sym(centroidalInertia, tmp, DinvMax); + c.template tail<3>() = invm * b.template tail<3>() + comVector.template cross(c.template head<3>()); + + return c; +} + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/FrameDeclaration.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/FrameDeclaration.h new file mode 100644 index 000000000..a50518442 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/FrameDeclaration.h @@ -0,0 +1,36 @@ +// +// Created by rgrandia on 27.04.22. +// + +#pragma once + +#include + +namespace anymal { + +struct CollisionDeclaration { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + std::string link; + switched_model::scalar_t radius; + switched_model::vector3_t offset; +}; + +struct LimbFrames { + std::string root; + std::string tip; + std::vector joints; +}; + +struct FrameDeclaration { + std::string root; + switched_model::feet_array_t legs; + std::vector collisions; +}; + +std::vector getJointNames(const FrameDeclaration& frameDeclaration); + +LimbFrames limbFramesFromFile(const std::string& file, const std::string& field); + +FrameDeclaration frameDeclarationFromFile(const std::string& file); + +} // namespace anymal \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedCom.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedCom.h new file mode 100644 index 000000000..347ba2131 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedCom.h @@ -0,0 +1,79 @@ +#pragma once + +#include + +#include + +#include "ocs2_anymal_models/QuadrupedPinocchioMapping.h" + +namespace anymal { +namespace tpl { + +template +class QuadrupedCom : public switched_model::ComModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + QuadrupedCom(const FrameDeclaration& frameDeclaration, const ocs2::PinocchioInterface& pinocchioInterface); + ~QuadrupedCom() = default; + + QuadrupedCom* clone() const override; + + SCALAR_T totalMass() const override { return totalMass_; } + + switched_model::vector3_s_t centerOfMassInBaseFrame(const switched_model::joint_coordinate_s_t& jointPositions) const; + + switched_model::vector3_s_t centerOfMassInWorldFrame(const switched_model::base_coordinate_s_t& basePose, + const switched_model::joint_coordinate_s_t& jointPositions) const; + + switched_model::base_coordinate_s_t calculateBaseLocalAccelerations( + const switched_model::base_coordinate_s_t& basePose, + const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::joint_coordinate_s_t& jointVelocities, + const switched_model::joint_coordinate_s_t& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) const override; + + private: + QuadrupedCom(const QuadrupedCom& rhs); + + Eigen::Matrix getPinnochioConfiguration( + const switched_model::base_coordinate_s_t& basePose, + const switched_model::joint_coordinate_s_t& jointPositions) const; + + Eigen::Matrix getPinnochioVelocity( + const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointVelocities) const; + + using PinocchioInterface_s_t = ocs2::PinocchioInterfaceTpl; + + template ::value, bool>::type = true> + PinocchioInterface_s_t castPinocchioInterface(const ocs2::PinocchioInterface& pinocchioInterface) { + return pinocchioInterface.toCppAd(); + } + + template ::value, bool>::type = true> + PinocchioInterface_s_t castPinocchioInterface(const ocs2::PinocchioInterface& pinocchioInterface) { + return pinocchioInterface; + } + + std::unique_ptr pinocchioInterfacePtr_; + QuadrupedPinocchioMapping pinocchioMapping_; + + SCALAR_T totalMass_; +}; + +} // namespace tpl + +ocs2::PinocchioInterface createQuadrupedPinocchioInterfaceFromUrdfString(const std::string& urdfString); + +using QuadrupedCom = tpl::QuadrupedCom; +using QuadrupedComAd = tpl::QuadrupedCom; + +} // namespace anymal + +/** + * Explicit instantiation, for instantiation additional types, include the implementation file instead of this one. + */ +extern template class anymal::tpl::QuadrupedCom; +extern template class anymal::tpl::QuadrupedCom; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedInverseKinematics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedInverseKinematics.h new file mode 100644 index 000000000..40c0742d9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedInverseKinematics.h @@ -0,0 +1,38 @@ +// +// Created by rgrandia on 02.08.22. +// + +#pragma once + +#include + +#include + +#include + +#include "ocs2_anymal_models/QuadrupedPinocchioMapping.h" + +namespace anymal { + +class QuadrupedInverseKinematics final : public switched_model::InverseKinematicsModelBase { + public: + QuadrupedInverseKinematics(const FrameDeclaration& frameDeclaration, const ocs2::PinocchioInterface& pinocchioInterface); + + ~QuadrupedInverseKinematics() override = default; + + QuadrupedInverseKinematics* clone() const override; + + switched_model::vector3_t getLimbJointPositionsFromPositionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::vector3_t& positionBaseToFootInBaseFrame) const override; + + switched_model::vector3_t getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame( + size_t footIndex, const switched_model::vector3_t& footVelocityRelativeToBaseInBaseFrame, + const joint_jacobian_block_t& jointJacobian, switched_model::scalar_t damping) const override; + + private: + QuadrupedInverseKinematics(const QuadrupedInverseKinematics& other) = default; + + switched_model::feet_array_t parameters_; +}; + +}; // namespace anymal \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedKinematics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedKinematics.h new file mode 100644 index 000000000..5d53b3c6a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedKinematics.h @@ -0,0 +1,84 @@ +#pragma once + +#include +#include +#include + +#include + +#include + +#include "ocs2_anymal_models/QuadrupedPinocchioMapping.h" + +namespace anymal { +namespace tpl { + +template +class QuadrupedKinematics final : public switched_model::KinematicsModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef switched_model::KinematicsModelBase BASE; + using typename BASE::CollisionSphere; + using typename BASE::joint_jacobian_block_t; + using typename BASE::joint_jacobian_t; + + QuadrupedKinematics(const FrameDeclaration& frameDeclaration, const ocs2::PinocchioInterface& pinocchioInterface); + ~QuadrupedKinematics() = default; + + QuadrupedKinematics* clone() const override; + + switched_model::vector3_s_t baseToLegRootInBaseFrame(size_t footIndex) const override; + + switched_model::vector3_s_t positionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + joint_jacobian_block_t baseToFootJacobianBlockInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + switched_model::matrix3_s_t footOrientationInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + switched_model::vector3_s_t footVelocityRelativeToBaseInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::joint_coordinate_s_t& jointVelocities) const override; + + std::vector collisionSpheresInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions) const override; + + private: + QuadrupedKinematics(const QuadrupedKinematics& rhs); + + using PinocchioInterface_s_t = ocs2::PinocchioInterfaceTpl; + + template ::value, bool>::type = true> + PinocchioInterface_s_t castPinocchioInterface(const ocs2::PinocchioInterface& pinocchioInterface) { + return pinocchioInterface.toCppAd(); + } + + template ::value, bool>::type = true> + PinocchioInterface_s_t castPinocchioInterface(const ocs2::PinocchioInterface& pinocchioInterface) { + return pinocchioInterface; + } + + switched_model::vector3_s_t relativeTranslationInBaseFrame(const switched_model::joint_coordinate_s_t& jointPositions, + std::size_t frame) const; + switched_model::matrix3_s_t relativeOrientationInBaseFrame(const switched_model::joint_coordinate_s_t& jointPositions, + std::size_t frame) const; + + std::unique_ptr pinocchioInterfacePtr_; + QuadrupedPinocchioMapping pinocchioMapping_; + switched_model::feet_array_t> baseToLegRootInBaseFrame_; +}; + +} // namespace tpl + +using QuadrupedKinematics = tpl::QuadrupedKinematics; +using QuadrupedKinematicsAd = tpl::QuadrupedKinematics; +} // namespace anymal + +/** + * Explicit instantiation, for instantiation additional types, include the implementation file instead of this one. + */ +extern template class anymal::tpl::QuadrupedKinematics; +extern template class anymal::tpl::QuadrupedKinematics; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedPinocchioMapping.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedPinocchioMapping.h new file mode 100644 index 000000000..8f21c4c17 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/QuadrupedPinocchioMapping.h @@ -0,0 +1,59 @@ +#pragma once + +#include + +#include + +#include + +namespace anymal { + +/** + * Used to map joint configuration space from OCS2 to Pinocchio. In OCS2, the feet order is {LF, RF, LH, RH}. But in Pinocchio, the feet + * order depends on the URDF. + */ +class QuadrupedPinocchioMapping { + public: + QuadrupedPinocchioMapping(const FrameDeclaration& frameDeclaration, const ocs2::PinocchioInterface& pinocchioInterface); + + switched_model::joint_coordinate_t getPinocchioJointVector(const switched_model::joint_coordinate_t& jointPositions) const; + + switched_model::joint_coordinate_ad_t getPinocchioJointVector(const switched_model::joint_coordinate_ad_t& jointPositions) const; + + size_t getPinocchioFootIndex(size_t ocs2FootIdx) const { return mapFeetOrderOcs2ToPinocchio_[ocs2FootIdx]; } + + size_t getFootFrameId(size_t ocs2FootIdx) const { return footFrameIds_[ocs2FootIdx]; } + + size_t getHipFrameId(size_t ocs2FootIdx) const { return hipFrameIds_[ocs2FootIdx]; } + + const std::vector& getCollisionLinkFrameIds() const { return collisionLinkFrameIds_; } + const std::vector& getCollisionDeclaration() const { return collisionDeclaration_; } + + const std::vector& getOcs2JointNames() const { return ocs2JointNames_; } + + const std::vector& getPinocchioJointNames() const { return pinocchioJointNames_; } + + static size_t getBodyId(const std::string& bodyName, const ocs2::PinocchioInterface& pinocchioInterface); + + private: + void extractPinocchioJointNames(const ocs2::PinocchioInterface& pinocchioInterface); + void extractFeetOrdering(const ocs2::PinocchioInterface& pinocchioInterface); + + // Frame Ids + switched_model::feet_array_t hipFrameIds_; + switched_model::feet_array_t footFrameIds_; + + // Collisions + std::vector collisionLinkFrameIds_; + std::vector collisionDeclaration_; + + // Feet ordering + switched_model::feet_array_t mapFeetOrderOcs2ToPinocchio_; + switched_model::feet_array_t mapFeetOrderPinocchioToOcs2_; + + // Frame names + std::vector ocs2JointNames_; + std::vector pinocchioJointNames_; +}; + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/package_path.h.in b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/package_path.h.in new file mode 100644 index 000000000..1006eaa29 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/include/ocs2_anymal_models/package_path.h.in @@ -0,0 +1,42 @@ +/****************************************************************************** +Copyright (c) 2021, Farbod Farshidian. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************/ + +#pragma once + +#include +#include + +namespace anymal { + +/** Gets the path to the package source directory. */ +inline std::string getPath() { + return "@PROJECT_SOURCE_DIR@"; +} + +} // namespace anymal \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/load_urdf.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/load_urdf.launch new file mode 100644 index 000000000..d1d420683 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/load_urdf.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/vizualize_urdf.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/vizualize_urdf.launch new file mode 100644 index 000000000..29784f3dc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/launch/vizualize_urdf.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/package.xml new file mode 100644 index 000000000..cdc7ac229 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/package.xml @@ -0,0 +1,21 @@ + + + ocs2_anymal_models + 0.0.1 + The ocs2_anymal_models package + + Farbod Farshidian + Jan Carius + Ruben Grandia + + TODO + + catkin + + ocs2_switched_model_interface + ocs2_pinocchio_interface + ocs2_robotic_assets + ocs2_robotic_tools + roslib + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/AnymalModels.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/AnymalModels.cpp new file mode 100644 index 000000000..3f4e6c493 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/AnymalModels.cpp @@ -0,0 +1,79 @@ +// +// Created by rgrandia on 22.09.20. +// + +#include + +#include + +#include + +#include +#include +#include + +#include + +namespace anymal { + +std::string toString(AnymalModel model) { + static const std::unordered_map map{{AnymalModel::Camel, "camel"}}; + return map.at(model); +} + +AnymalModel stringToAnymalModel(const std::string& name) { + static const std::unordered_map map{{"camel", AnymalModel::Camel}}; + return map.at(name); +} + +std::string getUrdfPath(AnymalModel model) { + switch (model) { + case AnymalModel::Camel: + return getPath() + "/urdf/anymal_camel_rsl.urdf"; + default: + throw std::runtime_error("[AnymalModels] no default urdf available"); + } +} + +std::string getUrdfString(AnymalModel model) { + const auto path = getUrdfPath(model); + std::ifstream stream(path.c_str()); + if (!stream) { + throw std::runtime_error("File " + path + " does not exist"); + } + + std::string xml_str((std::istreambuf_iterator(stream)), std::istreambuf_iterator()); + return xml_str; +} + +std::unique_ptr getAnymalInverseKinematics(const FrameDeclaration& frameDeclaration, + const std::string& urdf) { + return std::unique_ptr( + new QuadrupedInverseKinematics(frameDeclaration, ocs2::getPinocchioInterfaceFromUrdfString(urdf))); +} + +std::unique_ptr> getAnymalKinematics(const FrameDeclaration& frameDeclaration, + const std::string& urdf) { + return std::unique_ptr>( + new QuadrupedKinematics(frameDeclaration, ocs2::getPinocchioInterfaceFromUrdfString(urdf))); +} + +std::unique_ptr> getAnymalKinematicsAd(const FrameDeclaration& frameDeclaration, + const std::string& urdf) { + return std::unique_ptr>( + new QuadrupedKinematicsAd(frameDeclaration, ocs2::getPinocchioInterfaceFromUrdfString(urdf))); +} + +std::unique_ptr> getAnymalComModel(const FrameDeclaration& frameDeclaration, + const std::string& urdf) { + return std::unique_ptr>( + new QuadrupedCom(frameDeclaration, createQuadrupedPinocchioInterfaceFromUrdfString(urdf))); +} + +std::unique_ptr> getAnymalComModelAd(const FrameDeclaration& frameDeclaration, + const std::string& urdf) { + return std::unique_ptr>( + new QuadrupedComAd(frameDeclaration, createQuadrupedPinocchioInterfaceFromUrdfString(urdf))); +} + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/FrameDeclaration.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/FrameDeclaration.cpp new file mode 100644 index 000000000..0b097322c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/FrameDeclaration.cpp @@ -0,0 +1,54 @@ +// +// Created by rgrandia on 27.04.22. +// + +#include "ocs2_anymal_models/FrameDeclaration.h" + +#include +#include + +namespace anymal { + +std::vector getJointNames(const FrameDeclaration& frameDeclaration) { + std::vector jointNames; + for (const auto& leg : frameDeclaration.legs) { + jointNames.insert(jointNames.end(), leg.joints.begin(), leg.joints.end()); + } + return jointNames; +} + +LimbFrames limbFramesFromFile(const std::string& file, const std::string& field) { + LimbFrames frames; + ocs2::loadData::loadCppDataType(file, field + ".root", frames.root); + ocs2::loadData::loadCppDataType(file, field + ".tip", frames.tip); + ocs2::loadData::loadStdVector(file, field + ".joints", frames.joints, false); + return frames; +} + +FrameDeclaration frameDeclarationFromFile(const std::string& file) { + FrameDeclaration decl; + ocs2::loadData::loadCppDataType(file, "root", decl.root); + decl.legs[0] = limbFramesFromFile(file, "left_front"); + decl.legs[1] = limbFramesFromFile(file, "right_front"); + decl.legs[2] = limbFramesFromFile(file, "left_hind"); + decl.legs[3] = limbFramesFromFile(file, "right_hind"); + + std::vector> collisionSpheres; + ocs2::loadData::loadStdVectorOfPair(file, "collisions.collisionSpheres", collisionSpheres, false); + + ocs2::matrix_t offsets(collisionSpheres.size(), 3); + ocs2::loadData::loadEigenMatrix(file, "collisions.collisionOffsets", offsets); + + decl.collisions.reserve(collisionSpheres.size()); + for (int i = 0; i < collisionSpheres.size(); ++i) { + CollisionDeclaration collisionDeclaration; + collisionDeclaration.link = collisionSpheres[i].first; + collisionDeclaration.radius = collisionSpheres[i].second; + collisionDeclaration.offset = offsets.row(i).transpose(); + decl.collisions.push_back(std::move(collisionDeclaration)); + } + + return decl; +} + +} // namespace anymal \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedCom.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedCom.cpp new file mode 100644 index 000000000..91973c6fc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedCom.cpp @@ -0,0 +1,156 @@ +#include "ocs2_anymal_models/QuadrupedCom.h" +#include "ocs2_anymal_models/DynamicsHelpers.h" + +#include + +#include + +// Pinocchio +#include +#include + +#include +#include +#include + +namespace anymal { + +ocs2::PinocchioInterface createQuadrupedPinocchioInterfaceFromUrdfString(const std::string& urdfString) { + // add 6 DoF for the floating base + return ocs2::getPinocchioInterfaceFromUrdfString(urdfString, pinocchio::JointModelFreeFlyer()); +} + +namespace tpl { +template +QuadrupedCom::QuadrupedCom(const FrameDeclaration& frameDeclaration, const ocs2::PinocchioInterface& pinocchioInterface) + : pinocchioInterfacePtr_(new PinocchioInterface_s_t(castPinocchioInterface(pinocchioInterface))), + pinocchioMapping_(frameDeclaration, pinocchioInterface) { + const auto& model = pinocchioInterfacePtr_->getModel(); + totalMass_ = pinocchio::computeTotalMass(model); +} + +template +QuadrupedCom::QuadrupedCom(const QuadrupedCom& rhs) + : pinocchioInterfacePtr_(new PinocchioInterface_s_t(*rhs.pinocchioInterfacePtr_)), + pinocchioMapping_(rhs.pinocchioMapping_), + totalMass_(rhs.totalMass_) {} + +template +QuadrupedCom* QuadrupedCom::clone() const { + return new QuadrupedCom(*this); +} + +template +switched_model::vector3_s_t QuadrupedCom::centerOfMassInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions) const { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + const auto configuration = getPinnochioConfiguration(switched_model::base_coordinate_s_t::Zero(), jointPositions); + pinocchio::centerOfMass(model, data, configuration); + return data.com[1]; // CoM of the full robot in the free-flyer frame, i.e. base frame. +} + +template +switched_model::vector3_s_t QuadrupedCom::centerOfMassInWorldFrame( + const switched_model::base_coordinate_s_t& basePose, + const switched_model::joint_coordinate_s_t& jointPositions) const { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + const auto configuration = getPinnochioConfiguration(basePose, jointPositions); + return pinocchio::centerOfMass(model, data, configuration); +} + +template +switched_model::base_coordinate_s_t QuadrupedCom::calculateBaseLocalAccelerations( + const switched_model::base_coordinate_s_t& basePose, const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::joint_coordinate_s_t& jointVelocities, + const switched_model::joint_coordinate_s_t& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) const { + using vector_t = Eigen::Matrix; + + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + /** + * pinocchio state = [basePos(0-2) baseQuad(3-6) q(7-18)] + * + * basePos: Base position in Origin frame (3x1) + * baseQuad: (x,y,z,w) (4x1) + * q: Joint angles per leg [HAA, HFE, KFE] (3x1) [4x] + * + * pinocchio velocity = [v(0-2) w(3-5) qj(6-17)] + * + * v: Base linear velocity in Base Frame (3x1) + * w: Base angular velocity in Base Frame (3x1) + * qj: Joint velocities per leg [HAA, HFE, KFE] (3x1) + */ + const auto configuration = getPinnochioConfiguration(basePose, jointPositions); + const auto velocity = getPinnochioVelocity(baseLocalVelocities, jointVelocities); + + // Calculate joint space inertial matrix + pinocchio::crba(model, data, configuration); + + const vector_t dynamicBias = pinocchio::nonLinearEffects(model, data, configuration, velocity); + + switched_model::base_coordinate_s_t pinocchioBaseForces; + // Force + pinocchioBaseForces.template head<3>() = forcesOnBaseInBaseFrame.template tail<3>(); + // Wrench + pinocchioBaseForces.template tail<3>() = forcesOnBaseInBaseFrame.template head<3>(); + + switched_model::vector6_s_t baseForcesInBaseFrame = pinocchioBaseForces - dynamicBias.head(6); + baseForcesInBaseFrame.noalias() -= data.M.template block<6, 12>(0, 6) * pinocchioMapping_.getPinocchioJointVector(jointAccelerations); + + // M are symmetric but pinocchio only fills in the upper triangle. + switched_model::matrix6_s_t Mb = data.M.topLeftCorner(6, 6).template selfadjointView(); + vector_t baseAcceleration = inertiaTensorSolveLinearAngular(Mb, baseForcesInBaseFrame); + + vector_t ocs2baseAcceleration(6); + // Angular + ocs2baseAcceleration.template head<3>() = baseAcceleration.template tail<3>(); + // Linear + ocs2baseAcceleration.template tail<3>() = baseAcceleration.template head<3>(); + + return ocs2baseAcceleration; +} + +template +Eigen::Matrix QuadrupedCom::getPinnochioConfiguration( + const switched_model::base_coordinate_s_t& basePose, + const switched_model::joint_coordinate_s_t& jointPositions) const { + const auto& model = pinocchioInterfacePtr_->getModel(); + + Eigen::Matrix configuration(model.nq); + // basePost + configuration.template head<3>() = switched_model::getPositionInOrigin(basePose); + // baseQuad + const Eigen::Quaternion baseQuat = switched_model::quaternionBaseToOrigin(switched_model::getOrientation(basePose)); + configuration.template segment<4>(3) = baseQuat.coeffs(); + // JointsPos + configuration.template segment(7) = pinocchioMapping_.getPinocchioJointVector(jointPositions); + return configuration; +} + +template +Eigen::Matrix QuadrupedCom::getPinnochioVelocity( + const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointVelocities) const { + const auto& model = pinocchioInterfacePtr_->getModel(); + + Eigen::Matrix velocity(model.nv); + // Base linear velocity in Base frame + velocity.template head<3>() = switched_model::getLinearVelocity(baseLocalVelocities); + // Base angular velocity in Base frame + velocity.template segment<3>(3) = switched_model::getAngularVelocity(baseLocalVelocities); + // Joint velocity + velocity.template segment(6) = pinocchioMapping_.getPinocchioJointVector(jointVelocities); + + return velocity; +} + +} // namespace tpl +} // namespace anymal + +// Explicit instantiation +template class anymal::tpl::QuadrupedCom; +template class anymal::tpl::QuadrupedCom; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedInverseKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedInverseKinematics.cpp new file mode 100644 index 000000000..0b6295737 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedInverseKinematics.cpp @@ -0,0 +1,59 @@ +#include "ocs2_anymal_models/QuadrupedInverseKinematics.h" + +// Pinocchio +#include +#include + +#include + +namespace anymal { + +QuadrupedInverseKinematics::QuadrupedInverseKinematics(const FrameDeclaration& frameDeclaration, + const ocs2::PinocchioInterface& pinocchioInterface) { + auto data = pinocchioInterface.getData(); + const auto& model = pinocchioInterface.getModel(); + + switched_model::joint_coordinate_t zeroConfiguration(switched_model::joint_coordinate_t::Zero()); + pinocchio::forwardKinematics(model, data, zeroConfiguration); + pinocchio::updateFramePlacements(model, data); + + for (size_t leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + if (frameDeclaration.legs[leg].joints.size() != 3) { + throw std::runtime_error("[QuadrupedInverseKinematics] analytical inverse kinematics only valid for 3 joints per leg"); + } + + const auto& hipTransform = data.oMf[QuadrupedPinocchioMapping::getBodyId(frameDeclaration.legs[leg].joints[0], pinocchioInterface)]; + const auto& thighTransform = data.oMf[QuadrupedPinocchioMapping::getBodyId(frameDeclaration.legs[leg].joints[1], pinocchioInterface)]; + const auto& shankTransform = data.oMf[QuadrupedPinocchioMapping::getBodyId(frameDeclaration.legs[leg].joints[2], pinocchioInterface)]; + const auto& footTransform = data.oMf[QuadrupedPinocchioMapping::getBodyId(frameDeclaration.legs[leg].tip, pinocchioInterface)]; + + parameters_[leg] = switched_model::analytical_inverse_kinematics::LegInverseKinematicParameters( + hipTransform.translation(), thighTransform.translation() - hipTransform.translation(), + shankTransform.translation() - thighTransform.translation(), footTransform.translation() - shankTransform.translation()); + } +} + +QuadrupedInverseKinematics* QuadrupedInverseKinematics::clone() const { + return new QuadrupedInverseKinematics(*this); +} + +switched_model::vector3_t QuadrupedInverseKinematics::getLimbJointPositionsFromPositionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::vector3_t& positionBaseToFootInBaseFrame) const { + switched_model::vector3_t jointAngles{switched_model::vector3_t::Zero()}; + switched_model::analytical_inverse_kinematics::getLimbJointPositionsFromPositionBaseToFootInBaseFrame( + jointAngles, positionBaseToFootInBaseFrame, parameters_[footIndex], footIndex); + return jointAngles; +} + +switched_model::vector3_t QuadrupedInverseKinematics::getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame( + size_t footIndex, const switched_model::vector3_t& footVelocityRelativeToBaseInBaseFrame, const joint_jacobian_block_t& jointJacobian, + switched_model::scalar_t damping) const { + // v = J * dq, (bottom 3 rows = translational part) + switched_model::matrix3_t Jtranslational = jointJacobian.block<3, 3>(3, 0); + switched_model::matrix3_t JTJ = Jtranslational.transpose() * Jtranslational; + JTJ.diagonal().array() += damping; // regularize + + return JTJ.ldlt().solve(Jtranslational.transpose() * footVelocityRelativeToBaseInBaseFrame); +} + +} // namespace anymal \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedKinematics.cpp new file mode 100644 index 000000000..679122b3f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedKinematics.cpp @@ -0,0 +1,144 @@ +#include "ocs2_anymal_models/QuadrupedKinematics.h" + +// Pinocchio +#include +#include +#include + +#include +#include +#include + +namespace anymal { +namespace tpl { + +template +QuadrupedKinematics::QuadrupedKinematics(const FrameDeclaration& frameDeclaration, + const ocs2::PinocchioInterface& pinocchioInterface) + : pinocchioInterfacePtr_(new PinocchioInterface_s_t(castPinocchioInterface(pinocchioInterface))), + pinocchioMapping_(frameDeclaration, pinocchioInterface) { + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + switched_model::joint_coordinate_s_t zeroConfiguration; + zeroConfiguration.setZero(); + baseToLegRootInBaseFrame_[footIndex] = relativeTranslationInBaseFrame(zeroConfiguration, pinocchioMapping_.getHipFrameId(footIndex)); + } +} + +template +QuadrupedKinematics::QuadrupedKinematics(const QuadrupedKinematics& rhs) + : pinocchioInterfacePtr_(new PinocchioInterface_s_t(*rhs.pinocchioInterfacePtr_)), + pinocchioMapping_(rhs.pinocchioMapping_), + baseToLegRootInBaseFrame_(rhs.baseToLegRootInBaseFrame_){}; + +template +QuadrupedKinematics* QuadrupedKinematics::clone() const { + return new QuadrupedKinematics(*this); +} + +template +switched_model::vector3_s_t QuadrupedKinematics::baseToLegRootInBaseFrame(size_t footIndex) const { + return baseToLegRootInBaseFrame_[footIndex]; +} + +template +switched_model::vector3_s_t QuadrupedKinematics::positionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const { + pinocchio::FrameIndex frameId = pinocchioMapping_.getFootFrameId(footIndex); + const auto pinocchioJointPositions = pinocchioMapping_.getPinocchioJointVector(jointPositions); + return relativeTranslationInBaseFrame(pinocchioJointPositions, frameId); +} + +template +auto QuadrupedKinematics::baseToFootJacobianBlockInBaseFrame( + std::size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const -> joint_jacobian_block_t { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + + const auto pinocchioJointPositions = pinocchioMapping_.getPinocchioJointVector(jointPositions); + pinocchio::FrameIndex frameId = pinocchioMapping_.getFootFrameId(footIndex); + + joint_jacobian_t J; + pinocchio::computeFrameJacobian(model, data, pinocchioJointPositions, frameId, pinocchio::ReferenceFrame::LOCAL_WORLD_ALIGNED, J); + + // In Pinocchio, the first three coordinates of J represent linear part and the last three coordinates represent angular part. But it + // is the other way round in OCS2. Swap linear and angular parts to stick to the originally used OCS2's convention. + joint_jacobian_block_t res; + res.template block<3, 3>(0, 0) = J.template block<3, 3>(3, pinocchioMapping_.getPinocchioFootIndex(footIndex) * 3u); + res.template block<3, 3>(3, 0) = J.template block<3, 3>(0, pinocchioMapping_.getPinocchioFootIndex(footIndex) * 3u); + + return res; +} + +template +switched_model::matrix3_s_t QuadrupedKinematics::footOrientationInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const { + pinocchio::FrameIndex frameId = pinocchioMapping_.getFootFrameId(footIndex); + const auto pinocchioJointPositions = pinocchioMapping_.getPinocchioJointVector(jointPositions); + return relativeOrientationInBaseFrame(pinocchioJointPositions, frameId); +} + +template +switched_model::vector3_s_t QuadrupedKinematics::footVelocityRelativeToBaseInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::joint_coordinate_s_t& jointVelocities) const { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + + const auto pinocchioJointPositions = pinocchioMapping_.getPinocchioJointVector(jointPositions); + const auto pinocchioJointVelocities = pinocchioMapping_.getPinocchioJointVector(jointVelocities); + + pinocchio::forwardKinematics(model, data, pinocchioJointPositions, pinocchioJointVelocities); + + pinocchio::FrameIndex frameId = pinocchioMapping_.getFootFrameId(footIndex); + + return getFrameVelocity(model, data, frameId, pinocchio::ReferenceFrame::LOCAL_WORLD_ALIGNED).linear(); +} + +template +auto QuadrupedKinematics::collisionSpheresInBaseFrame(const switched_model::joint_coordinate_s_t& jointPositions) const + -> std::vector { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + const auto pinocchioJointPositions = pinocchioMapping_.getPinocchioJointVector(jointPositions); + pinocchio::forwardKinematics(model, data, pinocchioJointPositions); + + const auto& linkFrames = pinocchioMapping_.getCollisionLinkFrameIds(); + const auto& decl = pinocchioMapping_.getCollisionDeclaration(); + + std::vector collisionSpheres; + collisionSpheres.reserve(linkFrames.size()); + for (int i = 0; i < linkFrames.size(); ++i) { + const auto& transformation = pinocchio::updateFramePlacement(model, data, linkFrames[i]); + const switched_model::vector3_s_t offset = decl[i].offset.cast(); + collisionSpheres.push_back({transformation.act(offset), SCALAR_T(decl[i].radius)}); + } + + return collisionSpheres; +} + +template +switched_model::vector3_s_t QuadrupedKinematics::relativeTranslationInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions, pinocchio::FrameIndex frame) const { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + pinocchio::forwardKinematics(model, data, jointPositions); + + return pinocchio::updateFramePlacement(model, data, frame).translation(); +} + +template +switched_model::matrix3_s_t QuadrupedKinematics::relativeOrientationInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions, pinocchio::FrameIndex frame) const { + auto& data = pinocchioInterfacePtr_->getData(); + const auto& model = pinocchioInterfacePtr_->getModel(); + pinocchio::forwardKinematics(model, data, jointPositions); + + return pinocchio::updateFramePlacement(model, data, frame).rotation(); +} + +} // namespace tpl +} // namespace anymal + +// Explicit instantiation +template class anymal::tpl::QuadrupedKinematics; +template class anymal::tpl::QuadrupedKinematics; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedPinocchioMapping.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedPinocchioMapping.cpp new file mode 100644 index 000000000..f27383afc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/src/QuadrupedPinocchioMapping.cpp @@ -0,0 +1,97 @@ +#include "ocs2_anymal_models/QuadrupedPinocchioMapping.h" + +// Pinocchio +#include +#include + +namespace anymal { + +QuadrupedPinocchioMapping::QuadrupedPinocchioMapping(const FrameDeclaration& frameDeclaration, + const ocs2::PinocchioInterface& pinocchioInterface) { + for (int i = 0; i < switched_model::NUM_CONTACT_POINTS; ++i) { + hipFrameIds_[i] = getBodyId(frameDeclaration.legs[i].root, pinocchioInterface); + footFrameIds_[i] = getBodyId(frameDeclaration.legs[i].tip, pinocchioInterface); + } + ocs2JointNames_ = getJointNames(frameDeclaration); + extractPinocchioJointNames(pinocchioInterface); + extractFeetOrdering(pinocchioInterface); + + for (const auto& collision : frameDeclaration.collisions) { + collisionLinkFrameIds_.push_back(getBodyId(collision.link, pinocchioInterface)); + } + collisionDeclaration_ = frameDeclaration.collisions; +} + +namespace { +template +switched_model::joint_coordinate_s_t getPinocchioJointVectorImpl( + const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::feet_array_t& mapFeetOrderOcs2ToPinocchio) { + switched_model::joint_coordinate_s_t pinocchioJointPositions; + // OCS2 LF + pinocchioJointPositions.template segment<3>(3 * mapFeetOrderOcs2ToPinocchio[0]) = jointPositions.template segment<3>(0); + // OCS2 RF + pinocchioJointPositions.template segment<3>(3 * mapFeetOrderOcs2ToPinocchio[1]) = jointPositions.template segment<3>(3); + // OCS2 LH + pinocchioJointPositions.template segment<3>(3 * mapFeetOrderOcs2ToPinocchio[2]) = jointPositions.template segment<3>(6); + // OCS2 RH + pinocchioJointPositions.template segment<3>(3 * mapFeetOrderOcs2ToPinocchio[3]) = jointPositions.template segment<3>(9); + + return pinocchioJointPositions; +} +} // namespace + +switched_model::joint_coordinate_t QuadrupedPinocchioMapping::getPinocchioJointVector( + const switched_model::joint_coordinate_t& jointPositions) const { + return getPinocchioJointVectorImpl(jointPositions, mapFeetOrderOcs2ToPinocchio_); +} + +switched_model::joint_coordinate_ad_t QuadrupedPinocchioMapping::getPinocchioJointVector( + const switched_model::joint_coordinate_ad_t& jointPositions) const { + return getPinocchioJointVectorImpl(jointPositions, mapFeetOrderOcs2ToPinocchio_); +} + +size_t QuadrupedPinocchioMapping::getBodyId(const std::string& bodyName, const ocs2::PinocchioInterface& pinocchioInterface) { + const auto& model = pinocchioInterface.getModel(); + // Try as body first, to prevent a conflict when a body and joint have the same name + if (model.existBodyName(bodyName)) { + return model.getBodyId(bodyName); + } else { + // Try to take the joint frame if body does not exist + if (model.existJointName(bodyName)) { + return model.getFrameId(bodyName, pinocchio::JOINT); + } else { + throw std::runtime_error("[QuadrupedPinocchioMapping] Body " + bodyName + " does not exist."); + } + } +} + +void QuadrupedPinocchioMapping::extractPinocchioJointNames(const ocs2::PinocchioInterface& pinocchioInterface) { + const auto& model = pinocchioInterface.getModel(); + std::vector> pinocchioJointIds; + for (const auto& jointName : ocs2JointNames_) { + if (!model.existJointName(jointName)) { + throw std::runtime_error("[QuadrupedPinocchioMapping] Joint " + jointName + " does not exist."); + } else { + pinocchioJointIds.push_back({jointName, model.getJointId(jointName)}); + } + } + std::sort(pinocchioJointIds.begin(), pinocchioJointIds.end(), + [](const std::pair& lhs, const std::pair& rhs) { return lhs.second < rhs.second; }); + + for (const auto& jointPair : pinocchioJointIds) { + pinocchioJointNames_.push_back(jointPair.first); + } +} + +void QuadrupedPinocchioMapping::extractFeetOrdering(const ocs2::PinocchioInterface& pinocchioInterface) { + for (int i = 0; i < switched_model::NUM_CONTACT_POINTS; ++i) { + size_t jointMapping = + std::find(pinocchioJointNames_.begin(), pinocchioJointNames_.end(), ocs2JointNames_[3 * i]) - pinocchioJointNames_.begin(); + size_t pinocchioIdx = jointMapping / 3; + mapFeetOrderOcs2ToPinocchio_[i] = pinocchioIdx; + mapFeetOrderPinocchioToOcs2_[pinocchioIdx] = i; + } +} + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestDynamicsHelpers.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestDynamicsHelpers.cpp new file mode 100644 index 000000000..24f3a33ac --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestDynamicsHelpers.cpp @@ -0,0 +1,68 @@ +// +// Created by rgrandia on 12.05.21. +// + +#include + +#include + +#include + +using namespace switched_model; + +TEST(TestInertiaInverse, inv33sym) { + using anymal::inv33sym; + + matrix3_t Ahalf = matrix3_t::Random(); + matrix3_t A = Ahalf.transpose() * Ahalf; + matrix3_t AinvTest = inv33sym(A); + matrix3_t AinvCheck = A.inverse(); + + ASSERT_TRUE(AinvTest.isApprox(AinvCheck)); +} + +TEST(TestInertiaInverse, solve33sym) { + using anymal::solve33sym; + + matrix3_t Ahalf = matrix3_t::Random(); + vector3_t b = vector3_t::Random(); + matrix3_t A = Ahalf.transpose() * Ahalf; + + vector3_t solveTest = solve33sym(A, b); + vector3_t solveCheck = A.lu().solve(b); + + ASSERT_TRUE(solveTest.isApprox(solveCheck)); +} + +TEST(TestInertiaInverse, inertiaTensorSolve) { + using anymal::inertiaTensorSolveLinearAngular; + using anymal::inertiaTensorSolveAngularLinear; + + // Construct a inertia tensor + double m = 10.0; + matrix3_t Ihalf = matrix3_t::Random(); + vector3_t comVector = vector3_t::Random(); + matrix3_t crossTerm = crossProductMatrix(m * comVector); + matrix6_t MLinAng, MAngLin; + MLinAng << m * matrix3_t::Identity(), crossTerm.transpose(), crossTerm, Ihalf.transpose() * Ihalf + 1.0 / m * crossTerm * crossTerm.transpose(); + MAngLin << Ihalf.transpose() * Ihalf + 1.0 / m * crossTerm * crossTerm.transpose(), crossTerm, crossTerm.transpose(), m * matrix3_t::Identity(); + + // Check if the eigenvalues are valid + ASSERT_GT(MLinAng.eigenvalues().real().minCoeff(), 0.0); + ASSERT_GT(MAngLin.eigenvalues().real().minCoeff(), 0.0); + + vector6_t bLinAng = vector6_t::Random(); + vector6_t bAngLin; + bAngLin << bLinAng.tail<3>(), bLinAng.head<3>(); + + vector6_t solveTestLinAng = inertiaTensorSolveLinearAngular(MLinAng, bLinAng); + vector6_t solveCheckLinAng = MLinAng.lu().solve(bLinAng); + ASSERT_TRUE(solveTestLinAng.isApprox(solveCheckLinAng, 1e-8)); + + vector6_t solveTestAngLin = inertiaTensorSolveAngularLinear(MAngLin, bAngLin); + vector6_t solveCheckAngLin = MAngLin.lu().solve(bAngLin); + ASSERT_TRUE(solveTestAngLin.isApprox(solveCheckAngLin, 1e-8)); + + ASSERT_TRUE(solveTestAngLin.head<3>().isApprox(solveTestLinAng.tail<3>())); + ASSERT_TRUE(solveTestAngLin.tail<3>().isApprox(solveTestLinAng.head<3>())); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestFrameDeclaration.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestFrameDeclaration.cpp new file mode 100644 index 000000000..8a03cb316 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestFrameDeclaration.cpp @@ -0,0 +1,34 @@ +// +// Created by rgrandia on 27.04.22. +// + +#include + +#include + +#include +#include +#include +#include + +TEST(TestFrameDeclaration, loadTestFile) { + const auto decl = anymal::frameDeclarationFromFile(anymal::getPath() + "/urdf/frame_declaration_anymal_c.info"); + EXPECT_EQ(decl.root, "base"); + EXPECT_EQ(decl.legs[0].root, "LF_HAA"); + EXPECT_EQ(decl.legs[1].tip, "RF_FOOT"); + EXPECT_EQ(decl.legs[2].joints[1], "LH_HFE"); + EXPECT_EQ(decl.collisions[3].link, "RH_KFE"); + EXPECT_DOUBLE_EQ(decl.collisions[3].radius, 0.08); + EXPECT_DOUBLE_EQ(decl.collisions[3].offset.x(), -0.055); +} + +TEST(TestFrameMapping, camelPinocchioMapping) { + const auto interface = ocs2::getPinocchioInterfaceFromUrdfString(getUrdfString(anymal::AnymalModel::Camel)); + const auto decl = anymal::frameDeclarationFromFile(anymal::getPath() + "/urdf/frame_declaration_anymal_c.info"); + anymal::QuadrupedPinocchioMapping mapping(decl, interface); + + EXPECT_EQ(mapping.getPinocchioFootIndex(0), 0); + EXPECT_EQ(mapping.getPinocchioFootIndex(1), 2); + EXPECT_EQ(mapping.getPinocchioFootIndex(2), 1); + EXPECT_EQ(mapping.getPinocchioFootIndex(3), 3); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestInverseKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestInverseKinematics.cpp new file mode 100644 index 000000000..9ee357ce4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestInverseKinematics.cpp @@ -0,0 +1,208 @@ +#include + +#include + +// Pinocchio +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +using namespace anymal; + +class QuadrupedInverseKinematicsTest : public ::testing::Test { + public: + QuadrupedInverseKinematicsTest() + : frameDeclaration(frameDeclarationFromFile(getPath() + "/urdf/frame_declaration_anymal_c.info")), + pinocchioInterface(ocs2::getPinocchioInterfaceFromUrdfString(getUrdfString(AnymalModel::Camel))), + kinematics_(frameDeclaration, pinocchioInterface), + inverseKinematics_(frameDeclaration, pinocchioInterface) { + srand(10); + } + + FrameDeclaration frameDeclaration; + ocs2::PinocchioInterface pinocchioInterface; + QuadrupedKinematics kinematics_; + QuadrupedInverseKinematics inverseKinematics_; + switched_model::feet_array_t legParametersPerLeg; +}; + +TEST_F(QuadrupedInverseKinematicsTest, defaultJointAngles) { + switched_model::joint_coordinate_t jointPositions; + jointPositions << -0.25, 0.60, -0.85, 0.25, 0.60, -0.85, -0.25, -0.60, 0.85, 0.25, -0.60, 0.85; + auto jointsPerLeg = switched_model::toArray(jointPositions); + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + switched_model::vector3_t positionBaseToFootInBaseFrame = kinematics_.positionBaseToFootInBaseFrame(footIndex, jointPositions); + + switched_model::vector3_t legJoints = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, positionBaseToFootInBaseFrame); + EXPECT_TRUE(jointsPerLeg[footIndex].isApprox(legJoints)); + } +} + +TEST_F(QuadrupedInverseKinematicsTest, randomJointAngles) { + switched_model::joint_coordinate_t jointPositionsDefault; + jointPositionsDefault << -0.25, 0.60, -0.85, 0.25, 0.60, -0.85, -0.25, -0.60, 0.85, 0.25, -0.60, 0.85; + const auto jointsPerLegDefault = switched_model::toArray(jointPositionsDefault); + const switched_model::scalar_t perturbation = 0.4; + const int Ntest = 100; + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + for (int i = 0; i < Ntest; ++i) { + auto jointsPerLeg = jointsPerLegDefault; + jointsPerLeg[footIndex] += perturbation * switched_model::vector3_t::Random(); + + // Forward kinematics + switched_model::vector3_t positionBaseToFootInBaseFrame = + kinematics_.positionBaseToFootInBaseFrame(footIndex, switched_model::fromArray(jointsPerLeg)); + + // Inverse kinematics + switched_model::vector3_t legJoints = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, positionBaseToFootInBaseFrame); + + EXPECT_TRUE(jointsPerLeg[footIndex].isApprox(legJoints)) + << "Foot: " << footIndex << ", True angles: " << jointsPerLeg[footIndex].transpose() << ", IK: " << legJoints.transpose(); + } + } +} + +TEST_F(QuadrupedInverseKinematicsTest, outOfRange) { + const int Ntest = 100; + const double tol = 1e-6; + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + for (int i = 0; i < Ntest; ++i) { + const switched_model::vector3_t outOfRangeTarget = 1000.0 * switched_model::vector3_t::Random(); + + // Inverse kinematics + switched_model::vector3_t legJoints = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, outOfRangeTarget); + + // Forward kinematics + switched_model::feet_array_t jointsPerLeg = + switched_model::constantFeetArray(switched_model::vector3_t::Zero()); + jointsPerLeg[footIndex] = legJoints; + + switched_model::vector3_t positionBaseToFootInBaseFrame = + kinematics_.positionBaseToFootInBaseFrame(footIndex, switched_model::fromArray(jointsPerLeg)); + + // Inverse kinematics + legJoints = inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, positionBaseToFootInBaseFrame); + + EXPECT_TRUE(jointsPerLeg[footIndex].allFinite()) + << "Foot: " << footIndex << " First IK not finite! " << jointsPerLeg[footIndex].transpose(); + EXPECT_TRUE(legJoints.allFinite()) << "Foot: " << footIndex << " Second IK not finite! " << legJoints.transpose(); + EXPECT_TRUE(jointsPerLeg[footIndex].isApprox(legJoints, tol)) + << "Foot: " << footIndex << ", First IK: " << jointsPerLeg[footIndex].transpose() << ", second IK: " << legJoints.transpose(); + } + } +} + +TEST_F(QuadrupedInverseKinematicsTest, closeToHip) { + const int Ntest = 100; + const double tol = 1e-6; + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + for (int i = 0; i < Ntest; ++i) { + switched_model::vector3_t outOfRangeTarget = legParametersPerLeg[footIndex].positionBaseToHaaCenterInBaseFrame_; + if (i > 0) { // test equal to HAA center for the first test, afterward test in range close to the hip + outOfRangeTarget += legParametersPerLeg[footIndex].positionHipToFootYoffset_ * switched_model::vector3_t::Random(); + } + + // Inverse kinematics + switched_model::vector3_t legJoints = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, outOfRangeTarget); + + // Forward kinematics + switched_model::feet_array_t jointsPerLeg = + switched_model::constantFeetArray(switched_model::vector3_t::Zero()); + jointsPerLeg[footIndex] = legJoints; + + switched_model::vector3_t positionBaseToFootInBaseFrame = + kinematics_.positionBaseToFootInBaseFrame(footIndex, switched_model::fromArray(jointsPerLeg)); + + // Inverse kinematics + legJoints = inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, positionBaseToFootInBaseFrame); + + EXPECT_TRUE(jointsPerLeg[footIndex].allFinite()) + << "Foot: " << footIndex << " First IK not finite! " << jointsPerLeg[footIndex].transpose(); + EXPECT_TRUE(legJoints.allFinite()) << "Foot: " << footIndex << " Second IK not finite! " << legJoints.transpose(); + EXPECT_TRUE(jointsPerLeg[footIndex].isApprox(legJoints, tol)) + << "Foot: " << footIndex << ", First IK: " << jointsPerLeg[footIndex].transpose() << ", second IK: " << legJoints.transpose(); + } + } +} + +TEST_F(QuadrupedInverseKinematicsTest, defaultJointAnglesVelocity) { + const double tol = 1e-6; + const double damping = 1e-9; + + switched_model::joint_coordinate_t jointPositions; + jointPositions << -0.25, 0.60, -0.85, 0.25, 0.60, -0.85, -0.25, -0.60, 0.85, 0.25, -0.60, 0.85; + + switched_model::joint_coordinate_t jointVelocities; + jointVelocities.setRandom(); + auto jointVelocitiesPerLeg = switched_model::toArray(jointVelocities); + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + switched_model::vector3_t footVelocity = kinematics_.footVelocityRelativeToBaseInBaseFrame(footIndex, jointPositions, jointVelocities); + + switched_model::vector3_t legJointVelocities = inverseKinematics_.getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame( + footIndex, footVelocity, kinematics_.baseToFootJacobianBlockInBaseFrame(footIndex, jointPositions), damping); + EXPECT_TRUE(jointVelocitiesPerLeg[footIndex].isApprox(legJointVelocities, tol)); + } +} + +TEST_F(QuadrupedInverseKinematicsTest, singularityJointAnglesVelocity) { + const int Ntest = 100; + + const double tol = 1e-6; + const double damping = 1e-9; + + switched_model::joint_coordinate_t jointVelocities; + jointVelocities.setRandom(); + auto jointVelocitiesPerLeg = switched_model::toArray(jointVelocities); + + for (size_t footIndex = 0; footIndex < switched_model::NUM_CONTACT_POINTS; ++footIndex) { + for (int i = 0; i < Ntest; ++i) { + // Inverse kinematics to create singular configuration + const switched_model::vector3_t outOfRangeTarget = 1000.0 * switched_model::vector3_t::Random(); + switched_model::vector3_t legJoints = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(footIndex, outOfRangeTarget); + + // Set joint positions + switched_model::feet_array_t jointsPerLeg = + switched_model::constantFeetArray(switched_model::vector3_t::Zero()); + jointsPerLeg[footIndex] = legJoints; + auto jointPositions = switched_model::fromArray(jointsPerLeg); + + switched_model::vector3_t footVelocity = + kinematics_.footVelocityRelativeToBaseInBaseFrame(footIndex, jointPositions, jointVelocities); + + auto J = kinematics_.baseToFootJacobianBlockInBaseFrame(footIndex, jointPositions); + + switched_model::vector3_t legJointVelocities = + inverseKinematics_.getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame(footIndex, footVelocity, J, damping); + EXPECT_TRUE(legJointVelocities.allFinite()); + + // Compare on the achieved foot velocity + EXPECT_TRUE(footVelocity.isApprox(J.block<3, 3>(3, 0) * legJointVelocities, tol)) + << "Foot: " << footIndex << ", Velocities: " << jointVelocitiesPerLeg[footIndex].transpose() + << ", IK: " << legJointVelocities.transpose(); + } + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioCom.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioCom.cpp new file mode 100644 index 000000000..22f107d37 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioCom.cpp @@ -0,0 +1,105 @@ +#include + +#include + +#include + +#include +#include +#include +#include +#include + +#include "camel/AnymalCamelCom.h" + +using namespace anymal; + +class QuadrupedComTest : public ::testing::Test { + public: + QuadrupedComTest() + : frameDeclaration(frameDeclarationFromFile(getPath() + "/urdf/frame_declaration_anymal_c.info")), + pinocchioInterface(createQuadrupedPinocchioInterfaceFromUrdfString(getUrdfString(AnymalModel::Camel))), + pinocchioCom_(frameDeclaration, pinocchioInterface), + kinematics_(frameDeclaration, ocs2::getPinocchioInterfaceFromUrdfString(getUrdfString(AnymalModel::Camel))), + inverseKinematics_(frameDeclaration, ocs2::getPinocchioInterfaceFromUrdfString(getUrdfString(AnymalModel::Camel))) { + srand(0); + } + + FrameDeclaration frameDeclaration; + ocs2::PinocchioInterface pinocchioInterface; + QuadrupedCom pinocchioCom_; + AnymalCamelCom robcogenCom_; + QuadrupedKinematics kinematics_; + QuadrupedInverseKinematics inverseKinematics_; +}; + +TEST_F(QuadrupedComTest, totalMass) { + EXPECT_FLOAT_EQ(pinocchioCom_.totalMass(), robcogenCom_.totalMass()); +} + +TEST_F(QuadrupedComTest, calculateBaseLocalAccelerations) { + const ocs2::vector_t basePose = switched_model::base_coordinate_t::Random(); + const ocs2::vector_t baseLocalVelocities = switched_model::base_coordinate_t::Random(); + + const ocs2::vector_t jointPositions = switched_model::joint_coordinate_t::Random(); + const ocs2::vector_t jointVelocities = switched_model::joint_coordinate_t::Random(); + const ocs2::vector_t jointAccelerations = switched_model::joint_coordinate_t::Random(); + const ocs2::vector_t forcesOnBaseInBaseFrame = switched_model::base_coordinate_t::Random(); + + ocs2::vector_t rAcc = robcogenCom_.calculateBaseLocalAccelerations(basePose, baseLocalVelocities, jointPositions, jointVelocities, + jointAccelerations, forcesOnBaseInBaseFrame); + ocs2::vector_t pAcc = pinocchioCom_.calculateBaseLocalAccelerations(basePose, baseLocalVelocities, jointPositions, jointVelocities, + jointAccelerations, forcesOnBaseInBaseFrame); + + EXPECT_TRUE(pAcc.isApprox(rAcc, 1e-8)) << "Pinocchio: \n" << pAcc.transpose() << "\nRoboGen: \n" << rAcc.transpose(); +} + +TEST_F(QuadrupedComTest, comWorldAndBase) { + const switched_model::base_coordinate_t basePose = switched_model::base_coordinate_t::Random(); + const switched_model::joint_coordinate_t jointPositions = switched_model::joint_coordinate_t::Random(); + + const auto comInWorld = pinocchioCom_.centerOfMassInWorldFrame(basePose, jointPositions); + const auto comInBase = pinocchioCom_.centerOfMassInBaseFrame(jointPositions); + const switched_model::vector3_t comInWorldCheck = + switched_model::rotateVectorBaseToOrigin(comInBase, switched_model::getOrientation(basePose)) + + switched_model::getPositionInOrigin(basePose); + + ASSERT_TRUE(comInWorld.isApprox(comInWorldCheck)); +} + +TEST_F(QuadrupedComTest, comInBasePerConfiguration) { + switched_model::base_coordinate_t basePose = switched_model::base_coordinate_t::Zero(); + switched_model::joint_coordinate_t jointPositionsDefault; + jointPositionsDefault << -0.25, 0.60, -0.85, 0.25, 0.60, -0.85, -0.25, -0.60, 0.85, 0.25, -0.60, 0.85; + + const auto baseToFeetDefault = kinematics_.positionBaseToFeetInBaseFrame(jointPositionsDefault); + auto hipToFeetDefault = baseToFeetDefault; + for (int leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + hipToFeetDefault[leg] -= kinematics_.baseToLegRootInBaseFrame(leg); + } + + for (ocs2::scalar_t pitchDeg = -50; pitchDeg < 51.0; pitchDeg += 5.0) { + ocs2::scalar_t pitch = pitchDeg * (M_PI / 180.0); + basePose[1] = pitch; + + const auto comInWorldDefault = pinocchioCom_.centerOfMassInWorldFrame(basePose, jointPositionsDefault); + const auto comInBaseDefault = pinocchioCom_.centerOfMassInBaseFrame(jointPositionsDefault); + + // Adaptive legs + switched_model::joint_coordinate_t jointPositionsAdaptive; + for (int leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + switched_model::vector3_t baseToFootInBase = + kinematics_.baseToLegRootInBaseFrame(leg) + + switched_model::rotateVectorOriginToBase(hipToFeetDefault[leg], switched_model::getOrientation(basePose)); + jointPositionsAdaptive.segment<3>(3 * leg) = + inverseKinematics_.getLimbJointPositionsFromPositionBaseToFootInBaseFrame(leg, baseToFootInBase); + } + + const auto comInWorldAdaptive = pinocchioCom_.centerOfMassInWorldFrame(basePose, jointPositionsAdaptive); + const auto comInBaseAdaptive = pinocchioCom_.centerOfMassInBaseFrame(jointPositionsAdaptive); + + // std::cout << "Pitch: " << pitchDeg << ", CoM default: " << comInWorldDefault.transpose() + // << ", CoM adaptive: " << comInWorldAdaptive.transpose() << std::endl; + std::cout << pitchDeg << ", " << comInWorldDefault.x() << ", " << comInWorldAdaptive.x() << std::endl; + } +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioKinematics.cpp new file mode 100644 index 000000000..846238e1f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/TestQuadrupedPinocchioKinematics.cpp @@ -0,0 +1,89 @@ +#include + +#include + +#include +#include +#include + +#include "camel/AnymalCamelKinematics.h" + +#include +#include + +using namespace anymal; + +class QuadrupedKinematicsTest : public ::testing::Test { + public: + QuadrupedKinematicsTest() + : frameDeclaration(frameDeclarationFromFile(getPath() + "/urdf/frame_declaration_anymal_c.info")), + pinocchioInterface(ocs2::getPinocchioInterfaceFromUrdfString(getUrdfString(AnymalModel::Camel))), + pinocchioKinematics_(frameDeclaration, pinocchioInterface) { + srand(10); + } + + FrameDeclaration frameDeclaration; + ocs2::PinocchioInterface pinocchioInterface; + QuadrupedKinematics pinocchioKinematics_; + AnymalCamelKinematics robcogenKinematics_; +}; + +TEST_F(QuadrupedKinematicsTest, baseToLegRootInBaseFrame) { + for (int i = 0; i < 4; i++) { + switched_model::vector3_t pinocchio = pinocchioKinematics_.baseToLegRootInBaseFrame(i); + switched_model::vector3_t robcogen = robcogenKinematics_.baseToLegRootInBaseFrame(i); + EXPECT_TRUE(pinocchio.isApprox(robcogen)) << "i: " << i << "\nPinocchio: " << pinocchio.transpose() + << "\n\n RobCoGen: " << robcogen.transpose(); + } +} + +TEST_F(QuadrupedKinematicsTest, baseToFootJacobianBlockInBaseFrame) { + switched_model::joint_coordinate_t q; + q.setRandom(); + + for (int i = 0; i < 4; i++) { + ocs2::matrix_t pinocchio = pinocchioKinematics_.baseToFootJacobianBlockInBaseFrame(i, q); + ocs2::matrix_t robcogen = robcogenKinematics_.baseToFootJacobianBlockInBaseFrame(i, q); + EXPECT_TRUE(pinocchio.isApprox(robcogen)) << "i: " << i << "\nPinocchio:\n" << pinocchio << "\n\n RobCoGen:\n" << robcogen; + } +} + +TEST_F(QuadrupedKinematicsTest, footOrientationInBaseFrame) { + switched_model::joint_coordinate_t q; + q.setRandom(); + + for (int i = 0; i < 4; i++) { + ocs2::matrix_t pinocchio = pinocchioKinematics_.footOrientationInBaseFrame(i, q); + ocs2::matrix_t robcogen = robcogenKinematics_.footOrientationInBaseFrame(i, q); + EXPECT_TRUE(pinocchio.isApprox(robcogen)) << "i: " << i << "\nPinocchio:\n" << pinocchio << "\n\n RobCoGen:\n" << robcogen; + } +} + +TEST_F(QuadrupedKinematicsTest, collisionSpheresInBaseFrame) { + switched_model::joint_coordinate_t q; + q.setRandom(); + // q << 0, 1.5, 0, 0, 1.53, 0, 0, 0, 0, 0, 1.59; + + auto pinocchio = pinocchioKinematics_.collisionSpheresInBaseFrame(q); + auto robcogen = robcogenKinematics_.collisionSpheresInBaseFrame(q); + for (std::size_t i = 0; i < switched_model::NUM_CONTACT_POINTS; i++) { + EXPECT_TRUE(pinocchio[i].position.isApprox(robcogen[i].position)) << "i: " << i << "\nPinocchio:\n" + << pinocchio[i].position.transpose() << "\nRobCoGen:\n" + << robcogen[i].position.transpose() << "\n"; + } +} + +TEST_F(QuadrupedKinematicsTest, footVelocityRelativeToBaseInBaseFrame) { + switched_model::joint_coordinate_t q; + q.setRandom(); + switched_model::joint_coordinate_t v; + v.setRandom(); + + for (std::size_t i = 0; i < switched_model::NUM_CONTACT_POINTS; i++) { + auto pinocchio = pinocchioKinematics_.footVelocityRelativeToBaseInBaseFrame(i, q, v); + auto reference = robcogenKinematics_.footVelocityRelativeToBaseInBaseFrame(i, q, v); + EXPECT_TRUE(pinocchio.isApprox(reference)) << "i: " << i << "\nPinocchio:\n" + << pinocchio.transpose() << "\nReference:\n" + << reference.transpose() << "\n"; + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.cpp new file mode 100644 index 000000000..6e8c89365 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.cpp @@ -0,0 +1,58 @@ +/* + * AnymalCamelCom.h + * + * Created on: Nov, 2018 + * Author: farbod + */ + +#include "AnymalCamelCom.h" + +#include +#include "RobcogenHelpers.h" +#include "generated/inertia_properties.h" +#include "generated/inverse_dynamics.h" +#include "generated/jsim.h" +#include "generated/miscellaneous.h" +#include "generated/transforms.h" + +#include "ocs2_switched_model_interface/core/Rotations.h" + +namespace anymal { +namespace tpl { + +template +AnymalCamelCom::AnymalCamelCom() { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + iit::camel::dyn::tpl::InertiaProperties inertiaProperties_; + totalMass_ = inertiaProperties_.getTotalMass(); +} + +template +AnymalCamelCom* AnymalCamelCom::clone() const { + return new AnymalCamelCom(*this); +} + +template +switched_model::base_coordinate_s_t AnymalCamelCom::calculateBaseLocalAccelerations( + const switched_model::base_coordinate_s_t& basePose, const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointPositions, + const switched_model::joint_coordinate_s_t& jointVelocities, + const switched_model::joint_coordinate_s_t& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + iit::camel::dyn::tpl::InertiaProperties inertiaProperties_; + iit::camel::tpl::ForceTransforms forceTransforms_; + iit::camel::tpl::MotionTransforms motionTransforms_; + iit::camel::dyn::tpl::JSIM jointSpaceInertiaMatrix_(inertiaProperties_, forceTransforms_); + iit::camel::dyn::tpl::InverseDynamics inverseDynamics_(inertiaProperties_, motionTransforms_); + + return anymal::robcogen_helpers::computeBaseAcceleration(inverseDynamics_, jointSpaceInertiaMatrix_, basePose, baseLocalVelocities, + jointPositions, jointVelocities, jointAccelerations, forcesOnBaseInBaseFrame); +} + +} // namespace tpl +} // namespace anymal + +// Explicit instantiation +template class anymal::tpl::AnymalCamelCom; +template class anymal::tpl::AnymalCamelCom; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.h new file mode 100644 index 000000000..4de4700e2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelCom.h @@ -0,0 +1,55 @@ +/* + * AnymalCamelCom.h + * + * Created on: Aug 11, 2018 + * Author: farbod + */ + +#pragma once + +#include + +namespace anymal { +namespace tpl { + +template +class AnymalCamelCom : public switched_model::ComModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** + * Constructor needed for initialization + */ + AnymalCamelCom(); + + /** + * Default destructor + */ + ~AnymalCamelCom() = default; + + AnymalCamelCom* clone() const override; + + SCALAR_T totalMass() const override { return totalMass_; } + + switched_model::base_coordinate_s_t calculateBaseLocalAccelerations( + const switched_model::base_coordinate_s_t& basePose, const switched_model::base_coordinate_s_t& baseLocalVelocities, + const switched_model::joint_coordinate_s_t& jointPositions, const switched_model::joint_coordinate_s_t& jointVelocities, + const switched_model::joint_coordinate_s_t& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) const override; + + private: + SCALAR_T totalMass_; +}; + +} // namespace tpl + +using AnymalCamelCom = tpl::AnymalCamelCom; +using AnymalCamelComAd = tpl::AnymalCamelCom; + +} // namespace anymal + +/** + * Explicit instantiation, for instantiation additional types, include the implementation file instead of this one. + */ +extern template class anymal::tpl::AnymalCamelCom; +extern template class anymal::tpl::AnymalCamelCom; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.cpp new file mode 100644 index 000000000..f5cc3980f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.cpp @@ -0,0 +1,174 @@ +// +// Created by rgrandia on 18.09.19. +// + +#include "AnymalCamelKinematics.h" + +#include + +#include "generated/jacobians.h" +#include "generated/transforms.h" + +namespace anymal { +namespace tpl { + +template +AnymalCamelKinematics* AnymalCamelKinematics::clone() const { + return new AnymalCamelKinematics(*this); +} + +template +switched_model::vector3_s_t AnymalCamelKinematics::baseToLegRootInBaseFrame(size_t footIndex) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + + switch (footIndex) { + case LF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HAA fr_trunk_X_fr_LF_haa_; + return fr_trunk_X_fr_LF_haa_.template topRightCorner<3, 1>(); + } + case RF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HAA fr_trunk_X_fr_RF_haa_; + return fr_trunk_X_fr_RF_haa_.template topRightCorner<3, 1>(); + } + case LH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HAA fr_trunk_X_fr_LH_haa_; + return fr_trunk_X_fr_LH_haa_.template topRightCorner<3, 1>(); + } + case RH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HAA fr_trunk_X_fr_RH_haa_; + return fr_trunk_X_fr_RH_haa_.template topRightCorner<3, 1>(); + } + default: + throw std::runtime_error("Not defined foot index."); + } +} + +template +switched_model::vector3_s_t AnymalCamelKinematics::positionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + + switch (footIndex) { + case LF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_FOOT fr_trunk_X_fr_LF_foot_; + return fr_trunk_X_fr_LF_foot_(jointPositions).template topRightCorner<3, 1>(); + } + case RF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_FOOT fr_trunk_X_fr_RF_foot_; + return fr_trunk_X_fr_RF_foot_(jointPositions).template topRightCorner<3, 1>(); + } + case LH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_FOOT fr_trunk_X_fr_LH_foot_; + return fr_trunk_X_fr_LH_foot_(jointPositions).template topRightCorner<3, 1>(); + } + case RH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_FOOT fr_trunk_X_fr_RH_foot_; + return fr_trunk_X_fr_RH_foot_(jointPositions).template topRightCorner<3, 1>(); + } + default: + throw std::runtime_error("Not defined foot index."); + } +} + +template +typename AnymalCamelKinematics::joint_jacobian_block_t AnymalCamelKinematics::baseToFootJacobianBlockInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + + switch (footIndex) { + case LF: { + typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LF_FOOT fr_trunk_J_fr_LF_foot_; + return fr_trunk_J_fr_LF_foot_(jointPositions); + } + case RF: { + typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RF_FOOT fr_trunk_J_fr_RF_foot_; + return fr_trunk_J_fr_RF_foot_(jointPositions); + } + case LH: { + typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LH_FOOT fr_trunk_J_fr_LH_foot_; + return fr_trunk_J_fr_LH_foot_(jointPositions); + } + case RH: { + typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RH_FOOT fr_trunk_J_fr_RH_foot_; + return fr_trunk_J_fr_RH_foot_(jointPositions); + } + default: { + throw std::runtime_error("Not defined foot index."); + } + } +} + +template +switched_model::matrix3_s_t AnymalCamelKinematics::footOrientationInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + + switch (footIndex) { + case LF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_FOOT fr_base_X_fr_LF_FOOT; + return fr_base_X_fr_LF_FOOT(jointPositions).template topLeftCorner<3, 3>(); + } + case RF: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_FOOT fr_base_X_fr_RF_FOOT; + return fr_base_X_fr_RF_FOOT(jointPositions).template topLeftCorner<3, 3>(); + } + case LH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_FOOT fr_base_X_fr_LH_FOOT; + return fr_base_X_fr_LH_FOOT(jointPositions).template topLeftCorner<3, 3>(); + } + case RH: { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_FOOT fr_base_X_fr_RH_FOOT; + return fr_base_X_fr_RH_FOOT(jointPositions).template topLeftCorner<3, 3>(); + } + default: + throw std::runtime_error("Undefined endeffector index."); + } +} + +template +std::vector::CollisionSphere> AnymalCamelKinematics::collisionSpheresInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions) const { + using trait_t = typename iit::rbd::tpl::TraitSelector::Trait; + + const SCALAR_T kneeRadius(0.08); + const switched_model::vector3_s_t kneeOffsetInKneeFrame{SCALAR_T(0.0), SCALAR_T(0.0), SCALAR_T(0.055)}; + + std::vector collisionSpheres; + + { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_KFE fr_base_X_fr_LF_KFE; + fr_base_X_fr_LF_KFE.update(jointPositions); + collisionSpheres.push_back(CollisionSphere{fr_base_X_fr_LF_KFE.template topRightCorner<3, 1>(), kneeRadius}); + collisionSpheres.back().position -= fr_base_X_fr_LF_KFE.template topLeftCorner<3, 3>() * kneeOffsetInKneeFrame; + } + + { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_KFE fr_base_X_fr_RF_KFE; + fr_base_X_fr_RF_KFE.update(jointPositions); + collisionSpheres.push_back(CollisionSphere{fr_base_X_fr_RF_KFE.template topRightCorner<3, 1>(), kneeRadius}); + collisionSpheres.back().position += fr_base_X_fr_RF_KFE.template topLeftCorner<3, 3>() * kneeOffsetInKneeFrame; + } + + { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_KFE fr_base_X_fr_LH_KFE; + fr_base_X_fr_LH_KFE.update(jointPositions); + collisionSpheres.push_back(CollisionSphere{fr_base_X_fr_LH_KFE.template topRightCorner<3, 1>(), kneeRadius}); + collisionSpheres.back().position -= fr_base_X_fr_LH_KFE.template topLeftCorner<3, 3>() * kneeOffsetInKneeFrame; + } + + { + typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_KFE fr_base_X_fr_RH_KFE; + fr_base_X_fr_RH_KFE.update(jointPositions); + collisionSpheres.push_back(CollisionSphere{fr_base_X_fr_RH_KFE.template topRightCorner<3, 1>(), kneeRadius}); + collisionSpheres.back().position += fr_base_X_fr_RH_KFE.template topLeftCorner<3, 3>() * kneeOffsetInKneeFrame; + } + + return collisionSpheres; +} + +} // namespace tpl +} // end of namespace anymal + +// Explicit instantiation +template class anymal::tpl::AnymalCamelKinematics; +template class anymal::tpl::AnymalCamelKinematics; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.h new file mode 100644 index 000000000..44d197c93 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/AnymalCamelKinematics.h @@ -0,0 +1,58 @@ +/* + * AnymalCamelKinematics.h + * + * Created on: Aug 11, 2017 + * Author: farbod + */ + +#pragma once + +#include + +namespace anymal { +namespace tpl { + +template +class AnymalCamelKinematics final : public switched_model::KinematicsModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef switched_model::KinematicsModelBase BASE; + using typename BASE::CollisionSphere; + using typename BASE::joint_jacobian_block_t; + + enum { LF = 0, RF = 1, LH = 2, RH = 3 }; + + AnymalCamelKinematics() = default; + + ~AnymalCamelKinematics() = default; + + AnymalCamelKinematics* clone() const override; + + switched_model::vector3_s_t baseToLegRootInBaseFrame(size_t footIndex) const override; + + switched_model::vector3_s_t positionBaseToFootInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + joint_jacobian_block_t baseToFootJacobianBlockInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + switched_model::matrix3_s_t footOrientationInBaseFrame( + size_t footIndex, const switched_model::joint_coordinate_s_t& jointPositions) const override; + + std::vector collisionSpheresInBaseFrame( + const switched_model::joint_coordinate_s_t& jointPositions) const override; +}; + +} // namespace tpl + +using AnymalCamelKinematics = tpl::AnymalCamelKinematics; +using AnymalCamelKinematicsAd = tpl::AnymalCamelKinematics; + +} // namespace anymal + +/** + * Explicit instantiation, for instantiation additional types, include the implementation file instead of this one. + */ +extern template class anymal::tpl::AnymalCamelKinematics; +extern template class anymal::tpl::AnymalCamelKinematics; diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/RobcogenHelpers.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/RobcogenHelpers.h new file mode 100644 index 000000000..ce12c23f5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/RobcogenHelpers.h @@ -0,0 +1,76 @@ +// +// Created by rgrandia on 23.09.20. +// + +#pragma once + +#include +#include + +#include "ocs2_anymal_models/DynamicsHelpers.h" + +namespace anymal { +namespace robcogen_helpers { + +template +struct BaseDynamicsTerms { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// 6 x 6 : inertia tensor of the base + Eigen::Matrix Mb; + /// 6 x number joints : inertial coupling between joints and base + Eigen::Matrix Mj; + /// centrifugal/coriolis effects on the base + switched_model::base_coordinate_s_t C; + /// result of inv(Mb) * G, where G is the gravitation base term of the rigid body dynamics. + switched_model::base_coordinate_s_t invMbG; +}; + +template +BaseDynamicsTerms getBaseDynamicsTermsImpl(INVDYN& inverseDynamics, JSIM& jsim, + const switched_model::base_coordinate_s_t& qBase, + const switched_model::base_coordinate_s_t& qdBase, + const Eigen::Matrix& qJoints, + const Eigen::Matrix& qdJoints) { + BaseDynamicsTerms baseDynamicsTerms; + + const auto M = jsim.update(qJoints); + baseDynamicsTerms.Mb = M.template topLeftCorner(); + baseDynamicsTerms.Mj = M.template topRightCorner(); + + inverseDynamics.setJointStatus(qJoints); + + { // Get gravitational vector + // gravity vector in the base frame + const SCALAR_T gravitationalAcceleration = SCALAR_T(9.81); + baseDynamicsTerms.invMbG << switched_model::vector3_s_t::Zero(), + switched_model::rotateVectorOriginToBase( + switched_model::vector3_s_t(SCALAR_T(0.0), SCALAR_T(0.0), gravitationalAcceleration), + switched_model::getOrientation(qBase)); + } + + { // Get coriolis/centrifugal vector + switched_model::vector6_s_t baseWrench; + Eigen::Matrix jForces; + inverseDynamics.C_terms_fully_actuated(baseDynamicsTerms.C, jForces, qdBase, qdJoints); + } + + return baseDynamicsTerms; +} + +template +switched_model::base_coordinate_s_t computeBaseAcceleration( + INVDYN& inverseDynamics, JSIM& jsim, const switched_model::base_coordinate_s_t& basePose, + const switched_model::base_coordinate_s_t& baseLocalVelocities, + const Eigen::Matrix& jointPositions, const Eigen::Matrix& jointVelocities, + const Eigen::Matrix& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) { + const auto baseDynamics = getBaseDynamicsTermsImpl(inverseDynamics, jsim, basePose, baseLocalVelocities, jointPositions, jointVelocities); + + switched_model::base_coordinate_s_t baseForces = forcesOnBaseInBaseFrame - baseDynamics.C; + baseForces.noalias() -= baseDynamics.Mj * jointAccelerations; + + return inertiaTensorSolveAngularLinear(baseDynamics.Mb, baseForces) - baseDynamics.invMbG; +} + +} // namespace robcogen_helpers +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/declarations.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/declarations.h new file mode 100644 index 000000000..e6c552c39 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/declarations.h @@ -0,0 +1,64 @@ +#ifndef IIT_ROBOT_CAMEL_DECLARATIONS_H_ +#define IIT_ROBOT_CAMEL_DECLARATIONS_H_ + +#include + +namespace iit { +namespace camel { + +static const int JointSpaceDimension = 12; +static const int jointsCount = 12; +/** The total number of rigid bodies of this robot, including the base */ +static const int linksCount = 13; + +namespace tpl { +template +using Column12d = iit::rbd::PlainMatrix; + +template +using JointState = Column12d; +} + +using Column12d = tpl::Column12d; +typedef Column12d JointState; + +enum JointIdentifiers { + LF_HAA = 0 + , LF_HFE + , LF_KFE + , RF_HAA + , RF_HFE + , RF_KFE + , LH_HAA + , LH_HFE + , LH_KFE + , RH_HAA + , RH_HFE + , RH_KFE +}; + +enum LinkIdentifiers { + BASE = 0 + , LF_HIP + , LF_THIGH + , LF_SHANK + , RF_HIP + , RF_THIGH + , RF_SHANK + , LH_HIP + , LH_THIGH + , LH_SHANK + , RH_HIP + , RH_THIGH + , RH_SHANK +}; + +static const JointIdentifiers orderedJointIDs[jointsCount] = + {LF_HAA,LF_HFE,LF_KFE,RF_HAA,RF_HFE,RF_KFE,LH_HAA,LH_HFE,LH_KFE,RH_HAA,RH_HFE,RH_KFE}; + +static const LinkIdentifiers orderedLinkIDs[linksCount] = + {BASE,LF_HIP,LF_THIGH,LF_SHANK,RF_HIP,RF_THIGH,RF_SHANK,LH_HIP,LH_THIGH,LH_SHANK,RH_HIP,RH_THIGH,RH_SHANK}; + +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/default_dynparams_getter.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/default_dynparams_getter.h new file mode 100644 index 000000000..8e00f333f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/default_dynparams_getter.h @@ -0,0 +1,30 @@ +#ifndef _CAMEL_DEFAULT_GETTER_INERTIA_PARAMETERS_ +#define _CAMEL_DEFAULT_GETTER_INERTIA_PARAMETERS_ + +#include "dynamics_parameters.h" + +namespace iit { +namespace camel { +namespace dyn { + +class DefaultParamsGetter : public RuntimeParamsGetter +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + DefaultParamsGetter() { + resetDefaults(); + } + ~DefaultParamsGetter() {}; + + public: + void resetDefaults() { + } + + private: + RuntimeInertiaParams values; +}; + +} +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/dynamics_parameters.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/dynamics_parameters.h new file mode 100644 index 000000000..80d009a38 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/dynamics_parameters.h @@ -0,0 +1,43 @@ +#ifndef _CAMEL_RUNTIME_INERTIA_PARAMETERS_ +#define _CAMEL_RUNTIME_INERTIA_PARAMETERS_ + +namespace iit { +namespace camel { +namespace dyn { +/** + * \defgroup dynparams Dynamics-parameters + * Facilities related to the parameters of the inertia properties of the + * robot camel. + * + * Inertia parameters are non-constants used in the robot model, where the + * inertia properties (mass, center of mass, intertia tensor) of the links + * are specified. Since the value of such parameters must be resolved + * at runtime, we sometimes refer to them as "runtime parameters", "runtime + * dynamics parameters", "runtime inertia parameters", etc. + * + * Do not confuse them with the "inertia properties" of links, which + * unfortunately, in the literature, are commonly referred to as + * "inertia parameters"... Here, the parameters are the non-constant + * fields of the inertia properties. + */ + + /** + * A container for the set of non-constant inertia parameters of the robot camel + * \ingroup dynparams + */ + struct RuntimeInertiaParams { + }; + + /** + * The interface for classes that can compute the actual value of the + * non-constant inertia parameters of the robot camel. + * \ingroup dynparams + */ + class RuntimeParamsGetter { + public: + }; + +} +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.h new file mode 100644 index 000000000..4527a05f8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.h @@ -0,0 +1,261 @@ +#ifndef IIT_ROBOT_CAMEL_FORWARD_DYNAMICS_H_ +#define IIT_ROBOT_CAMEL_FORWARD_DYNAMICS_H_ + +#include +#include +#include + +#include "declarations.h" +#include "transforms.h" +#include "inertia_properties.h" +#include "link_data_map.h" + +namespace iit { +namespace camel { +namespace dyn { + +/** + * The Forward Dynamics routine for the robot camel. + * + * The parameters common to most of the methods are the joint status \c q, the + * joint velocities \c qd and the joint forces \c tau. The accelerations \c qdd + * will be filled with the computed values. Overloaded methods without the \c q + * parameter use the current configuration of the robot; they are provided for + * the sake of efficiency, in case the kinematics transforms of the robot have + * already been updated elsewhere with the most recent configuration (eg by a + * call to setJointStatus()), so that it would be useless to compute them again. + */ + +namespace tpl { + +template +class ForwardDynamics { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + // Convenient type aliases: + + typedef typename TRAIT::Scalar Scalar; + + typedef iit::rbd::Core CoreS; + + typedef typename CoreS::ForceVector Force; + typedef typename CoreS::VelocityVector Velocity; + typedef typename CoreS::VelocityVector Acceleration; + typedef typename CoreS::Column6D Column6DS; + typedef typename CoreS::Matrix66 Matrix66S; + typedef LinkDataMap ExtForces; + typedef typename iit::camel::tpl::JointState JointState; + typedef iit::camel::tpl::MotionTransforms MTransforms; + +public: + /** + * Default constructor + * \param in the inertia properties of the links + * \param tr the container of all the spatial motion transforms of + * the robot camel, which will be used by this instance + * to compute the dynamics. + */ + ForwardDynamics(InertiaProperties& in, MTransforms& tr); + /** \name Forward dynamics + * The Articulated-Body-Algorithm to compute the joint accelerations + */ ///@{ + /** + * \param qdd the joint accelerations vector (output parameter). + * \param base_a + * \param base_v + * \param g the gravity acceleration vector, expressed in the + * base coordinates + * \param q the joint status vector + * \param qd the joint velocities vector + * \param tau the joint forces (torque or force) + * \param fext the external forces, optional. Each force must be + * expressed in the reference frame of the link it is + * exerted on. + */ + void fd( + JointState& qdd, Acceleration& base_a, // output parameters, + const Velocity& base_v, const Acceleration& g, + const JointState& q, const JointState& qd, const JointState& tau, const ExtForces& fext = zeroExtForces); + void fd( + JointState& qdd, Acceleration& base_a, // output parameters, + const Velocity& base_v, const Acceleration& g, + const JointState& qd, const JointState& tau, const ExtForces& fext = zeroExtForces); + ///@} + + /** Updates all the kinematics transforms used by this instance. */ + void setJointStatus(const JointState& q) const; + +private: + InertiaProperties* inertiaProps; + MTransforms* motionTransforms; + + Matrix66S vcross; // support variable + Matrix66S Ia_r; // support variable, articulated inertia in the case of a revolute joint + // Link 'base' + Matrix66S base_AI; + Force base_p; + + // Link 'LF_HIP' : + Matrix66S LF_HIP_AI; + Velocity LF_HIP_a; + Velocity LF_HIP_v; + Velocity LF_HIP_c; + Force LF_HIP_p; + + Column6DS LF_HIP_U; + Scalar LF_HIP_D; + Scalar LF_HIP_u; + // Link 'LF_THIGH' : + Matrix66S LF_THIGH_AI; + Velocity LF_THIGH_a; + Velocity LF_THIGH_v; + Velocity LF_THIGH_c; + Force LF_THIGH_p; + + Column6DS LF_THIGH_U; + Scalar LF_THIGH_D; + Scalar LF_THIGH_u; + // Link 'LF_SHANK' : + Matrix66S LF_SHANK_AI; + Velocity LF_SHANK_a; + Velocity LF_SHANK_v; + Velocity LF_SHANK_c; + Force LF_SHANK_p; + + Column6DS LF_SHANK_U; + Scalar LF_SHANK_D; + Scalar LF_SHANK_u; + // Link 'RF_HIP' : + Matrix66S RF_HIP_AI; + Velocity RF_HIP_a; + Velocity RF_HIP_v; + Velocity RF_HIP_c; + Force RF_HIP_p; + + Column6DS RF_HIP_U; + Scalar RF_HIP_D; + Scalar RF_HIP_u; + // Link 'RF_THIGH' : + Matrix66S RF_THIGH_AI; + Velocity RF_THIGH_a; + Velocity RF_THIGH_v; + Velocity RF_THIGH_c; + Force RF_THIGH_p; + + Column6DS RF_THIGH_U; + Scalar RF_THIGH_D; + Scalar RF_THIGH_u; + // Link 'RF_SHANK' : + Matrix66S RF_SHANK_AI; + Velocity RF_SHANK_a; + Velocity RF_SHANK_v; + Velocity RF_SHANK_c; + Force RF_SHANK_p; + + Column6DS RF_SHANK_U; + Scalar RF_SHANK_D; + Scalar RF_SHANK_u; + // Link 'LH_HIP' : + Matrix66S LH_HIP_AI; + Velocity LH_HIP_a; + Velocity LH_HIP_v; + Velocity LH_HIP_c; + Force LH_HIP_p; + + Column6DS LH_HIP_U; + Scalar LH_HIP_D; + Scalar LH_HIP_u; + // Link 'LH_THIGH' : + Matrix66S LH_THIGH_AI; + Velocity LH_THIGH_a; + Velocity LH_THIGH_v; + Velocity LH_THIGH_c; + Force LH_THIGH_p; + + Column6DS LH_THIGH_U; + Scalar LH_THIGH_D; + Scalar LH_THIGH_u; + // Link 'LH_SHANK' : + Matrix66S LH_SHANK_AI; + Velocity LH_SHANK_a; + Velocity LH_SHANK_v; + Velocity LH_SHANK_c; + Force LH_SHANK_p; + + Column6DS LH_SHANK_U; + Scalar LH_SHANK_D; + Scalar LH_SHANK_u; + // Link 'RH_HIP' : + Matrix66S RH_HIP_AI; + Velocity RH_HIP_a; + Velocity RH_HIP_v; + Velocity RH_HIP_c; + Force RH_HIP_p; + + Column6DS RH_HIP_U; + Scalar RH_HIP_D; + Scalar RH_HIP_u; + // Link 'RH_THIGH' : + Matrix66S RH_THIGH_AI; + Velocity RH_THIGH_a; + Velocity RH_THIGH_v; + Velocity RH_THIGH_c; + Force RH_THIGH_p; + + Column6DS RH_THIGH_U; + Scalar RH_THIGH_D; + Scalar RH_THIGH_u; + // Link 'RH_SHANK' : + Matrix66S RH_SHANK_AI; + Velocity RH_SHANK_a; + Velocity RH_SHANK_v; + Velocity RH_SHANK_c; + Force RH_SHANK_p; + + Column6DS RH_SHANK_U; + Scalar RH_SHANK_D; + Scalar RH_SHANK_u; +private: + static const ExtForces zeroExtForces; +}; + +template +inline void ForwardDynamics::setJointStatus(const JointState& q) const { + (motionTransforms-> fr_LF_HIP_X_fr_base)(q); + (motionTransforms-> fr_LF_THIGH_X_fr_LF_HIP)(q); + (motionTransforms-> fr_LF_SHANK_X_fr_LF_THIGH)(q); + (motionTransforms-> fr_RF_HIP_X_fr_base)(q); + (motionTransforms-> fr_RF_THIGH_X_fr_RF_HIP)(q); + (motionTransforms-> fr_RF_SHANK_X_fr_RF_THIGH)(q); + (motionTransforms-> fr_LH_HIP_X_fr_base)(q); + (motionTransforms-> fr_LH_THIGH_X_fr_LH_HIP)(q); + (motionTransforms-> fr_LH_SHANK_X_fr_LH_THIGH)(q); + (motionTransforms-> fr_RH_HIP_X_fr_base)(q); + (motionTransforms-> fr_RH_THIGH_X_fr_RH_HIP)(q); + (motionTransforms-> fr_RH_SHANK_X_fr_RH_THIGH)(q); +} + +template +inline void ForwardDynamics::fd( + JointState& qdd, Acceleration& base_a, // output parameters, + const Velocity& base_v, const Acceleration& g, + const JointState& q, + const JointState& qd, + const JointState& tau, + const ExtForces& fext/* = zeroExtForces */) +{ + setJointStatus(q); + fd(qdd, base_a, base_v, g, qd, tau, fext); +} + +} + +typedef tpl::ForwardDynamics ForwardDynamics; + +} +} +} + +#include "forward_dynamics.impl.h" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.impl.h new file mode 100644 index 000000000..da472fcdc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/forward_dynamics.impl.h @@ -0,0 +1,423 @@ + +// Initialization of static-const data +template +const typename iit::camel::dyn::tpl::ForwardDynamics::ExtForces + iit::camel::dyn::tpl::ForwardDynamics::zeroExtForces(Force::Zero()); + +template +iit::camel::dyn::tpl::ForwardDynamics::ForwardDynamics(iit::camel::dyn::tpl::InertiaProperties& inertia, MTransforms& transforms) : + inertiaProps( & inertia ), + motionTransforms( & transforms ) +{ + LF_HIP_v.setZero(); + LF_HIP_c.setZero(); + LF_THIGH_v.setZero(); + LF_THIGH_c.setZero(); + LF_SHANK_v.setZero(); + LF_SHANK_c.setZero(); + RF_HIP_v.setZero(); + RF_HIP_c.setZero(); + RF_THIGH_v.setZero(); + RF_THIGH_c.setZero(); + RF_SHANK_v.setZero(); + RF_SHANK_c.setZero(); + LH_HIP_v.setZero(); + LH_HIP_c.setZero(); + LH_THIGH_v.setZero(); + LH_THIGH_c.setZero(); + LH_SHANK_v.setZero(); + LH_SHANK_c.setZero(); + RH_HIP_v.setZero(); + RH_HIP_c.setZero(); + RH_THIGH_v.setZero(); + RH_THIGH_c.setZero(); + RH_SHANK_v.setZero(); + RH_SHANK_c.setZero(); + + vcross.setZero(); + Ia_r.setZero(); + +} + +template +void iit::camel::dyn::tpl::ForwardDynamics::fd( + JointState& qdd, + Acceleration& base_a, + const Velocity& base_v, + const Acceleration& g, + const JointState& qd, + const JointState& tau, + const ExtForces& fext/* = zeroExtForces */) +{ + + base_AI = inertiaProps->getTensor_base(); + base_p = - fext[BASE]; + LF_HIP_AI = inertiaProps->getTensor_LF_HIP(); + LF_HIP_p = - fext[LF_HIP]; + LF_THIGH_AI = inertiaProps->getTensor_LF_THIGH(); + LF_THIGH_p = - fext[LF_THIGH]; + LF_SHANK_AI = inertiaProps->getTensor_LF_SHANK(); + LF_SHANK_p = - fext[LF_SHANK]; + RF_HIP_AI = inertiaProps->getTensor_RF_HIP(); + RF_HIP_p = - fext[RF_HIP]; + RF_THIGH_AI = inertiaProps->getTensor_RF_THIGH(); + RF_THIGH_p = - fext[RF_THIGH]; + RF_SHANK_AI = inertiaProps->getTensor_RF_SHANK(); + RF_SHANK_p = - fext[RF_SHANK]; + LH_HIP_AI = inertiaProps->getTensor_LH_HIP(); + LH_HIP_p = - fext[LH_HIP]; + LH_THIGH_AI = inertiaProps->getTensor_LH_THIGH(); + LH_THIGH_p = - fext[LH_THIGH]; + LH_SHANK_AI = inertiaProps->getTensor_LH_SHANK(); + LH_SHANK_p = - fext[LH_SHANK]; + RH_HIP_AI = inertiaProps->getTensor_RH_HIP(); + RH_HIP_p = - fext[RH_HIP]; + RH_THIGH_AI = inertiaProps->getTensor_RH_THIGH(); + RH_THIGH_p = - fext[RH_THIGH]; + RH_SHANK_AI = inertiaProps->getTensor_RH_SHANK(); + RH_SHANK_p = - fext[RH_SHANK]; + // ---------------------- FIRST PASS ---------------------- // + // Note that, during the first pass, the articulated inertias are really + // just the spatial inertia of the links (see assignments above). + // Afterwards things change, and articulated inertias shall not be used + // in functions which work specifically with spatial inertias. + + // + Link LF_HIP + // - The spatial velocity: + LF_HIP_v = (motionTransforms-> fr_LF_HIP_X_fr_base) * base_v; + LF_HIP_v(iit::rbd::AZ) += qd(LF_HAA); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LF_HIP_v, vcross); + LF_HIP_c = vcross.col(iit::rbd::AZ) * qd(LF_HAA); + + // - The bias force term: + LF_HIP_p += iit::rbd::vxIv(LF_HIP_v, LF_HIP_AI); + + // + Link LF_THIGH + // - The spatial velocity: + LF_THIGH_v = (motionTransforms-> fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_v; + LF_THIGH_v(iit::rbd::AZ) += qd(LF_HFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LF_THIGH_v, vcross); + LF_THIGH_c = vcross.col(iit::rbd::AZ) * qd(LF_HFE); + + // - The bias force term: + LF_THIGH_p += iit::rbd::vxIv(LF_THIGH_v, LF_THIGH_AI); + + // + Link LF_SHANK + // - The spatial velocity: + LF_SHANK_v = (motionTransforms-> fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_v; + LF_SHANK_v(iit::rbd::AZ) += qd(LF_KFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LF_SHANK_v, vcross); + LF_SHANK_c = vcross.col(iit::rbd::AZ) * qd(LF_KFE); + + // - The bias force term: + LF_SHANK_p += iit::rbd::vxIv(LF_SHANK_v, LF_SHANK_AI); + + // + Link RF_HIP + // - The spatial velocity: + RF_HIP_v = (motionTransforms-> fr_RF_HIP_X_fr_base) * base_v; + RF_HIP_v(iit::rbd::AZ) += qd(RF_HAA); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RF_HIP_v, vcross); + RF_HIP_c = vcross.col(iit::rbd::AZ) * qd(RF_HAA); + + // - The bias force term: + RF_HIP_p += iit::rbd::vxIv(RF_HIP_v, RF_HIP_AI); + + // + Link RF_THIGH + // - The spatial velocity: + RF_THIGH_v = (motionTransforms-> fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_v; + RF_THIGH_v(iit::rbd::AZ) += qd(RF_HFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RF_THIGH_v, vcross); + RF_THIGH_c = vcross.col(iit::rbd::AZ) * qd(RF_HFE); + + // - The bias force term: + RF_THIGH_p += iit::rbd::vxIv(RF_THIGH_v, RF_THIGH_AI); + + // + Link RF_SHANK + // - The spatial velocity: + RF_SHANK_v = (motionTransforms-> fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_v; + RF_SHANK_v(iit::rbd::AZ) += qd(RF_KFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RF_SHANK_v, vcross); + RF_SHANK_c = vcross.col(iit::rbd::AZ) * qd(RF_KFE); + + // - The bias force term: + RF_SHANK_p += iit::rbd::vxIv(RF_SHANK_v, RF_SHANK_AI); + + // + Link LH_HIP + // - The spatial velocity: + LH_HIP_v = (motionTransforms-> fr_LH_HIP_X_fr_base) * base_v; + LH_HIP_v(iit::rbd::AZ) += qd(LH_HAA); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LH_HIP_v, vcross); + LH_HIP_c = vcross.col(iit::rbd::AZ) * qd(LH_HAA); + + // - The bias force term: + LH_HIP_p += iit::rbd::vxIv(LH_HIP_v, LH_HIP_AI); + + // + Link LH_THIGH + // - The spatial velocity: + LH_THIGH_v = (motionTransforms-> fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_v; + LH_THIGH_v(iit::rbd::AZ) += qd(LH_HFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LH_THIGH_v, vcross); + LH_THIGH_c = vcross.col(iit::rbd::AZ) * qd(LH_HFE); + + // - The bias force term: + LH_THIGH_p += iit::rbd::vxIv(LH_THIGH_v, LH_THIGH_AI); + + // + Link LH_SHANK + // - The spatial velocity: + LH_SHANK_v = (motionTransforms-> fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_v; + LH_SHANK_v(iit::rbd::AZ) += qd(LH_KFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(LH_SHANK_v, vcross); + LH_SHANK_c = vcross.col(iit::rbd::AZ) * qd(LH_KFE); + + // - The bias force term: + LH_SHANK_p += iit::rbd::vxIv(LH_SHANK_v, LH_SHANK_AI); + + // + Link RH_HIP + // - The spatial velocity: + RH_HIP_v = (motionTransforms-> fr_RH_HIP_X_fr_base) * base_v; + RH_HIP_v(iit::rbd::AZ) += qd(RH_HAA); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RH_HIP_v, vcross); + RH_HIP_c = vcross.col(iit::rbd::AZ) * qd(RH_HAA); + + // - The bias force term: + RH_HIP_p += iit::rbd::vxIv(RH_HIP_v, RH_HIP_AI); + + // + Link RH_THIGH + // - The spatial velocity: + RH_THIGH_v = (motionTransforms-> fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_v; + RH_THIGH_v(iit::rbd::AZ) += qd(RH_HFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RH_THIGH_v, vcross); + RH_THIGH_c = vcross.col(iit::rbd::AZ) * qd(RH_HFE); + + // - The bias force term: + RH_THIGH_p += iit::rbd::vxIv(RH_THIGH_v, RH_THIGH_AI); + + // + Link RH_SHANK + // - The spatial velocity: + RH_SHANK_v = (motionTransforms-> fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_v; + RH_SHANK_v(iit::rbd::AZ) += qd(RH_KFE); + + // - The velocity-product acceleration term: + iit::rbd::motionCrossProductMx(RH_SHANK_v, vcross); + RH_SHANK_c = vcross.col(iit::rbd::AZ) * qd(RH_KFE); + + // - The bias force term: + RH_SHANK_p += iit::rbd::vxIv(RH_SHANK_v, RH_SHANK_AI); + + // + The floating base body + base_p += iit::rbd::vxIv(base_v, base_AI); + + // ---------------------- SECOND PASS ---------------------- // + Matrix66S IaB; + Force pa; + + // + Link RH_SHANK + RH_SHANK_u = tau(RH_KFE) - RH_SHANK_p(iit::rbd::AZ); + RH_SHANK_U = RH_SHANK_AI.col(iit::rbd::AZ); + RH_SHANK_D = RH_SHANK_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RH_SHANK_AI, RH_SHANK_U, RH_SHANK_D, Ia_r); // same as: Ia_r = RH_SHANK_AI - RH_SHANK_U/RH_SHANK_D * RH_SHANK_U.transpose(); + pa = RH_SHANK_p + Ia_r * RH_SHANK_c + RH_SHANK_U * RH_SHANK_u/RH_SHANK_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RH_SHANK_X_fr_RH_THIGH, IaB); + RH_THIGH_AI += IaB; + RH_THIGH_p += (motionTransforms-> fr_RH_SHANK_X_fr_RH_THIGH).transpose() * pa; + + // + Link RH_THIGH + RH_THIGH_u = tau(RH_HFE) - RH_THIGH_p(iit::rbd::AZ); + RH_THIGH_U = RH_THIGH_AI.col(iit::rbd::AZ); + RH_THIGH_D = RH_THIGH_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RH_THIGH_AI, RH_THIGH_U, RH_THIGH_D, Ia_r); // same as: Ia_r = RH_THIGH_AI - RH_THIGH_U/RH_THIGH_D * RH_THIGH_U.transpose(); + pa = RH_THIGH_p + Ia_r * RH_THIGH_c + RH_THIGH_U * RH_THIGH_u/RH_THIGH_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RH_THIGH_X_fr_RH_HIP, IaB); + RH_HIP_AI += IaB; + RH_HIP_p += (motionTransforms-> fr_RH_THIGH_X_fr_RH_HIP).transpose() * pa; + + // + Link RH_HIP + RH_HIP_u = tau(RH_HAA) - RH_HIP_p(iit::rbd::AZ); + RH_HIP_U = RH_HIP_AI.col(iit::rbd::AZ); + RH_HIP_D = RH_HIP_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RH_HIP_AI, RH_HIP_U, RH_HIP_D, Ia_r); // same as: Ia_r = RH_HIP_AI - RH_HIP_U/RH_HIP_D * RH_HIP_U.transpose(); + pa = RH_HIP_p + Ia_r * RH_HIP_c + RH_HIP_U * RH_HIP_u/RH_HIP_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RH_HIP_X_fr_base, IaB); + base_AI += IaB; + base_p += (motionTransforms-> fr_RH_HIP_X_fr_base).transpose() * pa; + + // + Link LH_SHANK + LH_SHANK_u = tau(LH_KFE) - LH_SHANK_p(iit::rbd::AZ); + LH_SHANK_U = LH_SHANK_AI.col(iit::rbd::AZ); + LH_SHANK_D = LH_SHANK_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LH_SHANK_AI, LH_SHANK_U, LH_SHANK_D, Ia_r); // same as: Ia_r = LH_SHANK_AI - LH_SHANK_U/LH_SHANK_D * LH_SHANK_U.transpose(); + pa = LH_SHANK_p + Ia_r * LH_SHANK_c + LH_SHANK_U * LH_SHANK_u/LH_SHANK_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LH_SHANK_X_fr_LH_THIGH, IaB); + LH_THIGH_AI += IaB; + LH_THIGH_p += (motionTransforms-> fr_LH_SHANK_X_fr_LH_THIGH).transpose() * pa; + + // + Link LH_THIGH + LH_THIGH_u = tau(LH_HFE) - LH_THIGH_p(iit::rbd::AZ); + LH_THIGH_U = LH_THIGH_AI.col(iit::rbd::AZ); + LH_THIGH_D = LH_THIGH_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LH_THIGH_AI, LH_THIGH_U, LH_THIGH_D, Ia_r); // same as: Ia_r = LH_THIGH_AI - LH_THIGH_U/LH_THIGH_D * LH_THIGH_U.transpose(); + pa = LH_THIGH_p + Ia_r * LH_THIGH_c + LH_THIGH_U * LH_THIGH_u/LH_THIGH_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LH_THIGH_X_fr_LH_HIP, IaB); + LH_HIP_AI += IaB; + LH_HIP_p += (motionTransforms-> fr_LH_THIGH_X_fr_LH_HIP).transpose() * pa; + + // + Link LH_HIP + LH_HIP_u = tau(LH_HAA) - LH_HIP_p(iit::rbd::AZ); + LH_HIP_U = LH_HIP_AI.col(iit::rbd::AZ); + LH_HIP_D = LH_HIP_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LH_HIP_AI, LH_HIP_U, LH_HIP_D, Ia_r); // same as: Ia_r = LH_HIP_AI - LH_HIP_U/LH_HIP_D * LH_HIP_U.transpose(); + pa = LH_HIP_p + Ia_r * LH_HIP_c + LH_HIP_U * LH_HIP_u/LH_HIP_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LH_HIP_X_fr_base, IaB); + base_AI += IaB; + base_p += (motionTransforms-> fr_LH_HIP_X_fr_base).transpose() * pa; + + // + Link RF_SHANK + RF_SHANK_u = tau(RF_KFE) - RF_SHANK_p(iit::rbd::AZ); + RF_SHANK_U = RF_SHANK_AI.col(iit::rbd::AZ); + RF_SHANK_D = RF_SHANK_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RF_SHANK_AI, RF_SHANK_U, RF_SHANK_D, Ia_r); // same as: Ia_r = RF_SHANK_AI - RF_SHANK_U/RF_SHANK_D * RF_SHANK_U.transpose(); + pa = RF_SHANK_p + Ia_r * RF_SHANK_c + RF_SHANK_U * RF_SHANK_u/RF_SHANK_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RF_SHANK_X_fr_RF_THIGH, IaB); + RF_THIGH_AI += IaB; + RF_THIGH_p += (motionTransforms-> fr_RF_SHANK_X_fr_RF_THIGH).transpose() * pa; + + // + Link RF_THIGH + RF_THIGH_u = tau(RF_HFE) - RF_THIGH_p(iit::rbd::AZ); + RF_THIGH_U = RF_THIGH_AI.col(iit::rbd::AZ); + RF_THIGH_D = RF_THIGH_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RF_THIGH_AI, RF_THIGH_U, RF_THIGH_D, Ia_r); // same as: Ia_r = RF_THIGH_AI - RF_THIGH_U/RF_THIGH_D * RF_THIGH_U.transpose(); + pa = RF_THIGH_p + Ia_r * RF_THIGH_c + RF_THIGH_U * RF_THIGH_u/RF_THIGH_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RF_THIGH_X_fr_RF_HIP, IaB); + RF_HIP_AI += IaB; + RF_HIP_p += (motionTransforms-> fr_RF_THIGH_X_fr_RF_HIP).transpose() * pa; + + // + Link RF_HIP + RF_HIP_u = tau(RF_HAA) - RF_HIP_p(iit::rbd::AZ); + RF_HIP_U = RF_HIP_AI.col(iit::rbd::AZ); + RF_HIP_D = RF_HIP_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(RF_HIP_AI, RF_HIP_U, RF_HIP_D, Ia_r); // same as: Ia_r = RF_HIP_AI - RF_HIP_U/RF_HIP_D * RF_HIP_U.transpose(); + pa = RF_HIP_p + Ia_r * RF_HIP_c + RF_HIP_U * RF_HIP_u/RF_HIP_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_RF_HIP_X_fr_base, IaB); + base_AI += IaB; + base_p += (motionTransforms-> fr_RF_HIP_X_fr_base).transpose() * pa; + + // + Link LF_SHANK + LF_SHANK_u = tau(LF_KFE) - LF_SHANK_p(iit::rbd::AZ); + LF_SHANK_U = LF_SHANK_AI.col(iit::rbd::AZ); + LF_SHANK_D = LF_SHANK_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LF_SHANK_AI, LF_SHANK_U, LF_SHANK_D, Ia_r); // same as: Ia_r = LF_SHANK_AI - LF_SHANK_U/LF_SHANK_D * LF_SHANK_U.transpose(); + pa = LF_SHANK_p + Ia_r * LF_SHANK_c + LF_SHANK_U * LF_SHANK_u/LF_SHANK_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LF_SHANK_X_fr_LF_THIGH, IaB); + LF_THIGH_AI += IaB; + LF_THIGH_p += (motionTransforms-> fr_LF_SHANK_X_fr_LF_THIGH).transpose() * pa; + + // + Link LF_THIGH + LF_THIGH_u = tau(LF_HFE) - LF_THIGH_p(iit::rbd::AZ); + LF_THIGH_U = LF_THIGH_AI.col(iit::rbd::AZ); + LF_THIGH_D = LF_THIGH_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LF_THIGH_AI, LF_THIGH_U, LF_THIGH_D, Ia_r); // same as: Ia_r = LF_THIGH_AI - LF_THIGH_U/LF_THIGH_D * LF_THIGH_U.transpose(); + pa = LF_THIGH_p + Ia_r * LF_THIGH_c + LF_THIGH_U * LF_THIGH_u/LF_THIGH_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LF_THIGH_X_fr_LF_HIP, IaB); + LF_HIP_AI += IaB; + LF_HIP_p += (motionTransforms-> fr_LF_THIGH_X_fr_LF_HIP).transpose() * pa; + + // + Link LF_HIP + LF_HIP_u = tau(LF_HAA) - LF_HIP_p(iit::rbd::AZ); + LF_HIP_U = LF_HIP_AI.col(iit::rbd::AZ); + LF_HIP_D = LF_HIP_U(iit::rbd::AZ); + + iit::rbd::compute_Ia_revolute(LF_HIP_AI, LF_HIP_U, LF_HIP_D, Ia_r); // same as: Ia_r = LF_HIP_AI - LF_HIP_U/LF_HIP_D * LF_HIP_U.transpose(); + pa = LF_HIP_p + Ia_r * LF_HIP_c + LF_HIP_U * LF_HIP_u/LF_HIP_D; + ctransform_Ia_revolute(Ia_r, motionTransforms-> fr_LF_HIP_X_fr_base, IaB); + base_AI += IaB; + base_p += (motionTransforms-> fr_LF_HIP_X_fr_base).transpose() * pa; + + // + The acceleration of the floating base base, without gravity + base_a = - TRAIT::solve(base_AI, base_p); // base_a = - IA^-1 * base_p + + // ---------------------- THIRD PASS ---------------------- // + LF_HIP_a = (motionTransforms-> fr_LF_HIP_X_fr_base) * base_a + LF_HIP_c; + qdd(LF_HAA) = (LF_HIP_u - LF_HIP_U.dot(LF_HIP_a)) / LF_HIP_D; + LF_HIP_a(iit::rbd::AZ) += qdd(LF_HAA); + + LF_THIGH_a = (motionTransforms-> fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_a + LF_THIGH_c; + qdd(LF_HFE) = (LF_THIGH_u - LF_THIGH_U.dot(LF_THIGH_a)) / LF_THIGH_D; + LF_THIGH_a(iit::rbd::AZ) += qdd(LF_HFE); + + LF_SHANK_a = (motionTransforms-> fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_a + LF_SHANK_c; + qdd(LF_KFE) = (LF_SHANK_u - LF_SHANK_U.dot(LF_SHANK_a)) / LF_SHANK_D; + LF_SHANK_a(iit::rbd::AZ) += qdd(LF_KFE); + + RF_HIP_a = (motionTransforms-> fr_RF_HIP_X_fr_base) * base_a + RF_HIP_c; + qdd(RF_HAA) = (RF_HIP_u - RF_HIP_U.dot(RF_HIP_a)) / RF_HIP_D; + RF_HIP_a(iit::rbd::AZ) += qdd(RF_HAA); + + RF_THIGH_a = (motionTransforms-> fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_a + RF_THIGH_c; + qdd(RF_HFE) = (RF_THIGH_u - RF_THIGH_U.dot(RF_THIGH_a)) / RF_THIGH_D; + RF_THIGH_a(iit::rbd::AZ) += qdd(RF_HFE); + + RF_SHANK_a = (motionTransforms-> fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_a + RF_SHANK_c; + qdd(RF_KFE) = (RF_SHANK_u - RF_SHANK_U.dot(RF_SHANK_a)) / RF_SHANK_D; + RF_SHANK_a(iit::rbd::AZ) += qdd(RF_KFE); + + LH_HIP_a = (motionTransforms-> fr_LH_HIP_X_fr_base) * base_a + LH_HIP_c; + qdd(LH_HAA) = (LH_HIP_u - LH_HIP_U.dot(LH_HIP_a)) / LH_HIP_D; + LH_HIP_a(iit::rbd::AZ) += qdd(LH_HAA); + + LH_THIGH_a = (motionTransforms-> fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_a + LH_THIGH_c; + qdd(LH_HFE) = (LH_THIGH_u - LH_THIGH_U.dot(LH_THIGH_a)) / LH_THIGH_D; + LH_THIGH_a(iit::rbd::AZ) += qdd(LH_HFE); + + LH_SHANK_a = (motionTransforms-> fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_a + LH_SHANK_c; + qdd(LH_KFE) = (LH_SHANK_u - LH_SHANK_U.dot(LH_SHANK_a)) / LH_SHANK_D; + LH_SHANK_a(iit::rbd::AZ) += qdd(LH_KFE); + + RH_HIP_a = (motionTransforms-> fr_RH_HIP_X_fr_base) * base_a + RH_HIP_c; + qdd(RH_HAA) = (RH_HIP_u - RH_HIP_U.dot(RH_HIP_a)) / RH_HIP_D; + RH_HIP_a(iit::rbd::AZ) += qdd(RH_HAA); + + RH_THIGH_a = (motionTransforms-> fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_a + RH_THIGH_c; + qdd(RH_HFE) = (RH_THIGH_u - RH_THIGH_U.dot(RH_THIGH_a)) / RH_THIGH_D; + RH_THIGH_a(iit::rbd::AZ) += qdd(RH_HFE); + + RH_SHANK_a = (motionTransforms-> fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_a + RH_SHANK_c; + qdd(RH_KFE) = (RH_SHANK_u - RH_SHANK_U.dot(RH_SHANK_a)) / RH_SHANK_D; + RH_SHANK_a(iit::rbd::AZ) += qdd(RH_KFE); + + + // + Add gravity to the acceleration of the floating base + base_a += g; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.h new file mode 100644 index 000000000..1e007abc2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.h @@ -0,0 +1,281 @@ +#ifndef IIT_ROBOT_CAMEL_INERTIA_PROPERTIES_H_ +#define IIT_ROBOT_CAMEL_INERTIA_PROPERTIES_H_ + +#include +#include +#include +#include + +#include "declarations.h" + +namespace iit { +namespace camel { +/** + * This namespace encloses classes and functions related to the Dynamics + * of the robot camel. + */ +namespace dyn { + +using InertiaMatrix = iit::rbd::InertiaMatrixDense; + +namespace tpl { + +template +class InertiaProperties { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename TRAIT::Scalar Scalar; + typedef iit::rbd::Core CoreS; + typedef iit::rbd::tpl::InertiaMatrixDense IMatrix; + typedef typename CoreS::Vector3 Vec3d; + + InertiaProperties(); + ~InertiaProperties(); + const IMatrix& getTensor_base() const; + const IMatrix& getTensor_LF_HIP() const; + const IMatrix& getTensor_LF_THIGH() const; + const IMatrix& getTensor_LF_SHANK() const; + const IMatrix& getTensor_RF_HIP() const; + const IMatrix& getTensor_RF_THIGH() const; + const IMatrix& getTensor_RF_SHANK() const; + const IMatrix& getTensor_LH_HIP() const; + const IMatrix& getTensor_LH_THIGH() const; + const IMatrix& getTensor_LH_SHANK() const; + const IMatrix& getTensor_RH_HIP() const; + const IMatrix& getTensor_RH_THIGH() const; + const IMatrix& getTensor_RH_SHANK() const; + Scalar getMass_base() const; + Scalar getMass_LF_HIP() const; + Scalar getMass_LF_THIGH() const; + Scalar getMass_LF_SHANK() const; + Scalar getMass_RF_HIP() const; + Scalar getMass_RF_THIGH() const; + Scalar getMass_RF_SHANK() const; + Scalar getMass_LH_HIP() const; + Scalar getMass_LH_THIGH() const; + Scalar getMass_LH_SHANK() const; + Scalar getMass_RH_HIP() const; + Scalar getMass_RH_THIGH() const; + Scalar getMass_RH_SHANK() const; + const Vec3d& getCOM_base() const; + const Vec3d& getCOM_LF_HIP() const; + const Vec3d& getCOM_LF_THIGH() const; + const Vec3d& getCOM_LF_SHANK() const; + const Vec3d& getCOM_RF_HIP() const; + const Vec3d& getCOM_RF_THIGH() const; + const Vec3d& getCOM_RF_SHANK() const; + const Vec3d& getCOM_LH_HIP() const; + const Vec3d& getCOM_LH_THIGH() const; + const Vec3d& getCOM_LH_SHANK() const; + const Vec3d& getCOM_RH_HIP() const; + const Vec3d& getCOM_RH_THIGH() const; + const Vec3d& getCOM_RH_SHANK() const; + Scalar getTotalMass() const; + + private: + + IMatrix tensor_base; + IMatrix tensor_LF_HIP; + IMatrix tensor_LF_THIGH; + IMatrix tensor_LF_SHANK; + IMatrix tensor_RF_HIP; + IMatrix tensor_RF_THIGH; + IMatrix tensor_RF_SHANK; + IMatrix tensor_LH_HIP; + IMatrix tensor_LH_THIGH; + IMatrix tensor_LH_SHANK; + IMatrix tensor_RH_HIP; + IMatrix tensor_RH_THIGH; + IMatrix tensor_RH_SHANK; + Vec3d com_base; + Vec3d com_LF_HIP; + Vec3d com_LF_THIGH; + Vec3d com_LF_SHANK; + Vec3d com_RF_HIP; + Vec3d com_RF_THIGH; + Vec3d com_RF_SHANK; + Vec3d com_LH_HIP; + Vec3d com_LH_THIGH; + Vec3d com_LH_SHANK; + Vec3d com_RH_HIP; + Vec3d com_RH_THIGH; + Vec3d com_RH_SHANK; +}; + +template +inline InertiaProperties::~InertiaProperties() {} + +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_base() const { + return this->tensor_base; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LF_HIP() const { + return this->tensor_LF_HIP; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LF_THIGH() const { + return this->tensor_LF_THIGH; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LF_SHANK() const { + return this->tensor_LF_SHANK; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RF_HIP() const { + return this->tensor_RF_HIP; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RF_THIGH() const { + return this->tensor_RF_THIGH; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RF_SHANK() const { + return this->tensor_RF_SHANK; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LH_HIP() const { + return this->tensor_LH_HIP; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LH_THIGH() const { + return this->tensor_LH_THIGH; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_LH_SHANK() const { + return this->tensor_LH_SHANK; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RH_HIP() const { + return this->tensor_RH_HIP; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RH_THIGH() const { + return this->tensor_RH_THIGH; +} +template +inline const typename InertiaProperties::IMatrix& InertiaProperties::getTensor_RH_SHANK() const { + return this->tensor_RH_SHANK; +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_base() const { + return this->tensor_base.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LF_HIP() const { + return this->tensor_LF_HIP.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LF_THIGH() const { + return this->tensor_LF_THIGH.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LF_SHANK() const { + return this->tensor_LF_SHANK.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RF_HIP() const { + return this->tensor_RF_HIP.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RF_THIGH() const { + return this->tensor_RF_THIGH.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RF_SHANK() const { + return this->tensor_RF_SHANK.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LH_HIP() const { + return this->tensor_LH_HIP.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LH_THIGH() const { + return this->tensor_LH_THIGH.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_LH_SHANK() const { + return this->tensor_LH_SHANK.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RH_HIP() const { + return this->tensor_RH_HIP.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RH_THIGH() const { + return this->tensor_RH_THIGH.getMass(); +} +template +inline typename InertiaProperties::Scalar InertiaProperties::getMass_RH_SHANK() const { + return this->tensor_RH_SHANK.getMass(); +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_base() const { + return this->com_base; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LF_HIP() const { + return this->com_LF_HIP; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LF_THIGH() const { + return this->com_LF_THIGH; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LF_SHANK() const { + return this->com_LF_SHANK; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RF_HIP() const { + return this->com_RF_HIP; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RF_THIGH() const { + return this->com_RF_THIGH; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RF_SHANK() const { + return this->com_RF_SHANK; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LH_HIP() const { + return this->com_LH_HIP; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LH_THIGH() const { + return this->com_LH_THIGH; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_LH_SHANK() const { + return this->com_LH_SHANK; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RH_HIP() const { + return this->com_RH_HIP; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RH_THIGH() const { + return this->com_RH_THIGH; +} +template +inline const typename InertiaProperties::Vec3d& InertiaProperties::getCOM_RH_SHANK() const { + return this->com_RH_SHANK; +} + +template +inline typename InertiaProperties::Scalar InertiaProperties::getTotalMass() const { + return Scalar(26.499758 + 2.781 + 3.071 + 0.58842 + 2.781 + 3.071 + 0.58842 + 2.781 + 3.071 + 0.58842 + 2.781 + 3.071 + 0.58842); +} + +} + +using InertiaProperties = tpl::InertiaProperties; + +} +} +} + +#include "inertia_properties.impl.h" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.impl.h new file mode 100644 index 000000000..af0f58a1d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inertia_properties.impl.h @@ -0,0 +1,161 @@ +template +iit::camel::dyn::tpl::InertiaProperties::InertiaProperties() +{ + com_base = iit::rbd::Vector3d(-0.013955938,-1.8214522E-4,0.008853551).cast(); + tensor_base.fill( + Scalar(26.499758), + com_base, + rbd::Utils::buildInertiaTensor( + Scalar(0.22784324), + Scalar(1.7974265), + Scalar(1.8366772), + Scalar(-0.008108853), + Scalar(-0.041152608), + Scalar(0.0011102436)) ); + + com_LF_HIP = iit::rbd::Vector3d(4.608417E-4,0.017393887,0.056660626).cast(); + tensor_LF_HIP.fill( + Scalar(2.781), + com_LF_HIP, + rbd::Utils::buildInertiaTensor( + Scalar(0.015602534), + Scalar(0.013867088), + Scalar(0.004137501), + Scalar(1.5809995E-4), + Scalar(-2.5296624E-5), + Scalar(0.0027853446)) ); + + com_LF_THIGH = iit::rbd::Vector3d(-4.649951E-5,0.24569574,0.030814718).cast(); + tensor_LF_THIGH.fill( + Scalar(3.071), + com_LF_THIGH, + rbd::Utils::buildInertiaTensor( + Scalar(0.21820532), + Scalar(0.0077771503), + Scalar(0.21494901), + Scalar(-1.295655E-4), + Scalar(3.989154E-5), + Scalar(0.027393108)) ); + + com_LF_SHANK = iit::rbd::Vector3d(0.06125277,0.080659784,0.0054619997).cast(); + tensor_LF_SHANK.fill( + Scalar(0.58842), + com_LF_SHANK, + rbd::Utils::buildInertiaTensor( + Scalar(0.012656195), + Scalar(0.0037750325), + Scalar(0.016197097), + Scalar(0.004726522), + Scalar(1.4329211E-4), + Scalar(2.3657648E-4)) ); + + com_RF_HIP = iit::rbd::Vector3d(4.608417E-4,-0.017393887,0.05676332).cast(); + tensor_RF_HIP.fill( + Scalar(2.781), + com_RF_HIP, + rbd::Utils::buildInertiaTensor( + Scalar(0.015636748), + Scalar(0.013901301), + Scalar(0.004137501), + Scalar(-1.5810088E-4), + Scalar(1.7275191E-4), + Scalar(-0.002700748)) ); + + com_RF_THIGH = iit::rbd::Vector3d(4.649951E-5,0.24569574,-0.030814718).cast(); + tensor_RF_THIGH.fill( + Scalar(3.071), + com_RF_THIGH, + rbd::Utils::buildInertiaTensor( + Scalar(0.21820532), + Scalar(0.00777715), + Scalar(0.21494901), + Scalar(1.4987914E-4), + Scalar(3.9995582E-5), + Scalar(-0.027393105)) ); + + com_RF_SHANK = iit::rbd::Vector3d(0.06125277,0.080659784,-0.005461999).cast(); + tensor_RF_SHANK.fill( + Scalar(0.58842), + com_RF_SHANK, + rbd::Utils::buildInertiaTensor( + Scalar(0.012656195), + Scalar(0.0037750327), + Scalar(0.016197097), + Scalar(0.004726522), + Scalar(-1.4329197E-4), + Scalar(-2.3657575E-4)) ); + + com_LH_HIP = iit::rbd::Vector3d(4.6084123E-4,0.017393887,-0.05676332).cast(); + tensor_LH_HIP.fill( + Scalar(2.781), + com_LH_HIP, + rbd::Utils::buildInertiaTensor( + Scalar(0.015636746), + Scalar(0.013901301), + Scalar(0.004137501), + Scalar(1.58101E-4), + Scalar(-1.7275206E-4), + Scalar(-0.0027007482)) ); + + com_LH_THIGH = iit::rbd::Vector3d(-4.649951E-5,0.24569574,0.030814718).cast(); + tensor_LH_THIGH.fill( + Scalar(3.071), + com_LH_THIGH, + rbd::Utils::buildInertiaTensor( + Scalar(0.21820532), + Scalar(0.0077771503), + Scalar(0.21494901), + Scalar(-1.4987949E-4), + Scalar(3.9995542E-5), + Scalar(0.027393108)) ); + + com_LH_SHANK = iit::rbd::Vector3d(-0.06125277,0.080659784,0.005461999).cast(); + tensor_LH_SHANK.fill( + Scalar(0.58842), + com_LH_SHANK, + rbd::Utils::buildInertiaTensor( + Scalar(0.012656195), + Scalar(0.0037750327), + Scalar(0.016197097), + Scalar(-0.004726522), + Scalar(-1.4329198E-4), + Scalar(2.3657634E-4)) ); + + com_RH_HIP = iit::rbd::Vector3d(4.6084123E-4,-0.017393887,-0.056660626).cast(); + tensor_RH_HIP.fill( + Scalar(2.781), + com_RH_HIP, + rbd::Utils::buildInertiaTensor( + Scalar(0.015602534), + Scalar(0.013867087), + Scalar(0.004137501), + Scalar(-1.5810053E-4), + Scalar(2.5296595E-5), + Scalar(0.0027853448)) ); + + com_RH_THIGH = iit::rbd::Vector3d(4.649951E-5,0.24569574,-0.030814718).cast(); + tensor_RH_THIGH.fill( + Scalar(3.071), + com_RH_THIGH, + rbd::Utils::buildInertiaTensor( + Scalar(0.21820532), + Scalar(0.00777715), + Scalar(0.21494901), + Scalar(1.2956513E-4), + Scalar(3.989158E-5), + Scalar(-0.027393105)) ); + + com_RH_SHANK = iit::rbd::Vector3d(-0.06125277,0.080659784,-0.0054619987).cast(); + tensor_RH_SHANK.fill( + Scalar(0.58842), + com_RH_SHANK, + rbd::Utils::buildInertiaTensor( + Scalar(0.012656195), + Scalar(0.0037750327), + Scalar(0.016197097), + Scalar(-0.004726522), + Scalar(1.4329182E-4), + Scalar(-2.3657558E-4)) ); + +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.h new file mode 100644 index 000000000..973b4b9dc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.h @@ -0,0 +1,373 @@ +#ifndef IIT_CAMEL_INVERSE_DYNAMICS_H_ +#define IIT_CAMEL_INVERSE_DYNAMICS_H_ + +#include +#include +#include +#include +#include + +#include "declarations.h" +#include "inertia_properties.h" +#include "transforms.h" +#include "link_data_map.h" + +namespace iit { +namespace camel { +namespace dyn { + +/** + * The Inverse Dynamics routine for the robot camel. + * + * In addition to the full Newton-Euler algorithm, specialized versions to compute + * only certain terms are provided. + * The parameters common to most of the methods are the joint status vector \c q, the + * joint velocity vector \c qd and the acceleration vector \c qdd. + * + * Additional overloaded methods are provided without the \c q parameter. These + * methods use the current configuration of the robot; they are provided for the + * sake of efficiency, in case the motion transforms of the robot have already + * been updated elsewhere with the most recent configuration (eg by a call to + * setJointStatus()), so that it is useless to compute them again. + * + * Whenever present, the external forces parameter is a set of external + * wrenches acting on the robot links. Each wrench must be expressed in + * the reference frame of the link it is excerted on. + */ + +namespace tpl { + +template +class InverseDynamics { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename TRAIT::Scalar Scalar; + + typedef iit::rbd::Core CoreS; + + typedef typename CoreS::ForceVector Force; + typedef typename CoreS::VelocityVector Velocity; + typedef typename CoreS::VelocityVector Acceleration; + typedef typename CoreS::Matrix66 Matrix66s; + typedef iit::rbd::tpl::InertiaMatrixDense InertiaMatrix; + typedef iit::camel::tpl::JointState JointState; + typedef LinkDataMap ExtForces; + typedef iit::camel::tpl::MotionTransforms MTransforms; + typedef InertiaProperties IProperties; + +public: + /** + * Default constructor + * \param in the inertia properties of the links + * \param tr the container of all the spatial motion transforms of + * the robot camel, which will be used by this instance + * to compute inverse-dynamics. + */ + InverseDynamics(IProperties& in, MTransforms& tr); + + /** \name Inverse dynamics + * The full algorithm for the inverse dynamics of this robot. + * + * All the spatial vectors in the parameters are expressed in base coordinates, + * besides the external forces: each force must be expressed in the reference + * frame of the link it is acting on. + * \param[out] jForces the joint force vector required to achieve the desired accelerations + * \param[out] baseAccel the spatial acceleration of the robot base + * \param[in] g the gravity acceleration, as a spatial vector; + * gravity implicitly specifies the orientation of the base in space + * \param[in] base_v the spatial velocity of the base + * \param[in] q the joint position vector + * \param[in] qd the joint velocity vector + * \param[in] qdd the desired joint acceleration vector + * \param[in] fext the external forces acting on the links; this parameters + * defaults to zero + */ ///@{ + void id( + JointState& jForces, Acceleration& base_a, + const Acceleration& g, const Velocity& base_v, + const JointState& q, const JointState& qd, const JointState& qdd, + const ExtForces& fext = zeroExtForces); + void id( + JointState& jForces, Acceleration& base_a, + const Acceleration& g, const Velocity& base_v, + const JointState& qd, const JointState& qdd, + const ExtForces& fext = zeroExtForces); + ///@} + /** \name Inverse dynamics, fully actuated base + * The inverse dynamics algorithm for the floating base robot, + * in the assumption of a fully actuated base. + * + * All the spatial vectors in the parameters are expressed in base coordinates, + * besides the external forces: each force must be expressed in the reference + * frame of the link it is acting on. + * \param[out] baseWrench the spatial force to be applied to the robot base to achieve + * the desired accelerations + * \param[out] jForces the joint force vector required to achieve the desired accelerations + * \param[in] g the gravity acceleration, as a spatial vector; + * gravity implicitly specifies the orientation of the base in space + * \param[in] base_v the spatial velocity of the base + * \param[in] baseAccel the desired spatial acceleration of the robot base + * \param[in] q the joint position vector + * \param[in] qd the joint velocity vector + * \param[in] qdd the desired joint acceleration vector + * \param[in] fext the external forces acting on the links; this parameters + * defaults to zero + */ ///@{ + void id_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const Velocity& base_v, const Acceleration& baseAccel, + const JointState& q, const JointState& qd, const JointState& qdd, const ExtForces& fext = zeroExtForces); + void id_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const Velocity& base_v, const Acceleration& baseAccel, + const JointState& qd, const JointState& qdd, const ExtForces& fext = zeroExtForces); + ///@} + /** \name Gravity terms, fully actuated base + */ + ///@{ + void G_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const JointState& q); + void G_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g); + ///@} + /** \name Centrifugal and Coriolis terms, fully actuated base + * + * These functions take only velocity inputs, that is, they assume + * a zero spatial acceleration of the base (in addition to zero acceleration + * at the actuated joints). + * Note that this is NOT the same as imposing zero acceleration + * at the virtual 6-dof-floting-base joint, which would result, in general, + * in a non-zero spatial acceleration of the base, due to velocity + * product terms. + */ + ///@{ + void C_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Velocity& base_v, const JointState& q, const JointState& qd); + void C_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Velocity& base_v, const JointState& qd); + ///@} + /** Updates all the kinematics transforms used by the inverse dynamics routine. */ + void setJointStatus(const JointState& q) const; + +public: + /** \name Getters + * These functions return various spatial quantities used internally + * by the inverse dynamics routines, like the spatial acceleration + * of the links. + * + * The getters can be useful to retrieve the additional data that is not + * returned explicitly by the inverse dynamics routines even though it + * is computed. For example, after a call to the inverse dynamics, + * the spatial velocity of all the links has been determined and + * can be accessed. + * + * However, beware that certain routines might not use some of the + * spatial quantities, which therefore would retain their last value + * without being updated nor reset (for example, the spatial velocity + * of the links is unaffected by the computation of the gravity terms). + */ + ///@{ + const Force& getForce_base() const { return base_f; } + const Velocity& getVelocity_LF_HIP() const { return LF_HIP_v; } + const Acceleration& getAcceleration_LF_HIP() const { return LF_HIP_a; } + const Force& getForce_LF_HIP() const { return LF_HIP_f; } + const Velocity& getVelocity_LF_THIGH() const { return LF_THIGH_v; } + const Acceleration& getAcceleration_LF_THIGH() const { return LF_THIGH_a; } + const Force& getForce_LF_THIGH() const { return LF_THIGH_f; } + const Velocity& getVelocity_LF_SHANK() const { return LF_SHANK_v; } + const Acceleration& getAcceleration_LF_SHANK() const { return LF_SHANK_a; } + const Force& getForce_LF_SHANK() const { return LF_SHANK_f; } + const Velocity& getVelocity_RF_HIP() const { return RF_HIP_v; } + const Acceleration& getAcceleration_RF_HIP() const { return RF_HIP_a; } + const Force& getForce_RF_HIP() const { return RF_HIP_f; } + const Velocity& getVelocity_RF_THIGH() const { return RF_THIGH_v; } + const Acceleration& getAcceleration_RF_THIGH() const { return RF_THIGH_a; } + const Force& getForce_RF_THIGH() const { return RF_THIGH_f; } + const Velocity& getVelocity_RF_SHANK() const { return RF_SHANK_v; } + const Acceleration& getAcceleration_RF_SHANK() const { return RF_SHANK_a; } + const Force& getForce_RF_SHANK() const { return RF_SHANK_f; } + const Velocity& getVelocity_LH_HIP() const { return LH_HIP_v; } + const Acceleration& getAcceleration_LH_HIP() const { return LH_HIP_a; } + const Force& getForce_LH_HIP() const { return LH_HIP_f; } + const Velocity& getVelocity_LH_THIGH() const { return LH_THIGH_v; } + const Acceleration& getAcceleration_LH_THIGH() const { return LH_THIGH_a; } + const Force& getForce_LH_THIGH() const { return LH_THIGH_f; } + const Velocity& getVelocity_LH_SHANK() const { return LH_SHANK_v; } + const Acceleration& getAcceleration_LH_SHANK() const { return LH_SHANK_a; } + const Force& getForce_LH_SHANK() const { return LH_SHANK_f; } + const Velocity& getVelocity_RH_HIP() const { return RH_HIP_v; } + const Acceleration& getAcceleration_RH_HIP() const { return RH_HIP_a; } + const Force& getForce_RH_HIP() const { return RH_HIP_f; } + const Velocity& getVelocity_RH_THIGH() const { return RH_THIGH_v; } + const Acceleration& getAcceleration_RH_THIGH() const { return RH_THIGH_a; } + const Force& getForce_RH_THIGH() const { return RH_THIGH_f; } + const Velocity& getVelocity_RH_SHANK() const { return RH_SHANK_v; } + const Acceleration& getAcceleration_RH_SHANK() const { return RH_SHANK_a; } + const Force& getForce_RH_SHANK() const { return RH_SHANK_f; } + ///@} +protected: + void secondPass_fullyActuated(JointState& jForces); + +private: + IProperties* inertiaProps; + MTransforms* xm; +private: + Matrix66s vcross; // support variable + // Link 'LF_HIP' : + const InertiaMatrix& LF_HIP_I; + Velocity LF_HIP_v; + Acceleration LF_HIP_a; + Force LF_HIP_f; + // Link 'LF_THIGH' : + const InertiaMatrix& LF_THIGH_I; + Velocity LF_THIGH_v; + Acceleration LF_THIGH_a; + Force LF_THIGH_f; + // Link 'LF_SHANK' : + const InertiaMatrix& LF_SHANK_I; + Velocity LF_SHANK_v; + Acceleration LF_SHANK_a; + Force LF_SHANK_f; + // Link 'RF_HIP' : + const InertiaMatrix& RF_HIP_I; + Velocity RF_HIP_v; + Acceleration RF_HIP_a; + Force RF_HIP_f; + // Link 'RF_THIGH' : + const InertiaMatrix& RF_THIGH_I; + Velocity RF_THIGH_v; + Acceleration RF_THIGH_a; + Force RF_THIGH_f; + // Link 'RF_SHANK' : + const InertiaMatrix& RF_SHANK_I; + Velocity RF_SHANK_v; + Acceleration RF_SHANK_a; + Force RF_SHANK_f; + // Link 'LH_HIP' : + const InertiaMatrix& LH_HIP_I; + Velocity LH_HIP_v; + Acceleration LH_HIP_a; + Force LH_HIP_f; + // Link 'LH_THIGH' : + const InertiaMatrix& LH_THIGH_I; + Velocity LH_THIGH_v; + Acceleration LH_THIGH_a; + Force LH_THIGH_f; + // Link 'LH_SHANK' : + const InertiaMatrix& LH_SHANK_I; + Velocity LH_SHANK_v; + Acceleration LH_SHANK_a; + Force LH_SHANK_f; + // Link 'RH_HIP' : + const InertiaMatrix& RH_HIP_I; + Velocity RH_HIP_v; + Acceleration RH_HIP_a; + Force RH_HIP_f; + // Link 'RH_THIGH' : + const InertiaMatrix& RH_THIGH_I; + Velocity RH_THIGH_v; + Acceleration RH_THIGH_a; + Force RH_THIGH_f; + // Link 'RH_SHANK' : + const InertiaMatrix& RH_SHANK_I; + Velocity RH_SHANK_v; + Acceleration RH_SHANK_a; + Force RH_SHANK_f; + + // The robot base + const InertiaMatrix& base_I; + InertiaMatrix base_Ic; + Force base_f; + // The composite inertia tensors + InertiaMatrix LF_HIP_Ic; + InertiaMatrix LF_THIGH_Ic; + const InertiaMatrix& LF_SHANK_Ic; + InertiaMatrix RF_HIP_Ic; + InertiaMatrix RF_THIGH_Ic; + const InertiaMatrix& RF_SHANK_Ic; + InertiaMatrix LH_HIP_Ic; + InertiaMatrix LH_THIGH_Ic; + const InertiaMatrix& LH_SHANK_Ic; + InertiaMatrix RH_HIP_Ic; + InertiaMatrix RH_THIGH_Ic; + const InertiaMatrix& RH_SHANK_Ic; + +private: + static const ExtForces zeroExtForces; +}; + +template +inline void InverseDynamics::setJointStatus(const JointState& q) const +{ + (xm->fr_LF_HIP_X_fr_base)(q); + (xm->fr_LF_THIGH_X_fr_LF_HIP)(q); + (xm->fr_LF_SHANK_X_fr_LF_THIGH)(q); + (xm->fr_RF_HIP_X_fr_base)(q); + (xm->fr_RF_THIGH_X_fr_RF_HIP)(q); + (xm->fr_RF_SHANK_X_fr_RF_THIGH)(q); + (xm->fr_LH_HIP_X_fr_base)(q); + (xm->fr_LH_THIGH_X_fr_LH_HIP)(q); + (xm->fr_LH_SHANK_X_fr_LH_THIGH)(q); + (xm->fr_RH_HIP_X_fr_base)(q); + (xm->fr_RH_THIGH_X_fr_RH_HIP)(q); + (xm->fr_RH_SHANK_X_fr_RH_THIGH)(q); +} + +template +inline void InverseDynamics::id( + JointState& jForces, Acceleration& base_a, + const Acceleration& g, const Velocity& base_v, + const JointState& q, const JointState& qd, const JointState& qdd, + const ExtForces& fext) +{ + setJointStatus(q); + id(jForces, base_a, g, base_v, + qd, qdd, fext); +} + +template +inline void InverseDynamics::G_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const JointState& q) +{ + setJointStatus(q); + G_terms_fully_actuated(baseWrench, jForces, g); +} + +template +inline void InverseDynamics::C_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Velocity& base_v, const JointState& q, const JointState& qd) +{ + setJointStatus(q); + C_terms_fully_actuated(baseWrench, jForces, base_v, qd); +} + +template +inline void InverseDynamics::id_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const Velocity& base_v, const Acceleration& baseAccel, + const JointState& q, const JointState& qd, const JointState& qdd, const ExtForces& fext) +{ + setJointStatus(q); + id_fully_actuated(baseWrench, jForces, g, base_v, + baseAccel, qd, qdd, fext); +} + +} + +typedef tpl::InverseDynamics InverseDynamics; + +} +} + +} + +#include "inverse_dynamics.impl.h" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.impl.h new file mode 100644 index 000000000..108c2c101 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/inverse_dynamics.impl.h @@ -0,0 +1,634 @@ +// Initialization of static-const data +template +const typename iit::camel::dyn::tpl::InverseDynamics::ExtForces +iit::camel::dyn::tpl::InverseDynamics::zeroExtForces(Force::Zero()); + +template +iit::camel::dyn::tpl::InverseDynamics::InverseDynamics(IProperties& inertia, MTransforms& transforms) : + inertiaProps( & inertia ), + xm( & transforms ), + LF_HIP_I(inertiaProps->getTensor_LF_HIP() ), + LF_THIGH_I(inertiaProps->getTensor_LF_THIGH() ), + LF_SHANK_I(inertiaProps->getTensor_LF_SHANK() ), + RF_HIP_I(inertiaProps->getTensor_RF_HIP() ), + RF_THIGH_I(inertiaProps->getTensor_RF_THIGH() ), + RF_SHANK_I(inertiaProps->getTensor_RF_SHANK() ), + LH_HIP_I(inertiaProps->getTensor_LH_HIP() ), + LH_THIGH_I(inertiaProps->getTensor_LH_THIGH() ), + LH_SHANK_I(inertiaProps->getTensor_LH_SHANK() ), + RH_HIP_I(inertiaProps->getTensor_RH_HIP() ), + RH_THIGH_I(inertiaProps->getTensor_RH_THIGH() ), + RH_SHANK_I(inertiaProps->getTensor_RH_SHANK() ) + , + base_I( inertiaProps->getTensor_base() ), + LF_SHANK_Ic(LF_SHANK_I), + RF_SHANK_Ic(RF_SHANK_I), + LH_SHANK_Ic(LH_SHANK_I), + RH_SHANK_Ic(RH_SHANK_I) +{ +#ifndef EIGEN_NO_DEBUG + std::cout << "Robot camel, InverseDynamics::InverseDynamics()" << std::endl; + std::cout << "Compiled with Eigen debug active" << std::endl; +#endif + LF_HIP_v.setZero(); + LF_THIGH_v.setZero(); + LF_SHANK_v.setZero(); + RF_HIP_v.setZero(); + RF_THIGH_v.setZero(); + RF_SHANK_v.setZero(); + LH_HIP_v.setZero(); + LH_THIGH_v.setZero(); + LH_SHANK_v.setZero(); + RH_HIP_v.setZero(); + RH_THIGH_v.setZero(); + RH_SHANK_v.setZero(); + + vcross.setZero(); +} + +template +void iit::camel::dyn::tpl::InverseDynamics::id( + JointState& jForces, Acceleration& base_a, + const Acceleration& g, const Velocity& base_v, + const JointState& qd, const JointState& qdd, + const ExtForces& fext) +{ + base_Ic = base_I; + LF_HIP_Ic = LF_HIP_I; + LF_THIGH_Ic = LF_THIGH_I; + RF_HIP_Ic = RF_HIP_I; + RF_THIGH_Ic = RF_THIGH_I; + LH_HIP_Ic = LH_HIP_I; + LH_THIGH_Ic = LH_THIGH_I; + RH_HIP_Ic = RH_HIP_I; + RH_THIGH_Ic = RH_THIGH_I; + + // First pass, link 'LF_HIP' + LF_HIP_v = ((xm->fr_LF_HIP_X_fr_base) * base_v); + LF_HIP_v(iit::rbd::AZ) += qd(LF_HAA); + + iit::rbd::motionCrossProductMx(LF_HIP_v, vcross); + + LF_HIP_a = (vcross.col(iit::rbd::AZ) * qd(LF_HAA)); + LF_HIP_a(iit::rbd::AZ) += qdd(LF_HAA); + + LF_HIP_f = LF_HIP_I * LF_HIP_a + iit::rbd::vxIv(LF_HIP_v, LF_HIP_I); + + // First pass, link 'LF_THIGH' + LF_THIGH_v = ((xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_v); + LF_THIGH_v(iit::rbd::AZ) += qd(LF_HFE); + + iit::rbd::motionCrossProductMx(LF_THIGH_v, vcross); + + LF_THIGH_a = (xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_a + vcross.col(iit::rbd::AZ) * qd(LF_HFE); + LF_THIGH_a(iit::rbd::AZ) += qdd(LF_HFE); + + LF_THIGH_f = LF_THIGH_I * LF_THIGH_a + iit::rbd::vxIv(LF_THIGH_v, LF_THIGH_I); + + // First pass, link 'LF_SHANK' + LF_SHANK_v = ((xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_v); + LF_SHANK_v(iit::rbd::AZ) += qd(LF_KFE); + + iit::rbd::motionCrossProductMx(LF_SHANK_v, vcross); + + LF_SHANK_a = (xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LF_KFE); + LF_SHANK_a(iit::rbd::AZ) += qdd(LF_KFE); + + LF_SHANK_f = LF_SHANK_I * LF_SHANK_a + iit::rbd::vxIv(LF_SHANK_v, LF_SHANK_I); + + // First pass, link 'RF_HIP' + RF_HIP_v = ((xm->fr_RF_HIP_X_fr_base) * base_v); + RF_HIP_v(iit::rbd::AZ) += qd(RF_HAA); + + iit::rbd::motionCrossProductMx(RF_HIP_v, vcross); + + RF_HIP_a = (vcross.col(iit::rbd::AZ) * qd(RF_HAA)); + RF_HIP_a(iit::rbd::AZ) += qdd(RF_HAA); + + RF_HIP_f = RF_HIP_I * RF_HIP_a + iit::rbd::vxIv(RF_HIP_v, RF_HIP_I); + + // First pass, link 'RF_THIGH' + RF_THIGH_v = ((xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_v); + RF_THIGH_v(iit::rbd::AZ) += qd(RF_HFE); + + iit::rbd::motionCrossProductMx(RF_THIGH_v, vcross); + + RF_THIGH_a = (xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_a + vcross.col(iit::rbd::AZ) * qd(RF_HFE); + RF_THIGH_a(iit::rbd::AZ) += qdd(RF_HFE); + + RF_THIGH_f = RF_THIGH_I * RF_THIGH_a + iit::rbd::vxIv(RF_THIGH_v, RF_THIGH_I); + + // First pass, link 'RF_SHANK' + RF_SHANK_v = ((xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_v); + RF_SHANK_v(iit::rbd::AZ) += qd(RF_KFE); + + iit::rbd::motionCrossProductMx(RF_SHANK_v, vcross); + + RF_SHANK_a = (xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RF_KFE); + RF_SHANK_a(iit::rbd::AZ) += qdd(RF_KFE); + + RF_SHANK_f = RF_SHANK_I * RF_SHANK_a + iit::rbd::vxIv(RF_SHANK_v, RF_SHANK_I); + + // First pass, link 'LH_HIP' + LH_HIP_v = ((xm->fr_LH_HIP_X_fr_base) * base_v); + LH_HIP_v(iit::rbd::AZ) += qd(LH_HAA); + + iit::rbd::motionCrossProductMx(LH_HIP_v, vcross); + + LH_HIP_a = (vcross.col(iit::rbd::AZ) * qd(LH_HAA)); + LH_HIP_a(iit::rbd::AZ) += qdd(LH_HAA); + + LH_HIP_f = LH_HIP_I * LH_HIP_a + iit::rbd::vxIv(LH_HIP_v, LH_HIP_I); + + // First pass, link 'LH_THIGH' + LH_THIGH_v = ((xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_v); + LH_THIGH_v(iit::rbd::AZ) += qd(LH_HFE); + + iit::rbd::motionCrossProductMx(LH_THIGH_v, vcross); + + LH_THIGH_a = (xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_a + vcross.col(iit::rbd::AZ) * qd(LH_HFE); + LH_THIGH_a(iit::rbd::AZ) += qdd(LH_HFE); + + LH_THIGH_f = LH_THIGH_I * LH_THIGH_a + iit::rbd::vxIv(LH_THIGH_v, LH_THIGH_I); + + // First pass, link 'LH_SHANK' + LH_SHANK_v = ((xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_v); + LH_SHANK_v(iit::rbd::AZ) += qd(LH_KFE); + + iit::rbd::motionCrossProductMx(LH_SHANK_v, vcross); + + LH_SHANK_a = (xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LH_KFE); + LH_SHANK_a(iit::rbd::AZ) += qdd(LH_KFE); + + LH_SHANK_f = LH_SHANK_I * LH_SHANK_a + iit::rbd::vxIv(LH_SHANK_v, LH_SHANK_I); + + // First pass, link 'RH_HIP' + RH_HIP_v = ((xm->fr_RH_HIP_X_fr_base) * base_v); + RH_HIP_v(iit::rbd::AZ) += qd(RH_HAA); + + iit::rbd::motionCrossProductMx(RH_HIP_v, vcross); + + RH_HIP_a = (vcross.col(iit::rbd::AZ) * qd(RH_HAA)); + RH_HIP_a(iit::rbd::AZ) += qdd(RH_HAA); + + RH_HIP_f = RH_HIP_I * RH_HIP_a + iit::rbd::vxIv(RH_HIP_v, RH_HIP_I); + + // First pass, link 'RH_THIGH' + RH_THIGH_v = ((xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_v); + RH_THIGH_v(iit::rbd::AZ) += qd(RH_HFE); + + iit::rbd::motionCrossProductMx(RH_THIGH_v, vcross); + + RH_THIGH_a = (xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_a + vcross.col(iit::rbd::AZ) * qd(RH_HFE); + RH_THIGH_a(iit::rbd::AZ) += qdd(RH_HFE); + + RH_THIGH_f = RH_THIGH_I * RH_THIGH_a + iit::rbd::vxIv(RH_THIGH_v, RH_THIGH_I); + + // First pass, link 'RH_SHANK' + RH_SHANK_v = ((xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_v); + RH_SHANK_v(iit::rbd::AZ) += qd(RH_KFE); + + iit::rbd::motionCrossProductMx(RH_SHANK_v, vcross); + + RH_SHANK_a = (xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RH_KFE); + RH_SHANK_a(iit::rbd::AZ) += qdd(RH_KFE); + + RH_SHANK_f = RH_SHANK_I * RH_SHANK_a + iit::rbd::vxIv(RH_SHANK_v, RH_SHANK_I); + + // The force exerted on the floating base by the links + base_f = iit::rbd::vxIv(base_v, base_I); + + + // Add the external forces: + base_f -= fext[BASE]; + LF_HIP_f -= fext[LF_HIP]; + LF_THIGH_f -= fext[LF_THIGH]; + LF_SHANK_f -= fext[LF_SHANK]; + RF_HIP_f -= fext[RF_HIP]; + RF_THIGH_f -= fext[RF_THIGH]; + RF_SHANK_f -= fext[RF_SHANK]; + LH_HIP_f -= fext[LH_HIP]; + LH_THIGH_f -= fext[LH_THIGH]; + LH_SHANK_f -= fext[LH_SHANK]; + RH_HIP_f -= fext[RH_HIP]; + RH_THIGH_f -= fext[RH_THIGH]; + RH_SHANK_f -= fext[RH_SHANK]; + + RH_THIGH_Ic = RH_THIGH_Ic + (xm->fr_RH_SHANK_X_fr_RH_THIGH).transpose() * RH_SHANK_Ic * (xm->fr_RH_SHANK_X_fr_RH_THIGH); + RH_THIGH_f = RH_THIGH_f + (xm->fr_RH_SHANK_X_fr_RH_THIGH).transpose() * RH_SHANK_f; + + RH_HIP_Ic = RH_HIP_Ic + (xm->fr_RH_THIGH_X_fr_RH_HIP).transpose() * RH_THIGH_Ic * (xm->fr_RH_THIGH_X_fr_RH_HIP); + RH_HIP_f = RH_HIP_f + (xm->fr_RH_THIGH_X_fr_RH_HIP).transpose() * RH_THIGH_f; + + base_Ic = base_Ic + (xm->fr_RH_HIP_X_fr_base).transpose() * RH_HIP_Ic * (xm->fr_RH_HIP_X_fr_base); + base_f = base_f + (xm->fr_RH_HIP_X_fr_base).transpose() * RH_HIP_f; + + LH_THIGH_Ic = LH_THIGH_Ic + (xm->fr_LH_SHANK_X_fr_LH_THIGH).transpose() * LH_SHANK_Ic * (xm->fr_LH_SHANK_X_fr_LH_THIGH); + LH_THIGH_f = LH_THIGH_f + (xm->fr_LH_SHANK_X_fr_LH_THIGH).transpose() * LH_SHANK_f; + + LH_HIP_Ic = LH_HIP_Ic + (xm->fr_LH_THIGH_X_fr_LH_HIP).transpose() * LH_THIGH_Ic * (xm->fr_LH_THIGH_X_fr_LH_HIP); + LH_HIP_f = LH_HIP_f + (xm->fr_LH_THIGH_X_fr_LH_HIP).transpose() * LH_THIGH_f; + + base_Ic = base_Ic + (xm->fr_LH_HIP_X_fr_base).transpose() * LH_HIP_Ic * (xm->fr_LH_HIP_X_fr_base); + base_f = base_f + (xm->fr_LH_HIP_X_fr_base).transpose() * LH_HIP_f; + + RF_THIGH_Ic = RF_THIGH_Ic + (xm->fr_RF_SHANK_X_fr_RF_THIGH).transpose() * RF_SHANK_Ic * (xm->fr_RF_SHANK_X_fr_RF_THIGH); + RF_THIGH_f = RF_THIGH_f + (xm->fr_RF_SHANK_X_fr_RF_THIGH).transpose() * RF_SHANK_f; + + RF_HIP_Ic = RF_HIP_Ic + (xm->fr_RF_THIGH_X_fr_RF_HIP).transpose() * RF_THIGH_Ic * (xm->fr_RF_THIGH_X_fr_RF_HIP); + RF_HIP_f = RF_HIP_f + (xm->fr_RF_THIGH_X_fr_RF_HIP).transpose() * RF_THIGH_f; + + base_Ic = base_Ic + (xm->fr_RF_HIP_X_fr_base).transpose() * RF_HIP_Ic * (xm->fr_RF_HIP_X_fr_base); + base_f = base_f + (xm->fr_RF_HIP_X_fr_base).transpose() * RF_HIP_f; + + LF_THIGH_Ic = LF_THIGH_Ic + (xm->fr_LF_SHANK_X_fr_LF_THIGH).transpose() * LF_SHANK_Ic * (xm->fr_LF_SHANK_X_fr_LF_THIGH); + LF_THIGH_f = LF_THIGH_f + (xm->fr_LF_SHANK_X_fr_LF_THIGH).transpose() * LF_SHANK_f; + + LF_HIP_Ic = LF_HIP_Ic + (xm->fr_LF_THIGH_X_fr_LF_HIP).transpose() * LF_THIGH_Ic * (xm->fr_LF_THIGH_X_fr_LF_HIP); + LF_HIP_f = LF_HIP_f + (xm->fr_LF_THIGH_X_fr_LF_HIP).transpose() * LF_THIGH_f; + + base_Ic = base_Ic + (xm->fr_LF_HIP_X_fr_base).transpose() * LF_HIP_Ic * (xm->fr_LF_HIP_X_fr_base); + base_f = base_f + (xm->fr_LF_HIP_X_fr_base).transpose() * LF_HIP_f; + + + // The base acceleration due to the force due to the movement of the links + base_a = - base_Ic.inverse() * base_f; + + LF_HIP_a = xm->fr_LF_HIP_X_fr_base * base_a; + jForces(LF_HAA) = (LF_HIP_Ic.row(iit::rbd::AZ) * LF_HIP_a + LF_HIP_f(iit::rbd::AZ)); + + LF_THIGH_a = xm->fr_LF_THIGH_X_fr_LF_HIP * LF_HIP_a; + jForces(LF_HFE) = (LF_THIGH_Ic.row(iit::rbd::AZ) * LF_THIGH_a + LF_THIGH_f(iit::rbd::AZ)); + + LF_SHANK_a = xm->fr_LF_SHANK_X_fr_LF_THIGH * LF_THIGH_a; + jForces(LF_KFE) = (LF_SHANK_Ic.row(iit::rbd::AZ) * LF_SHANK_a + LF_SHANK_f(iit::rbd::AZ)); + + RF_HIP_a = xm->fr_RF_HIP_X_fr_base * base_a; + jForces(RF_HAA) = (RF_HIP_Ic.row(iit::rbd::AZ) * RF_HIP_a + RF_HIP_f(iit::rbd::AZ)); + + RF_THIGH_a = xm->fr_RF_THIGH_X_fr_RF_HIP * RF_HIP_a; + jForces(RF_HFE) = (RF_THIGH_Ic.row(iit::rbd::AZ) * RF_THIGH_a + RF_THIGH_f(iit::rbd::AZ)); + + RF_SHANK_a = xm->fr_RF_SHANK_X_fr_RF_THIGH * RF_THIGH_a; + jForces(RF_KFE) = (RF_SHANK_Ic.row(iit::rbd::AZ) * RF_SHANK_a + RF_SHANK_f(iit::rbd::AZ)); + + LH_HIP_a = xm->fr_LH_HIP_X_fr_base * base_a; + jForces(LH_HAA) = (LH_HIP_Ic.row(iit::rbd::AZ) * LH_HIP_a + LH_HIP_f(iit::rbd::AZ)); + + LH_THIGH_a = xm->fr_LH_THIGH_X_fr_LH_HIP * LH_HIP_a; + jForces(LH_HFE) = (LH_THIGH_Ic.row(iit::rbd::AZ) * LH_THIGH_a + LH_THIGH_f(iit::rbd::AZ)); + + LH_SHANK_a = xm->fr_LH_SHANK_X_fr_LH_THIGH * LH_THIGH_a; + jForces(LH_KFE) = (LH_SHANK_Ic.row(iit::rbd::AZ) * LH_SHANK_a + LH_SHANK_f(iit::rbd::AZ)); + + RH_HIP_a = xm->fr_RH_HIP_X_fr_base * base_a; + jForces(RH_HAA) = (RH_HIP_Ic.row(iit::rbd::AZ) * RH_HIP_a + RH_HIP_f(iit::rbd::AZ)); + + RH_THIGH_a = xm->fr_RH_THIGH_X_fr_RH_HIP * RH_HIP_a; + jForces(RH_HFE) = (RH_THIGH_Ic.row(iit::rbd::AZ) * RH_THIGH_a + RH_THIGH_f(iit::rbd::AZ)); + + RH_SHANK_a = xm->fr_RH_SHANK_X_fr_RH_THIGH * RH_THIGH_a; + jForces(RH_KFE) = (RH_SHANK_Ic.row(iit::rbd::AZ) * RH_SHANK_a + RH_SHANK_f(iit::rbd::AZ)); + + + base_a += g; +} + +template +void iit::camel::dyn::tpl::InverseDynamics::G_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g) +{ + const Acceleration& base_a = -g; + + // Link 'LF_HIP' + LF_HIP_a = (xm->fr_LF_HIP_X_fr_base) * base_a; + LF_HIP_f = LF_HIP_I * LF_HIP_a; + // Link 'LF_THIGH' + LF_THIGH_a = (xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_a; + LF_THIGH_f = LF_THIGH_I * LF_THIGH_a; + // Link 'LF_SHANK' + LF_SHANK_a = (xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_a; + LF_SHANK_f = LF_SHANK_I * LF_SHANK_a; + // Link 'RF_HIP' + RF_HIP_a = (xm->fr_RF_HIP_X_fr_base) * base_a; + RF_HIP_f = RF_HIP_I * RF_HIP_a; + // Link 'RF_THIGH' + RF_THIGH_a = (xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_a; + RF_THIGH_f = RF_THIGH_I * RF_THIGH_a; + // Link 'RF_SHANK' + RF_SHANK_a = (xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_a; + RF_SHANK_f = RF_SHANK_I * RF_SHANK_a; + // Link 'LH_HIP' + LH_HIP_a = (xm->fr_LH_HIP_X_fr_base) * base_a; + LH_HIP_f = LH_HIP_I * LH_HIP_a; + // Link 'LH_THIGH' + LH_THIGH_a = (xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_a; + LH_THIGH_f = LH_THIGH_I * LH_THIGH_a; + // Link 'LH_SHANK' + LH_SHANK_a = (xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_a; + LH_SHANK_f = LH_SHANK_I * LH_SHANK_a; + // Link 'RH_HIP' + RH_HIP_a = (xm->fr_RH_HIP_X_fr_base) * base_a; + RH_HIP_f = RH_HIP_I * RH_HIP_a; + // Link 'RH_THIGH' + RH_THIGH_a = (xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_a; + RH_THIGH_f = RH_THIGH_I * RH_THIGH_a; + // Link 'RH_SHANK' + RH_SHANK_a = (xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_a; + RH_SHANK_f = RH_SHANK_I * RH_SHANK_a; + + base_f = base_I * base_a; + + secondPass_fullyActuated(jForces); + + baseWrench = base_f; +} + +template +void iit::camel::dyn::tpl::InverseDynamics::C_terms_fully_actuated( + Force& baseWrench, JointState& jForces, + const Velocity& base_v, const JointState& qd) +{ + // Link 'LF_HIP' + LF_HIP_v = ((xm->fr_LF_HIP_X_fr_base) * base_v); + LF_HIP_v(iit::rbd::AZ) += qd(LF_HAA); + iit::rbd::motionCrossProductMx(LF_HIP_v, vcross); + LF_HIP_a = (vcross.col(iit::rbd::AZ) * qd(LF_HAA)); + LF_HIP_f = LF_HIP_I * LF_HIP_a + iit::rbd::vxIv(LF_HIP_v, LF_HIP_I); + + // Link 'LF_THIGH' + LF_THIGH_v = ((xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_v); + LF_THIGH_v(iit::rbd::AZ) += qd(LF_HFE); + iit::rbd::motionCrossProductMx(LF_THIGH_v, vcross); + LF_THIGH_a = (xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_a + vcross.col(iit::rbd::AZ) * qd(LF_HFE); + LF_THIGH_f = LF_THIGH_I * LF_THIGH_a + iit::rbd::vxIv(LF_THIGH_v, LF_THIGH_I); + + // Link 'LF_SHANK' + LF_SHANK_v = ((xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_v); + LF_SHANK_v(iit::rbd::AZ) += qd(LF_KFE); + iit::rbd::motionCrossProductMx(LF_SHANK_v, vcross); + LF_SHANK_a = (xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LF_KFE); + LF_SHANK_f = LF_SHANK_I * LF_SHANK_a + iit::rbd::vxIv(LF_SHANK_v, LF_SHANK_I); + + // Link 'RF_HIP' + RF_HIP_v = ((xm->fr_RF_HIP_X_fr_base) * base_v); + RF_HIP_v(iit::rbd::AZ) += qd(RF_HAA); + iit::rbd::motionCrossProductMx(RF_HIP_v, vcross); + RF_HIP_a = (vcross.col(iit::rbd::AZ) * qd(RF_HAA)); + RF_HIP_f = RF_HIP_I * RF_HIP_a + iit::rbd::vxIv(RF_HIP_v, RF_HIP_I); + + // Link 'RF_THIGH' + RF_THIGH_v = ((xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_v); + RF_THIGH_v(iit::rbd::AZ) += qd(RF_HFE); + iit::rbd::motionCrossProductMx(RF_THIGH_v, vcross); + RF_THIGH_a = (xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_a + vcross.col(iit::rbd::AZ) * qd(RF_HFE); + RF_THIGH_f = RF_THIGH_I * RF_THIGH_a + iit::rbd::vxIv(RF_THIGH_v, RF_THIGH_I); + + // Link 'RF_SHANK' + RF_SHANK_v = ((xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_v); + RF_SHANK_v(iit::rbd::AZ) += qd(RF_KFE); + iit::rbd::motionCrossProductMx(RF_SHANK_v, vcross); + RF_SHANK_a = (xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RF_KFE); + RF_SHANK_f = RF_SHANK_I * RF_SHANK_a + iit::rbd::vxIv(RF_SHANK_v, RF_SHANK_I); + + // Link 'LH_HIP' + LH_HIP_v = ((xm->fr_LH_HIP_X_fr_base) * base_v); + LH_HIP_v(iit::rbd::AZ) += qd(LH_HAA); + iit::rbd::motionCrossProductMx(LH_HIP_v, vcross); + LH_HIP_a = (vcross.col(iit::rbd::AZ) * qd(LH_HAA)); + LH_HIP_f = LH_HIP_I * LH_HIP_a + iit::rbd::vxIv(LH_HIP_v, LH_HIP_I); + + // Link 'LH_THIGH' + LH_THIGH_v = ((xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_v); + LH_THIGH_v(iit::rbd::AZ) += qd(LH_HFE); + iit::rbd::motionCrossProductMx(LH_THIGH_v, vcross); + LH_THIGH_a = (xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_a + vcross.col(iit::rbd::AZ) * qd(LH_HFE); + LH_THIGH_f = LH_THIGH_I * LH_THIGH_a + iit::rbd::vxIv(LH_THIGH_v, LH_THIGH_I); + + // Link 'LH_SHANK' + LH_SHANK_v = ((xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_v); + LH_SHANK_v(iit::rbd::AZ) += qd(LH_KFE); + iit::rbd::motionCrossProductMx(LH_SHANK_v, vcross); + LH_SHANK_a = (xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LH_KFE); + LH_SHANK_f = LH_SHANK_I * LH_SHANK_a + iit::rbd::vxIv(LH_SHANK_v, LH_SHANK_I); + + // Link 'RH_HIP' + RH_HIP_v = ((xm->fr_RH_HIP_X_fr_base) * base_v); + RH_HIP_v(iit::rbd::AZ) += qd(RH_HAA); + iit::rbd::motionCrossProductMx(RH_HIP_v, vcross); + RH_HIP_a = (vcross.col(iit::rbd::AZ) * qd(RH_HAA)); + RH_HIP_f = RH_HIP_I * RH_HIP_a + iit::rbd::vxIv(RH_HIP_v, RH_HIP_I); + + // Link 'RH_THIGH' + RH_THIGH_v = ((xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_v); + RH_THIGH_v(iit::rbd::AZ) += qd(RH_HFE); + iit::rbd::motionCrossProductMx(RH_THIGH_v, vcross); + RH_THIGH_a = (xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_a + vcross.col(iit::rbd::AZ) * qd(RH_HFE); + RH_THIGH_f = RH_THIGH_I * RH_THIGH_a + iit::rbd::vxIv(RH_THIGH_v, RH_THIGH_I); + + // Link 'RH_SHANK' + RH_SHANK_v = ((xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_v); + RH_SHANK_v(iit::rbd::AZ) += qd(RH_KFE); + iit::rbd::motionCrossProductMx(RH_SHANK_v, vcross); + RH_SHANK_a = (xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RH_KFE); + RH_SHANK_f = RH_SHANK_I * RH_SHANK_a + iit::rbd::vxIv(RH_SHANK_v, RH_SHANK_I); + + + base_f = iit::rbd::vxIv(base_v, base_I); + + secondPass_fullyActuated(jForces); + + baseWrench = base_f; +} + +template +void iit::camel::dyn::tpl::InverseDynamics::id_fully_actuated( + Force& baseWrench, JointState& jForces, + const Acceleration& g, const Velocity& base_v, const Acceleration& baseAccel, + const JointState& qd, const JointState& qdd, const ExtForces& fext) +{ + Acceleration base_a = baseAccel -g; + + // First pass, link 'LF_HIP' + LF_HIP_v = ((xm->fr_LF_HIP_X_fr_base) * base_v); + LF_HIP_v(iit::rbd::AZ) += qd(LF_HAA); + + iit::rbd::motionCrossProductMx(LF_HIP_v, vcross); + + LF_HIP_a = (xm->fr_LF_HIP_X_fr_base) * base_a + vcross.col(iit::rbd::AZ) * qd(LF_HAA); + LF_HIP_a(iit::rbd::AZ) += qdd(LF_HAA); + + LF_HIP_f = LF_HIP_I * LF_HIP_a + iit::rbd::vxIv(LF_HIP_v, LF_HIP_I) - fext[LF_HIP]; + + // First pass, link 'LF_THIGH' + LF_THIGH_v = ((xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_v); + LF_THIGH_v(iit::rbd::AZ) += qd(LF_HFE); + + iit::rbd::motionCrossProductMx(LF_THIGH_v, vcross); + + LF_THIGH_a = (xm->fr_LF_THIGH_X_fr_LF_HIP) * LF_HIP_a + vcross.col(iit::rbd::AZ) * qd(LF_HFE); + LF_THIGH_a(iit::rbd::AZ) += qdd(LF_HFE); + + LF_THIGH_f = LF_THIGH_I * LF_THIGH_a + iit::rbd::vxIv(LF_THIGH_v, LF_THIGH_I) - fext[LF_THIGH]; + + // First pass, link 'LF_SHANK' + LF_SHANK_v = ((xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_v); + LF_SHANK_v(iit::rbd::AZ) += qd(LF_KFE); + + iit::rbd::motionCrossProductMx(LF_SHANK_v, vcross); + + LF_SHANK_a = (xm->fr_LF_SHANK_X_fr_LF_THIGH) * LF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LF_KFE); + LF_SHANK_a(iit::rbd::AZ) += qdd(LF_KFE); + + LF_SHANK_f = LF_SHANK_I * LF_SHANK_a + iit::rbd::vxIv(LF_SHANK_v, LF_SHANK_I) - fext[LF_SHANK]; + + // First pass, link 'RF_HIP' + RF_HIP_v = ((xm->fr_RF_HIP_X_fr_base) * base_v); + RF_HIP_v(iit::rbd::AZ) += qd(RF_HAA); + + iit::rbd::motionCrossProductMx(RF_HIP_v, vcross); + + RF_HIP_a = (xm->fr_RF_HIP_X_fr_base) * base_a + vcross.col(iit::rbd::AZ) * qd(RF_HAA); + RF_HIP_a(iit::rbd::AZ) += qdd(RF_HAA); + + RF_HIP_f = RF_HIP_I * RF_HIP_a + iit::rbd::vxIv(RF_HIP_v, RF_HIP_I) - fext[RF_HIP]; + + // First pass, link 'RF_THIGH' + RF_THIGH_v = ((xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_v); + RF_THIGH_v(iit::rbd::AZ) += qd(RF_HFE); + + iit::rbd::motionCrossProductMx(RF_THIGH_v, vcross); + + RF_THIGH_a = (xm->fr_RF_THIGH_X_fr_RF_HIP) * RF_HIP_a + vcross.col(iit::rbd::AZ) * qd(RF_HFE); + RF_THIGH_a(iit::rbd::AZ) += qdd(RF_HFE); + + RF_THIGH_f = RF_THIGH_I * RF_THIGH_a + iit::rbd::vxIv(RF_THIGH_v, RF_THIGH_I) - fext[RF_THIGH]; + + // First pass, link 'RF_SHANK' + RF_SHANK_v = ((xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_v); + RF_SHANK_v(iit::rbd::AZ) += qd(RF_KFE); + + iit::rbd::motionCrossProductMx(RF_SHANK_v, vcross); + + RF_SHANK_a = (xm->fr_RF_SHANK_X_fr_RF_THIGH) * RF_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RF_KFE); + RF_SHANK_a(iit::rbd::AZ) += qdd(RF_KFE); + + RF_SHANK_f = RF_SHANK_I * RF_SHANK_a + iit::rbd::vxIv(RF_SHANK_v, RF_SHANK_I) - fext[RF_SHANK]; + + // First pass, link 'LH_HIP' + LH_HIP_v = ((xm->fr_LH_HIP_X_fr_base) * base_v); + LH_HIP_v(iit::rbd::AZ) += qd(LH_HAA); + + iit::rbd::motionCrossProductMx(LH_HIP_v, vcross); + + LH_HIP_a = (xm->fr_LH_HIP_X_fr_base) * base_a + vcross.col(iit::rbd::AZ) * qd(LH_HAA); + LH_HIP_a(iit::rbd::AZ) += qdd(LH_HAA); + + LH_HIP_f = LH_HIP_I * LH_HIP_a + iit::rbd::vxIv(LH_HIP_v, LH_HIP_I) - fext[LH_HIP]; + + // First pass, link 'LH_THIGH' + LH_THIGH_v = ((xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_v); + LH_THIGH_v(iit::rbd::AZ) += qd(LH_HFE); + + iit::rbd::motionCrossProductMx(LH_THIGH_v, vcross); + + LH_THIGH_a = (xm->fr_LH_THIGH_X_fr_LH_HIP) * LH_HIP_a + vcross.col(iit::rbd::AZ) * qd(LH_HFE); + LH_THIGH_a(iit::rbd::AZ) += qdd(LH_HFE); + + LH_THIGH_f = LH_THIGH_I * LH_THIGH_a + iit::rbd::vxIv(LH_THIGH_v, LH_THIGH_I) - fext[LH_THIGH]; + + // First pass, link 'LH_SHANK' + LH_SHANK_v = ((xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_v); + LH_SHANK_v(iit::rbd::AZ) += qd(LH_KFE); + + iit::rbd::motionCrossProductMx(LH_SHANK_v, vcross); + + LH_SHANK_a = (xm->fr_LH_SHANK_X_fr_LH_THIGH) * LH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(LH_KFE); + LH_SHANK_a(iit::rbd::AZ) += qdd(LH_KFE); + + LH_SHANK_f = LH_SHANK_I * LH_SHANK_a + iit::rbd::vxIv(LH_SHANK_v, LH_SHANK_I) - fext[LH_SHANK]; + + // First pass, link 'RH_HIP' + RH_HIP_v = ((xm->fr_RH_HIP_X_fr_base) * base_v); + RH_HIP_v(iit::rbd::AZ) += qd(RH_HAA); + + iit::rbd::motionCrossProductMx(RH_HIP_v, vcross); + + RH_HIP_a = (xm->fr_RH_HIP_X_fr_base) * base_a + vcross.col(iit::rbd::AZ) * qd(RH_HAA); + RH_HIP_a(iit::rbd::AZ) += qdd(RH_HAA); + + RH_HIP_f = RH_HIP_I * RH_HIP_a + iit::rbd::vxIv(RH_HIP_v, RH_HIP_I) - fext[RH_HIP]; + + // First pass, link 'RH_THIGH' + RH_THIGH_v = ((xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_v); + RH_THIGH_v(iit::rbd::AZ) += qd(RH_HFE); + + iit::rbd::motionCrossProductMx(RH_THIGH_v, vcross); + + RH_THIGH_a = (xm->fr_RH_THIGH_X_fr_RH_HIP) * RH_HIP_a + vcross.col(iit::rbd::AZ) * qd(RH_HFE); + RH_THIGH_a(iit::rbd::AZ) += qdd(RH_HFE); + + RH_THIGH_f = RH_THIGH_I * RH_THIGH_a + iit::rbd::vxIv(RH_THIGH_v, RH_THIGH_I) - fext[RH_THIGH]; + + // First pass, link 'RH_SHANK' + RH_SHANK_v = ((xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_v); + RH_SHANK_v(iit::rbd::AZ) += qd(RH_KFE); + + iit::rbd::motionCrossProductMx(RH_SHANK_v, vcross); + + RH_SHANK_a = (xm->fr_RH_SHANK_X_fr_RH_THIGH) * RH_THIGH_a + vcross.col(iit::rbd::AZ) * qd(RH_KFE); + RH_SHANK_a(iit::rbd::AZ) += qdd(RH_KFE); + + RH_SHANK_f = RH_SHANK_I * RH_SHANK_a + iit::rbd::vxIv(RH_SHANK_v, RH_SHANK_I) - fext[RH_SHANK]; + + + // The base + base_f = base_I * base_a + iit::rbd::vxIv(base_v, base_I) - fext[BASE]; + + secondPass_fullyActuated(jForces); + + baseWrench = base_f; +} + +template +void iit::camel::dyn::tpl::InverseDynamics::secondPass_fullyActuated(JointState& jForces) +{ + // Link 'RH_SHANK' + jForces(RH_KFE) = RH_SHANK_f(iit::rbd::AZ); + RH_THIGH_f += xm->fr_RH_SHANK_X_fr_RH_THIGH.transpose() * RH_SHANK_f; + // Link 'RH_THIGH' + jForces(RH_HFE) = RH_THIGH_f(iit::rbd::AZ); + RH_HIP_f += xm->fr_RH_THIGH_X_fr_RH_HIP.transpose() * RH_THIGH_f; + // Link 'RH_HIP' + jForces(RH_HAA) = RH_HIP_f(iit::rbd::AZ); + base_f += xm->fr_RH_HIP_X_fr_base.transpose() * RH_HIP_f; + // Link 'LH_SHANK' + jForces(LH_KFE) = LH_SHANK_f(iit::rbd::AZ); + LH_THIGH_f += xm->fr_LH_SHANK_X_fr_LH_THIGH.transpose() * LH_SHANK_f; + // Link 'LH_THIGH' + jForces(LH_HFE) = LH_THIGH_f(iit::rbd::AZ); + LH_HIP_f += xm->fr_LH_THIGH_X_fr_LH_HIP.transpose() * LH_THIGH_f; + // Link 'LH_HIP' + jForces(LH_HAA) = LH_HIP_f(iit::rbd::AZ); + base_f += xm->fr_LH_HIP_X_fr_base.transpose() * LH_HIP_f; + // Link 'RF_SHANK' + jForces(RF_KFE) = RF_SHANK_f(iit::rbd::AZ); + RF_THIGH_f += xm->fr_RF_SHANK_X_fr_RF_THIGH.transpose() * RF_SHANK_f; + // Link 'RF_THIGH' + jForces(RF_HFE) = RF_THIGH_f(iit::rbd::AZ); + RF_HIP_f += xm->fr_RF_THIGH_X_fr_RF_HIP.transpose() * RF_THIGH_f; + // Link 'RF_HIP' + jForces(RF_HAA) = RF_HIP_f(iit::rbd::AZ); + base_f += xm->fr_RF_HIP_X_fr_base.transpose() * RF_HIP_f; + // Link 'LF_SHANK' + jForces(LF_KFE) = LF_SHANK_f(iit::rbd::AZ); + LF_THIGH_f += xm->fr_LF_SHANK_X_fr_LF_THIGH.transpose() * LF_SHANK_f; + // Link 'LF_THIGH' + jForces(LF_HFE) = LF_THIGH_f(iit::rbd::AZ); + LF_HIP_f += xm->fr_LF_THIGH_X_fr_LF_HIP.transpose() * LF_THIGH_f; + // Link 'LF_HIP' + jForces(LF_HAA) = LF_HIP_f(iit::rbd::AZ); + base_f += xm->fr_LF_HIP_X_fr_base.transpose() * LF_HIP_f; +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.h new file mode 100644 index 000000000..9d9090c7a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.h @@ -0,0 +1,91 @@ +#ifndef CAMEL_JACOBIANS_H_ +#define CAMEL_JACOBIANS_H_ + + #include +#include +#include +#include "declarations.h" +#include "kinematics_parameters.h" + +namespace iit { +namespace camel { + +template +class JacobianT : public iit::rbd::JacobianBase, COLS, M> +{}; + +namespace tpl { + +/** + * + */ +template +class Jacobians { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename TRAIT::Scalar Scalar; + typedef iit::rbd::Core CoreS; + + typedef JointState JState; + + class Type_fr_base_J_fr_LF_FOOT : public JacobianT + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_J_fr_LF_FOOT(); + const Type_fr_base_J_fr_LF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_base_J_fr_LH_FOOT : public JacobianT + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_J_fr_LH_FOOT(); + const Type_fr_base_J_fr_LH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_base_J_fr_RF_FOOT : public JacobianT + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_J_fr_RF_FOOT(); + const Type_fr_base_J_fr_RF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_base_J_fr_RH_FOOT : public JacobianT + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_J_fr_RH_FOOT(); + const Type_fr_base_J_fr_RH_FOOT& update(const JState&); + protected: + }; + + public: + Jacobians(); + void updateParameters(); + public: + Type_fr_base_J_fr_LF_FOOT fr_base_J_fr_LF_FOOT; + Type_fr_base_J_fr_LH_FOOT fr_base_J_fr_LH_FOOT; + Type_fr_base_J_fr_RF_FOOT fr_base_J_fr_RF_FOOT; + Type_fr_base_J_fr_RH_FOOT fr_base_J_fr_RH_FOOT; + + protected: + +}; + +} //namespace tpl + +using Jacobians = tpl::Jacobians; + +#include "jacobians.impl.h" + + +} +} + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.impl.h new file mode 100644 index 000000000..b72dfadb9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jacobians.impl.h @@ -0,0 +1,182 @@ + +template +iit::camel::tpl::Jacobians::Jacobians + () + : + fr_base_J_fr_LF_FOOT(), + fr_base_J_fr_LH_FOOT(), + fr_base_J_fr_RF_FOOT(), + fr_base_J_fr_RH_FOOT() +{ + updateParameters(); +} + +template +void iit::camel::tpl::Jacobians::updateParameters() { +} + + +template +iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LF_FOOT::Type_fr_base_J_fr_LF_FOOT() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; +} + +template +const typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LF_FOOT& iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LF_FOOT::update(const JState& jState) { + Scalar s_q_LF_HAA_; + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar c_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_HAA_ = TRAIT::sin( jState(LF_HAA)); + s_q_LF_HFE_ = TRAIT::sin( jState(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( jState(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( jState(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( jState(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( jState(LF_KFE)); + + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = c_q_LF_HAA_; + (*this)(2,1) = s_q_LF_HAA_; + (*this)(2,2) = s_q_LF_HAA_; + (*this)(3,1) = ((((( 0.33797 * s_q_LF_HFE_) - ( 0.08795 * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((- 0.08795 * s_q_LF_HFE_) - ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.285 * c_q_LF_HFE_)); + (*this)(3,2) = (((( 0.33797 * s_q_LF_HFE_) - ( 0.08795 * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((- 0.08795 * s_q_LF_HFE_) - ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)); + (*this)(4,0) = ((((((( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * c_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.19716 * s_q_LF_HAA_)); + (*this)(4,1) = ((((((- 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(4,2) = (((((- 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)); + (*this)(5,0) = ((((((( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * c_q_LF_HFE_)) + ( 0.19716 * c_q_LF_HAA_)); + (*this)(5,1) = (((((( 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(5,2) = ((((( 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)); + return *this; +} +template +iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LH_FOOT::Type_fr_base_J_fr_LH_FOOT() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; +} + +template +const typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LH_FOOT& iit::camel::tpl::Jacobians::Type_fr_base_J_fr_LH_FOOT::update(const JState& jState) { + Scalar s_q_LH_HAA_; + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar c_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_HAA_ = TRAIT::sin( jState(LH_HAA)); + s_q_LH_HFE_ = TRAIT::sin( jState(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( jState(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( jState(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( jState(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( jState(LH_KFE)); + + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = c_q_LH_HAA_; + (*this)(2,1) = s_q_LH_HAA_; + (*this)(2,2) = s_q_LH_HAA_; + (*this)(3,1) = ((((( 0.33797 * s_q_LH_HFE_) + ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.08795 * s_q_LH_HFE_) - ( 0.33797 * c_q_LH_HFE_)) * c_q_LH_KFE_)) - ( 0.285 * c_q_LH_HFE_)); + (*this)(3,2) = (((( 0.33797 * s_q_LH_HFE_) + ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.08795 * s_q_LH_HFE_) - ( 0.33797 * c_q_LH_HFE_)) * c_q_LH_KFE_)); + (*this)(4,0) = (((((((- 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * c_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.19716 * s_q_LH_HAA_)); + (*this)(4,1) = (((((( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_)); + (*this)(4,2) = ((((( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)); + (*this)(5,0) = (((((((- 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * c_q_LH_HFE_)) + ( 0.19716 * c_q_LH_HAA_)); + (*this)(5,1) = (((((( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_)); + (*this)(5,2) = ((((( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)); + return *this; +} +template +iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RF_FOOT::Type_fr_base_J_fr_RF_FOOT() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; +} + +template +const typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RF_FOOT& iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RF_FOOT::update(const JState& jState) { + Scalar s_q_RF_HAA_; + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar c_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_HAA_ = TRAIT::sin( jState(RF_HAA)); + s_q_RF_HFE_ = TRAIT::sin( jState(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( jState(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( jState(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( jState(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( jState(RF_KFE)); + + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = c_q_RF_HAA_; + (*this)(2,1) = s_q_RF_HAA_; + (*this)(2,2) = s_q_RF_HAA_; + (*this)(3,1) = ((((( 0.33797 * s_q_RF_HFE_) - ( 0.08795 * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((- 0.08795 * s_q_RF_HFE_) - ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.285 * c_q_RF_HFE_)); + (*this)(3,2) = (((( 0.33797 * s_q_RF_HFE_) - ( 0.08795 * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((- 0.08795 * s_q_RF_HFE_) - ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)); + (*this)(4,0) = ((((((( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * c_q_RF_HAA_) * c_q_RF_HFE_)) + ( 0.19716 * s_q_RF_HAA_)); + (*this)(4,1) = ((((((- 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_)); + (*this)(4,2) = (((((- 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)); + (*this)(5,0) = ((((((( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.19716 * c_q_RF_HAA_)); + (*this)(5,1) = (((((( 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)); + (*this)(5,2) = ((((( 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)); + return *this; +} +template +iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RH_FOOT::Type_fr_base_J_fr_RH_FOOT() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; +} + +template +const typename iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RH_FOOT& iit::camel::tpl::Jacobians::Type_fr_base_J_fr_RH_FOOT::update(const JState& jState) { + Scalar s_q_RH_HAA_; + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar c_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_HAA_ = TRAIT::sin( jState(RH_HAA)); + s_q_RH_HFE_ = TRAIT::sin( jState(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( jState(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( jState(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( jState(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( jState(RH_KFE)); + + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = c_q_RH_HAA_; + (*this)(2,1) = s_q_RH_HAA_; + (*this)(2,2) = s_q_RH_HAA_; + (*this)(3,1) = ((((( 0.33797 * s_q_RH_HFE_) + ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.08795 * s_q_RH_HFE_) - ( 0.33797 * c_q_RH_HFE_)) * c_q_RH_KFE_)) - ( 0.285 * c_q_RH_HFE_)); + (*this)(3,2) = (((( 0.33797 * s_q_RH_HFE_) + ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.08795 * s_q_RH_HFE_) - ( 0.33797 * c_q_RH_HFE_)) * c_q_RH_KFE_)); + (*this)(4,0) = (((((((- 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * c_q_RH_HAA_) * c_q_RH_HFE_)) + ( 0.19716 * s_q_RH_HAA_)); + (*this)(4,1) = (((((( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_)); + (*this)(4,2) = ((((( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)); + (*this)(5,0) = (((((((- 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.19716 * c_q_RH_HAA_)); + (*this)(5,1) = (((((( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_)); + (*this)(5,2) = ((((( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)); + return *this; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/joint_data_map.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/joint_data_map.h new file mode 100644 index 000000000..78eddcc53 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/joint_data_map.h @@ -0,0 +1,130 @@ +#ifndef IIT_CAMEL_JOINT_DATA_MAP_H_ +#define IIT_CAMEL_JOINT_DATA_MAP_H_ + +#include "declarations.h" + +namespace iit { +namespace camel { + +/** + * A very simple container to associate a generic data item to each joint + */ +template class JointDataMap { +private: + T data[jointsCount]; +public: + JointDataMap() {}; + JointDataMap(const T& defaultValue); + JointDataMap(const JointDataMap& rhs); + JointDataMap& operator=(const JointDataMap& rhs); + JointDataMap& operator=(const T& rhs); + T& operator[](JointIdentifiers which); + const T& operator[](JointIdentifiers which) const; +private: + void copydata(const JointDataMap& rhs); + void assigndata(const T& rhs); +}; + +template inline +JointDataMap::JointDataMap(const T& value) { + assigndata(value); +} + +template inline +JointDataMap::JointDataMap(const JointDataMap& rhs) +{ + copydata(rhs); +} + +template inline +JointDataMap& JointDataMap::operator=(const JointDataMap& rhs) +{ + if(&rhs != this) { + copydata(rhs); + } + return *this; +} + +template inline +JointDataMap& JointDataMap::operator=(const T& value) +{ + assigndata(value); + return *this; +} + +template inline +T& JointDataMap::operator[](JointIdentifiers j) { + return data[j]; +} + +template inline +const T& JointDataMap::operator[](JointIdentifiers j) const { + return data[j]; +} + +template inline +void JointDataMap::copydata(const JointDataMap& rhs) { + data[LF_HAA] = rhs[LF_HAA]; + data[LF_HFE] = rhs[LF_HFE]; + data[LF_KFE] = rhs[LF_KFE]; + data[RF_HAA] = rhs[RF_HAA]; + data[RF_HFE] = rhs[RF_HFE]; + data[RF_KFE] = rhs[RF_KFE]; + data[LH_HAA] = rhs[LH_HAA]; + data[LH_HFE] = rhs[LH_HFE]; + data[LH_KFE] = rhs[LH_KFE]; + data[RH_HAA] = rhs[RH_HAA]; + data[RH_HFE] = rhs[RH_HFE]; + data[RH_KFE] = rhs[RH_KFE]; +} + +template inline +void JointDataMap::assigndata(const T& value) { + data[LF_HAA] = value; + data[LF_HFE] = value; + data[LF_KFE] = value; + data[RF_HAA] = value; + data[RF_HFE] = value; + data[RF_KFE] = value; + data[LH_HAA] = value; + data[LH_HFE] = value; + data[LH_KFE] = value; + data[RH_HAA] = value; + data[RH_HFE] = value; + data[RH_KFE] = value; +} + +template inline +std::ostream& operator<<(std::ostream& out, const JointDataMap& map) { + out + << " LF_HAA = " + << map[LF_HAA] + << " LF_HFE = " + << map[LF_HFE] + << " LF_KFE = " + << map[LF_KFE] + << " RF_HAA = " + << map[RF_HAA] + << " RF_HFE = " + << map[RF_HFE] + << " RF_KFE = " + << map[RF_KFE] + << " LH_HAA = " + << map[LH_HAA] + << " LH_HFE = " + << map[LH_HFE] + << " LH_KFE = " + << map[LH_KFE] + << " RH_HAA = " + << map[RH_HAA] + << " RH_HFE = " + << map[RH_HFE] + << " RH_KFE = " + << map[RH_KFE] + ; + return out; +} + +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.h new file mode 100644 index 000000000..ff662475e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.h @@ -0,0 +1,162 @@ +#ifndef IIT_CAMEL_JSIM_H_ +#define IIT_CAMEL_JSIM_H_ + +#include +#include + +#include "declarations.h" +#include "transforms.h" +#include "inertia_properties.h" +#include +#include + + +namespace iit { +namespace camel { +namespace dyn { + +namespace tpl { + +/** + * The type of the Joint Space Inertia Matrix (JSIM) of the robot camel. + */ +template +class JSIM : public iit::rbd::StateDependentMatrix, 18, 18, JSIM> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + typedef iit::rbd::StateDependentMatrix, 18, 18, JSIM> Base; + public: + typedef typename TRAIT::Scalar Scalar; + typedef typename iit::camel::tpl::JointState JointState; + typedef iit::rbd::Core CoreS; + typedef typename Base::Index Index; + typedef typename iit::rbd::PlainMatrix MatrixType; + /** The type of the F sub-block of the floating-base JSIM */ + typedef const Eigen::Block BlockF_t; + /** The type of the fixed-base sub-block of the JSIM */ + typedef const Eigen::Block BlockFixedBase_t; + typedef InertiaProperties IProperties; + typedef iit::camel::tpl::ForceTransforms FTransforms; + typedef iit::rbd::tpl::InertiaMatrixDense InertiaMatrix; + + public: + JSIM(IProperties&, FTransforms&); + ~JSIM() {} + + const JSIM& update(const JointState&); + + + /** + * Computes and saves the matrix L of the L^T L factorization of this JSIM. + */ + void computeL(); + /** + * Computes and saves the inverse of this JSIM. + * This function assumes that computeL() has been called already, since it + * uses L to compute the inverse. The algorithm takes advantage of the branch + * induced sparsity of the robot, if any. + */ + void computeInverse(); + /** + * Returns an unmodifiable reference to the matrix L. See also computeL() + */ + const MatrixType& getL() const; + /** + * Returns an unmodifiable reference to the inverse of this JSIM + */ + const MatrixType& getInverse() const; + + /** + * The spatial composite-inertia tensor of the robot base, + * ie the inertia of the whole robot for the current configuration. + * According to the convention of this class about the layout of the + * floating-base JSIM, this tensor is the 6x6 upper left corner of + * the JSIM itself. + * \return the 6x6 InertiaMatrix that correspond to the spatial inertia + * tensor of the whole robot, according to the last joints configuration + * used to update this JSIM + */ + const InertiaMatrix& getWholeBodyInertia() const; + /** + * The matrix that maps accelerations in the actual joints of the robot + * to the spatial force acting on the floating-base of the robot. + * This matrix is the F sub-block of the JSIM in Featherstone's notation. + * \return the 6x12 upper right block of this JSIM + */ + const BlockF_t getF() const; + /** + * The submatrix of this JSIM related only to the actual joints of the + * robot (as for a fixed-base robot). + * This matrix is the H sub-block of the JSIM in Featherstone's notation. + * \return the 12x12 lower right block of this JSIM, + * which correspond to the fixed-base JSIM + */ + const BlockFixedBase_t getFixedBaseBlock() const; + protected: + /** + * Computes and saves the inverse of the matrix L. See also computeL() + */ + void computeLInverse(); + private: + IProperties& linkInertias; + FTransforms* frcTransf; + + // The composite-inertia tensor for each link + InertiaMatrix base_Ic; + InertiaMatrix LF_HIP_Ic; + InertiaMatrix LF_THIGH_Ic; + const InertiaMatrix& LF_SHANK_Ic; + InertiaMatrix RF_HIP_Ic; + InertiaMatrix RF_THIGH_Ic; + const InertiaMatrix& RF_SHANK_Ic; + InertiaMatrix LH_HIP_Ic; + InertiaMatrix LH_THIGH_Ic; + const InertiaMatrix& LH_SHANK_Ic; + InertiaMatrix RH_HIP_Ic; + InertiaMatrix RH_THIGH_Ic; + const InertiaMatrix& RH_SHANK_Ic; + InertiaMatrix Ic_spare; + + MatrixType L; + MatrixType Linv; + MatrixType inverse; +}; + +template +inline const typename JSIM::MatrixType& JSIM::getL() const { + return L; +} + +template +inline const typename JSIM::MatrixType& JSIM::getInverse() const { + return inverse; +} + +template +inline const typename JSIM::InertiaMatrix& JSIM::getWholeBodyInertia() const { + return base_Ic; +} + +template +inline const typename JSIM::BlockF_t JSIM::getF() const { + return JSIM:: template block<6,12>(0,6); +} + +template +inline const typename JSIM::BlockFixedBase_t JSIM::getFixedBaseBlock() const{ + return JSIM:: template block<12,12>(6,6); +} + +} + +typedef tpl::JSIM JSIM; + +} +} +} + +#include "jsim.impl.h" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.impl.h new file mode 100644 index 000000000..55356d520 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/jsim.impl.h @@ -0,0 +1,344 @@ + + +//Implementation of default constructor +template +iit::camel::dyn::tpl::JSIM::JSIM(IProperties& inertiaProperties, FTransforms& forceTransforms) : + linkInertias(inertiaProperties), + frcTransf( &forceTransforms ), + LF_SHANK_Ic(linkInertias.getTensor_LF_SHANK()), + RF_SHANK_Ic(linkInertias.getTensor_RF_SHANK()), + LH_SHANK_Ic(linkInertias.getTensor_LH_SHANK()), + RH_SHANK_Ic(linkInertias.getTensor_RH_SHANK()) +{ + //Initialize the matrix itself + this->setZero(); +} + +#define DATA tpl::JSIM::operator() +#define Fcol(j) (tpl::JSIM:: template block<6,1>(0,(j)+6)) +#define F(i,j) DATA((i),(j)+6) + +template +const typename iit::camel::dyn::tpl::JSIM& iit::camel::dyn::tpl::JSIM::update(const JointState& state) { + + // Precomputes only once the coordinate transforms: + frcTransf -> fr_RH_THIGH_X_fr_RH_SHANK(state); + frcTransf -> fr_RH_HIP_X_fr_RH_THIGH(state); + frcTransf -> fr_base_X_fr_RH_HIP(state); + frcTransf -> fr_LH_THIGH_X_fr_LH_SHANK(state); + frcTransf -> fr_LH_HIP_X_fr_LH_THIGH(state); + frcTransf -> fr_base_X_fr_LH_HIP(state); + frcTransf -> fr_RF_THIGH_X_fr_RF_SHANK(state); + frcTransf -> fr_RF_HIP_X_fr_RF_THIGH(state); + frcTransf -> fr_base_X_fr_RF_HIP(state); + frcTransf -> fr_LF_THIGH_X_fr_LF_SHANK(state); + frcTransf -> fr_LF_HIP_X_fr_LF_THIGH(state); + frcTransf -> fr_base_X_fr_LF_HIP(state); + + // Initializes the composite inertia tensors + base_Ic = linkInertias.getTensor_base(); + LF_HIP_Ic = linkInertias.getTensor_LF_HIP(); + LF_THIGH_Ic = linkInertias.getTensor_LF_THIGH(); + RF_HIP_Ic = linkInertias.getTensor_RF_HIP(); + RF_THIGH_Ic = linkInertias.getTensor_RF_THIGH(); + LH_HIP_Ic = linkInertias.getTensor_LH_HIP(); + LH_THIGH_Ic = linkInertias.getTensor_LH_THIGH(); + RH_HIP_Ic = linkInertias.getTensor_RH_HIP(); + RH_THIGH_Ic = linkInertias.getTensor_RH_THIGH(); + + // "Bottom-up" loop to update the inertia-composite property of each link, for the current configuration + + // Link RH_SHANK: + iit::rbd::transformInertia(RH_SHANK_Ic, frcTransf -> fr_RH_THIGH_X_fr_RH_SHANK, Ic_spare); + RH_THIGH_Ic += Ic_spare; + + Fcol(RH_KFE) = RH_SHANK_Ic.col(iit::rbd::AZ); + DATA(RH_KFE+6, RH_KFE+6) = Fcol(RH_KFE)(iit::rbd::AZ); + + Fcol(RH_KFE) = frcTransf -> fr_RH_THIGH_X_fr_RH_SHANK * Fcol(RH_KFE); + DATA(RH_KFE+6, RH_HFE+6) = F(iit::rbd::AZ,RH_KFE); + DATA(RH_HFE+6, RH_KFE+6) = DATA(RH_KFE+6, RH_HFE+6); + Fcol(RH_KFE) = frcTransf -> fr_RH_HIP_X_fr_RH_THIGH * Fcol(RH_KFE); + DATA(RH_KFE+6, RH_HAA+6) = F(iit::rbd::AZ,RH_KFE); + DATA(RH_HAA+6, RH_KFE+6) = DATA(RH_KFE+6, RH_HAA+6); + Fcol(RH_KFE) = frcTransf -> fr_base_X_fr_RH_HIP * Fcol(RH_KFE); + + // Link RH_THIGH: + iit::rbd::transformInertia(RH_THIGH_Ic, frcTransf -> fr_RH_HIP_X_fr_RH_THIGH, Ic_spare); + RH_HIP_Ic += Ic_spare; + + Fcol(RH_HFE) = RH_THIGH_Ic.col(iit::rbd::AZ); + DATA(RH_HFE+6, RH_HFE+6) = Fcol(RH_HFE)(iit::rbd::AZ); + + Fcol(RH_HFE) = frcTransf -> fr_RH_HIP_X_fr_RH_THIGH * Fcol(RH_HFE); + DATA(RH_HFE+6, RH_HAA+6) = F(iit::rbd::AZ,RH_HFE); + DATA(RH_HAA+6, RH_HFE+6) = DATA(RH_HFE+6, RH_HAA+6); + Fcol(RH_HFE) = frcTransf -> fr_base_X_fr_RH_HIP * Fcol(RH_HFE); + + // Link RH_HIP: + iit::rbd::transformInertia(RH_HIP_Ic, frcTransf -> fr_base_X_fr_RH_HIP, Ic_spare); + base_Ic += Ic_spare; + + Fcol(RH_HAA) = RH_HIP_Ic.col(iit::rbd::AZ); + DATA(RH_HAA+6, RH_HAA+6) = Fcol(RH_HAA)(iit::rbd::AZ); + + Fcol(RH_HAA) = frcTransf -> fr_base_X_fr_RH_HIP * Fcol(RH_HAA); + + // Link LH_SHANK: + iit::rbd::transformInertia(LH_SHANK_Ic, frcTransf -> fr_LH_THIGH_X_fr_LH_SHANK, Ic_spare); + LH_THIGH_Ic += Ic_spare; + + Fcol(LH_KFE) = LH_SHANK_Ic.col(iit::rbd::AZ); + DATA(LH_KFE+6, LH_KFE+6) = Fcol(LH_KFE)(iit::rbd::AZ); + + Fcol(LH_KFE) = frcTransf -> fr_LH_THIGH_X_fr_LH_SHANK * Fcol(LH_KFE); + DATA(LH_KFE+6, LH_HFE+6) = F(iit::rbd::AZ,LH_KFE); + DATA(LH_HFE+6, LH_KFE+6) = DATA(LH_KFE+6, LH_HFE+6); + Fcol(LH_KFE) = frcTransf -> fr_LH_HIP_X_fr_LH_THIGH * Fcol(LH_KFE); + DATA(LH_KFE+6, LH_HAA+6) = F(iit::rbd::AZ,LH_KFE); + DATA(LH_HAA+6, LH_KFE+6) = DATA(LH_KFE+6, LH_HAA+6); + Fcol(LH_KFE) = frcTransf -> fr_base_X_fr_LH_HIP * Fcol(LH_KFE); + + // Link LH_THIGH: + iit::rbd::transformInertia(LH_THIGH_Ic, frcTransf -> fr_LH_HIP_X_fr_LH_THIGH, Ic_spare); + LH_HIP_Ic += Ic_spare; + + Fcol(LH_HFE) = LH_THIGH_Ic.col(iit::rbd::AZ); + DATA(LH_HFE+6, LH_HFE+6) = Fcol(LH_HFE)(iit::rbd::AZ); + + Fcol(LH_HFE) = frcTransf -> fr_LH_HIP_X_fr_LH_THIGH * Fcol(LH_HFE); + DATA(LH_HFE+6, LH_HAA+6) = F(iit::rbd::AZ,LH_HFE); + DATA(LH_HAA+6, LH_HFE+6) = DATA(LH_HFE+6, LH_HAA+6); + Fcol(LH_HFE) = frcTransf -> fr_base_X_fr_LH_HIP * Fcol(LH_HFE); + + // Link LH_HIP: + iit::rbd::transformInertia(LH_HIP_Ic, frcTransf -> fr_base_X_fr_LH_HIP, Ic_spare); + base_Ic += Ic_spare; + + Fcol(LH_HAA) = LH_HIP_Ic.col(iit::rbd::AZ); + DATA(LH_HAA+6, LH_HAA+6) = Fcol(LH_HAA)(iit::rbd::AZ); + + Fcol(LH_HAA) = frcTransf -> fr_base_X_fr_LH_HIP * Fcol(LH_HAA); + + // Link RF_SHANK: + iit::rbd::transformInertia(RF_SHANK_Ic, frcTransf -> fr_RF_THIGH_X_fr_RF_SHANK, Ic_spare); + RF_THIGH_Ic += Ic_spare; + + Fcol(RF_KFE) = RF_SHANK_Ic.col(iit::rbd::AZ); + DATA(RF_KFE+6, RF_KFE+6) = Fcol(RF_KFE)(iit::rbd::AZ); + + Fcol(RF_KFE) = frcTransf -> fr_RF_THIGH_X_fr_RF_SHANK * Fcol(RF_KFE); + DATA(RF_KFE+6, RF_HFE+6) = F(iit::rbd::AZ,RF_KFE); + DATA(RF_HFE+6, RF_KFE+6) = DATA(RF_KFE+6, RF_HFE+6); + Fcol(RF_KFE) = frcTransf -> fr_RF_HIP_X_fr_RF_THIGH * Fcol(RF_KFE); + DATA(RF_KFE+6, RF_HAA+6) = F(iit::rbd::AZ,RF_KFE); + DATA(RF_HAA+6, RF_KFE+6) = DATA(RF_KFE+6, RF_HAA+6); + Fcol(RF_KFE) = frcTransf -> fr_base_X_fr_RF_HIP * Fcol(RF_KFE); + + // Link RF_THIGH: + iit::rbd::transformInertia(RF_THIGH_Ic, frcTransf -> fr_RF_HIP_X_fr_RF_THIGH, Ic_spare); + RF_HIP_Ic += Ic_spare; + + Fcol(RF_HFE) = RF_THIGH_Ic.col(iit::rbd::AZ); + DATA(RF_HFE+6, RF_HFE+6) = Fcol(RF_HFE)(iit::rbd::AZ); + + Fcol(RF_HFE) = frcTransf -> fr_RF_HIP_X_fr_RF_THIGH * Fcol(RF_HFE); + DATA(RF_HFE+6, RF_HAA+6) = F(iit::rbd::AZ,RF_HFE); + DATA(RF_HAA+6, RF_HFE+6) = DATA(RF_HFE+6, RF_HAA+6); + Fcol(RF_HFE) = frcTransf -> fr_base_X_fr_RF_HIP * Fcol(RF_HFE); + + // Link RF_HIP: + iit::rbd::transformInertia(RF_HIP_Ic, frcTransf -> fr_base_X_fr_RF_HIP, Ic_spare); + base_Ic += Ic_spare; + + Fcol(RF_HAA) = RF_HIP_Ic.col(iit::rbd::AZ); + DATA(RF_HAA+6, RF_HAA+6) = Fcol(RF_HAA)(iit::rbd::AZ); + + Fcol(RF_HAA) = frcTransf -> fr_base_X_fr_RF_HIP * Fcol(RF_HAA); + + // Link LF_SHANK: + iit::rbd::transformInertia(LF_SHANK_Ic, frcTransf -> fr_LF_THIGH_X_fr_LF_SHANK, Ic_spare); + LF_THIGH_Ic += Ic_spare; + + Fcol(LF_KFE) = LF_SHANK_Ic.col(iit::rbd::AZ); + DATA(LF_KFE+6, LF_KFE+6) = Fcol(LF_KFE)(iit::rbd::AZ); + + Fcol(LF_KFE) = frcTransf -> fr_LF_THIGH_X_fr_LF_SHANK * Fcol(LF_KFE); + DATA(LF_KFE+6, LF_HFE+6) = F(iit::rbd::AZ,LF_KFE); + DATA(LF_HFE+6, LF_KFE+6) = DATA(LF_KFE+6, LF_HFE+6); + Fcol(LF_KFE) = frcTransf -> fr_LF_HIP_X_fr_LF_THIGH * Fcol(LF_KFE); + DATA(LF_KFE+6, LF_HAA+6) = F(iit::rbd::AZ,LF_KFE); + DATA(LF_HAA+6, LF_KFE+6) = DATA(LF_KFE+6, LF_HAA+6); + Fcol(LF_KFE) = frcTransf -> fr_base_X_fr_LF_HIP * Fcol(LF_KFE); + + // Link LF_THIGH: + iit::rbd::transformInertia(LF_THIGH_Ic, frcTransf -> fr_LF_HIP_X_fr_LF_THIGH, Ic_spare); + LF_HIP_Ic += Ic_spare; + + Fcol(LF_HFE) = LF_THIGH_Ic.col(iit::rbd::AZ); + DATA(LF_HFE+6, LF_HFE+6) = Fcol(LF_HFE)(iit::rbd::AZ); + + Fcol(LF_HFE) = frcTransf -> fr_LF_HIP_X_fr_LF_THIGH * Fcol(LF_HFE); + DATA(LF_HFE+6, LF_HAA+6) = F(iit::rbd::AZ,LF_HFE); + DATA(LF_HAA+6, LF_HFE+6) = DATA(LF_HFE+6, LF_HAA+6); + Fcol(LF_HFE) = frcTransf -> fr_base_X_fr_LF_HIP * Fcol(LF_HFE); + + // Link LF_HIP: + iit::rbd::transformInertia(LF_HIP_Ic, frcTransf -> fr_base_X_fr_LF_HIP, Ic_spare); + base_Ic += Ic_spare; + + Fcol(LF_HAA) = LF_HIP_Ic.col(iit::rbd::AZ); + DATA(LF_HAA+6, LF_HAA+6) = Fcol(LF_HAA)(iit::rbd::AZ); + + Fcol(LF_HAA) = frcTransf -> fr_base_X_fr_LF_HIP * Fcol(LF_HAA); + + // Copies the upper-right block into the lower-left block, after transposing + JSIM:: template block<12, 6>(6,0) = (JSIM:: template block<6, 12>(0,6)).transpose(); + // The composite-inertia of the whole robot is the upper-left quadrant of the JSIM + JSIM:: template block<6,6>(0,0) = base_Ic; + return *this; +} + +#undef DATA +#undef F + +template +void iit::camel::dyn::tpl::JSIM::computeL() { + L = this -> template triangularView(); + // Joint RH_KFE, index 11 : + L(11, 11) = std::sqrt(L(11, 11)); + L(11, 10) = L(11, 10) / L(11, 11); + L(11, 9) = L(11, 9) / L(11, 11); + L(10, 10) = L(10, 10) - L(11, 10) * L(11, 10); + L(10, 9) = L(10, 9) - L(11, 10) * L(11, 9); + L(9, 9) = L(9, 9) - L(11, 9) * L(11, 9); + + // Joint RH_HFE, index 10 : + L(10, 10) = std::sqrt(L(10, 10)); + L(10, 9) = L(10, 9) / L(10, 10); + L(9, 9) = L(9, 9) - L(10, 9) * L(10, 9); + + // Joint RH_HAA, index 9 : + L(9, 9) = std::sqrt(L(9, 9)); + + // Joint LH_KFE, index 8 : + L(8, 8) = std::sqrt(L(8, 8)); + L(8, 7) = L(8, 7) / L(8, 8); + L(8, 6) = L(8, 6) / L(8, 8); + L(7, 7) = L(7, 7) - L(8, 7) * L(8, 7); + L(7, 6) = L(7, 6) - L(8, 7) * L(8, 6); + L(6, 6) = L(6, 6) - L(8, 6) * L(8, 6); + + // Joint LH_HFE, index 7 : + L(7, 7) = std::sqrt(L(7, 7)); + L(7, 6) = L(7, 6) / L(7, 7); + L(6, 6) = L(6, 6) - L(7, 6) * L(7, 6); + + // Joint LH_HAA, index 6 : + L(6, 6) = std::sqrt(L(6, 6)); + + // Joint RF_KFE, index 5 : + L(5, 5) = std::sqrt(L(5, 5)); + L(5, 4) = L(5, 4) / L(5, 5); + L(5, 3) = L(5, 3) / L(5, 5); + L(4, 4) = L(4, 4) - L(5, 4) * L(5, 4); + L(4, 3) = L(4, 3) - L(5, 4) * L(5, 3); + L(3, 3) = L(3, 3) - L(5, 3) * L(5, 3); + + // Joint RF_HFE, index 4 : + L(4, 4) = std::sqrt(L(4, 4)); + L(4, 3) = L(4, 3) / L(4, 4); + L(3, 3) = L(3, 3) - L(4, 3) * L(4, 3); + + // Joint RF_HAA, index 3 : + L(3, 3) = std::sqrt(L(3, 3)); + + // Joint LF_KFE, index 2 : + L(2, 2) = std::sqrt(L(2, 2)); + L(2, 1) = L(2, 1) / L(2, 2); + L(2, 0) = L(2, 0) / L(2, 2); + L(1, 1) = L(1, 1) - L(2, 1) * L(2, 1); + L(1, 0) = L(1, 0) - L(2, 1) * L(2, 0); + L(0, 0) = L(0, 0) - L(2, 0) * L(2, 0); + + // Joint LF_HFE, index 1 : + L(1, 1) = std::sqrt(L(1, 1)); + L(1, 0) = L(1, 0) / L(1, 1); + L(0, 0) = L(0, 0) - L(1, 0) * L(1, 0); + + // Joint LF_HAA, index 0 : + L(0, 0) = std::sqrt(L(0, 0)); + +} + +template +void iit::camel::dyn::tpl::JSIM::computeInverse() { + computeLInverse(); + + inverse(0, 0) = + (Linv(0, 0) * Linv(0, 0)); + inverse(1, 1) = + (Linv(1, 0) * Linv(1, 0)) + (Linv(1, 1) * Linv(1, 1)); + inverse(1, 0) = + (Linv(1, 0) * Linv(0, 0)); + inverse(0, 1) = inverse(1, 0); + inverse(2, 2) = + (Linv(2, 0) * Linv(2, 0)) + (Linv(2, 1) * Linv(2, 1)) + (Linv(2, 2) * Linv(2, 2)); + inverse(2, 1) = + (Linv(2, 0) * Linv(1, 0)) + (Linv(2, 1) * Linv(1, 1)); + inverse(1, 2) = inverse(2, 1); + inverse(2, 0) = + (Linv(2, 0) * Linv(0, 0)); + inverse(0, 2) = inverse(2, 0); + inverse(3, 3) = + (Linv(3, 3) * Linv(3, 3)); + inverse(4, 4) = + (Linv(4, 3) * Linv(4, 3)) + (Linv(4, 4) * Linv(4, 4)); + inverse(4, 3) = + (Linv(4, 3) * Linv(3, 3)); + inverse(3, 4) = inverse(4, 3); + inverse(5, 5) = + (Linv(5, 3) * Linv(5, 3)) + (Linv(5, 4) * Linv(5, 4)) + (Linv(5, 5) * Linv(5, 5)); + inverse(5, 4) = + (Linv(5, 3) * Linv(4, 3)) + (Linv(5, 4) * Linv(4, 4)); + inverse(4, 5) = inverse(5, 4); + inverse(5, 3) = + (Linv(5, 3) * Linv(3, 3)); + inverse(3, 5) = inverse(5, 3); + inverse(6, 6) = + (Linv(6, 6) * Linv(6, 6)); + inverse(7, 7) = + (Linv(7, 6) * Linv(7, 6)) + (Linv(7, 7) * Linv(7, 7)); + inverse(7, 6) = + (Linv(7, 6) * Linv(6, 6)); + inverse(6, 7) = inverse(7, 6); + inverse(8, 8) = + (Linv(8, 6) * Linv(8, 6)) + (Linv(8, 7) * Linv(8, 7)) + (Linv(8, 8) * Linv(8, 8)); + inverse(8, 7) = + (Linv(8, 6) * Linv(7, 6)) + (Linv(8, 7) * Linv(7, 7)); + inverse(7, 8) = inverse(8, 7); + inverse(8, 6) = + (Linv(8, 6) * Linv(6, 6)); + inverse(6, 8) = inverse(8, 6); + inverse(9, 9) = + (Linv(9, 9) * Linv(9, 9)); + inverse(10, 10) = + (Linv(10, 9) * Linv(10, 9)) + (Linv(10, 10) * Linv(10, 10)); + inverse(10, 9) = + (Linv(10, 9) * Linv(9, 9)); + inverse(9, 10) = inverse(10, 9); + inverse(11, 11) = + (Linv(11, 9) * Linv(11, 9)) + (Linv(11, 10) * Linv(11, 10)) + (Linv(11, 11) * Linv(11, 11)); + inverse(11, 10) = + (Linv(11, 9) * Linv(10, 9)) + (Linv(11, 10) * Linv(10, 10)); + inverse(10, 11) = inverse(11, 10); + inverse(11, 9) = + (Linv(11, 9) * Linv(9, 9)); + inverse(9, 11) = inverse(11, 9); +} + +template +void iit::camel::dyn::tpl::JSIM::computeLInverse() { + //assumes L has been computed already + Linv(0, 0) = 1 / L(0, 0); + Linv(1, 1) = 1 / L(1, 1); + Linv(2, 2) = 1 / L(2, 2); + Linv(3, 3) = 1 / L(3, 3); + Linv(4, 4) = 1 / L(4, 4); + Linv(5, 5) = 1 / L(5, 5); + Linv(6, 6) = 1 / L(6, 6); + Linv(7, 7) = 1 / L(7, 7); + Linv(8, 8) = 1 / L(8, 8); + Linv(9, 9) = 1 / L(9, 9); + Linv(10, 10) = 1 / L(10, 10); + Linv(11, 11) = 1 / L(11, 11); + Linv(1, 0) = - Linv(0, 0) * ((Linv(1, 1) * L(1, 0)) + 0); + Linv(2, 1) = - Linv(1, 1) * ((Linv(2, 2) * L(2, 1)) + 0); + Linv(2, 0) = - Linv(0, 0) * ((Linv(2, 1) * L(1, 0)) + (Linv(2, 2) * L(2, 0)) + 0); + Linv(4, 3) = - Linv(3, 3) * ((Linv(4, 4) * L(4, 3)) + 0); + Linv(5, 4) = - Linv(4, 4) * ((Linv(5, 5) * L(5, 4)) + 0); + Linv(5, 3) = - Linv(3, 3) * ((Linv(5, 4) * L(4, 3)) + (Linv(5, 5) * L(5, 3)) + 0); + Linv(7, 6) = - Linv(6, 6) * ((Linv(7, 7) * L(7, 6)) + 0); + Linv(8, 7) = - Linv(7, 7) * ((Linv(8, 8) * L(8, 7)) + 0); + Linv(8, 6) = - Linv(6, 6) * ((Linv(8, 7) * L(7, 6)) + (Linv(8, 8) * L(8, 6)) + 0); + Linv(10, 9) = - Linv(9, 9) * ((Linv(10, 10) * L(10, 9)) + 0); + Linv(11, 10) = - Linv(10, 10) * ((Linv(11, 11) * L(11, 10)) + 0); + Linv(11, 9) = - Linv(9, 9) * ((Linv(11, 10) * L(10, 9)) + (Linv(11, 11) * L(11, 9)) + 0); +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/kinematics_parameters.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/kinematics_parameters.h new file mode 100644 index 000000000..4dbd9ef40 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/kinematics_parameters.h @@ -0,0 +1,11 @@ +#ifndef _CAMEL_PARAMETERS_GETTERS_ +#define _CAMEL_PARAMETERS_GETTERS_ + +namespace iit { +namespace camel { + + + +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/link_data_map.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/link_data_map.h new file mode 100644 index 000000000..7fc655461 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/link_data_map.h @@ -0,0 +1,136 @@ +#ifndef IIT_CAMEL_LINK_DATA_MAP_H_ +#define IIT_CAMEL_LINK_DATA_MAP_H_ + +#include "declarations.h" + +namespace iit { +namespace camel { + +/** + * A very simple container to associate a generic data item to each link + */ +template class LinkDataMap { +private: + T data[linksCount]; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + LinkDataMap() {}; + LinkDataMap(const T& defaultValue); + LinkDataMap(const LinkDataMap& rhs); + LinkDataMap& operator=(const LinkDataMap& rhs); + LinkDataMap& operator=(const T& rhs); + T& operator[](LinkIdentifiers which); + const T& operator[](LinkIdentifiers which) const; +private: + void copydata(const LinkDataMap& rhs); + void assigndata(const T& commonValue); +}; + +template inline +LinkDataMap::LinkDataMap(const T& value) { + assigndata(value); +} + +template inline +LinkDataMap::LinkDataMap(const LinkDataMap& rhs) +{ + copydata(rhs); +} + +template inline +LinkDataMap& LinkDataMap::operator=(const LinkDataMap& rhs) +{ + if(&rhs != this) { + copydata(rhs); + } + return *this; +} + +template inline +LinkDataMap& LinkDataMap::operator=(const T& value) +{ + assigndata(value); + return *this; +} + +template inline +T& LinkDataMap::operator[](LinkIdentifiers l) { + return data[l]; +} + +template inline +const T& LinkDataMap::operator[](LinkIdentifiers l) const { + return data[l]; +} + +template inline +void LinkDataMap::copydata(const LinkDataMap& rhs) { + data[BASE] = rhs[BASE]; + data[LF_HIP] = rhs[LF_HIP]; + data[LF_THIGH] = rhs[LF_THIGH]; + data[LF_SHANK] = rhs[LF_SHANK]; + data[RF_HIP] = rhs[RF_HIP]; + data[RF_THIGH] = rhs[RF_THIGH]; + data[RF_SHANK] = rhs[RF_SHANK]; + data[LH_HIP] = rhs[LH_HIP]; + data[LH_THIGH] = rhs[LH_THIGH]; + data[LH_SHANK] = rhs[LH_SHANK]; + data[RH_HIP] = rhs[RH_HIP]; + data[RH_THIGH] = rhs[RH_THIGH]; + data[RH_SHANK] = rhs[RH_SHANK]; +} + +template inline +void LinkDataMap::assigndata(const T& value) { + data[BASE] = value; + data[LF_HIP] = value; + data[LF_THIGH] = value; + data[LF_SHANK] = value; + data[RF_HIP] = value; + data[RF_THIGH] = value; + data[RF_SHANK] = value; + data[LH_HIP] = value; + data[LH_THIGH] = value; + data[LH_SHANK] = value; + data[RH_HIP] = value; + data[RH_THIGH] = value; + data[RH_SHANK] = value; +} + +template inline +std::ostream& operator<<(std::ostream& out, const LinkDataMap& map) { + out + << " base = " + << map[BASE] + << " LF_HIP = " + << map[LF_HIP] + << " LF_THIGH = " + << map[LF_THIGH] + << " LF_SHANK = " + << map[LF_SHANK] + << " RF_HIP = " + << map[RF_HIP] + << " RF_THIGH = " + << map[RF_THIGH] + << " RF_SHANK = " + << map[RF_SHANK] + << " LH_HIP = " + << map[LH_HIP] + << " LH_THIGH = " + << map[LH_THIGH] + << " LH_SHANK = " + << map[LH_SHANK] + << " RH_HIP = " + << map[RH_HIP] + << " RH_THIGH = " + << map[RH_THIGH] + << " RH_SHANK = " + << map[RH_SHANK] + ; + return out; +} + +} +} +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.cpp new file mode 100644 index 000000000..7a1c6bfad --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.cpp @@ -0,0 +1,104 @@ +#include +#include +#include "inertia_properties.h" +#include "transforms.h" +//#include "miscellaneous.h" + +namespace iit { +namespace camel { + + template + typename iit::rbd::Core::Vector3 getWholeBodyCOM( + const dyn::tpl::InertiaProperties::Trait> &inertiaProps, + const tpl::HomogeneousTransforms::Trait> &ht) { + + using Vec3 = typename iit::rbd::Core::Vector3; + Vec3 tmpSum = Vec3::Zero(); + + tmpSum += inertiaProps.getCOM_base() * inertiaProps.getMass_base(); + + using HomogeneousTransformsScalar_t = typename tpl::HomogeneousTransforms::Trait>; + typename HomogeneousTransformsScalar_t::MatrixType tmpX(HomogeneousTransformsScalar_t::MatrixType::Identity()); + typename HomogeneousTransformsScalar_t::MatrixType base_X_LF_HAA_chain; + typename HomogeneousTransformsScalar_t::MatrixType base_X_RF_HAA_chain; + typename HomogeneousTransformsScalar_t::MatrixType base_X_LH_HAA_chain; + typename HomogeneousTransformsScalar_t::MatrixType base_X_RH_HAA_chain; + + base_X_LF_HAA_chain = tmpX * ht.fr_base_X_fr_LF_HIP; + tmpSum += inertiaProps.getMass_LF_HIP() * + (iit::rbd::Utils::transform(base_X_LF_HAA_chain, inertiaProps.getCOM_LF_HIP())); + + base_X_LF_HAA_chain = base_X_LF_HAA_chain * ht.fr_LF_HIP_X_fr_LF_THIGH; + tmpSum += inertiaProps.getMass_LF_THIGH() * + (iit::rbd::Utils::transform(base_X_LF_HAA_chain, inertiaProps.getCOM_LF_THIGH())); + + base_X_LF_HAA_chain = base_X_LF_HAA_chain * ht.fr_LF_THIGH_X_fr_LF_SHANK; + tmpSum += inertiaProps.getMass_LF_SHANK() * + (iit::rbd::Utils::transform(base_X_LF_HAA_chain, inertiaProps.getCOM_LF_SHANK())); + + base_X_RF_HAA_chain = tmpX * ht.fr_base_X_fr_RF_HIP; + tmpSum += inertiaProps.getMass_RF_HIP() * + (iit::rbd::Utils::transform(base_X_RF_HAA_chain, inertiaProps.getCOM_RF_HIP())); + + base_X_RF_HAA_chain = base_X_RF_HAA_chain * ht.fr_RF_HIP_X_fr_RF_THIGH; + tmpSum += inertiaProps.getMass_RF_THIGH() * + (iit::rbd::Utils::transform(base_X_RF_HAA_chain, inertiaProps.getCOM_RF_THIGH())); + + base_X_RF_HAA_chain = base_X_RF_HAA_chain * ht.fr_RF_THIGH_X_fr_RF_SHANK; + tmpSum += inertiaProps.getMass_RF_SHANK() * + (iit::rbd::Utils::transform(base_X_RF_HAA_chain, inertiaProps.getCOM_RF_SHANK())); + + base_X_LH_HAA_chain = tmpX * ht.fr_base_X_fr_LH_HIP; + tmpSum += inertiaProps.getMass_LH_HIP() * + (iit::rbd::Utils::transform(base_X_LH_HAA_chain, inertiaProps.getCOM_LH_HIP())); + + base_X_LH_HAA_chain = base_X_LH_HAA_chain * ht.fr_LH_HIP_X_fr_LH_THIGH; + tmpSum += inertiaProps.getMass_LH_THIGH() * + (iit::rbd::Utils::transform(base_X_LH_HAA_chain, inertiaProps.getCOM_LH_THIGH())); + + base_X_LH_HAA_chain = base_X_LH_HAA_chain * ht.fr_LH_THIGH_X_fr_LH_SHANK; + tmpSum += inertiaProps.getMass_LH_SHANK() * + (iit::rbd::Utils::transform(base_X_LH_HAA_chain, inertiaProps.getCOM_LH_SHANK())); + + base_X_RH_HAA_chain = tmpX * ht.fr_base_X_fr_RH_HIP; + tmpSum += inertiaProps.getMass_RH_HIP() * + (iit::rbd::Utils::transform(base_X_RH_HAA_chain, inertiaProps.getCOM_RH_HIP())); + + base_X_RH_HAA_chain = base_X_RH_HAA_chain * ht.fr_RH_HIP_X_fr_RH_THIGH; + tmpSum += inertiaProps.getMass_RH_THIGH() * + (iit::rbd::Utils::transform(base_X_RH_HAA_chain, inertiaProps.getCOM_RH_THIGH())); + + base_X_RH_HAA_chain = base_X_RH_HAA_chain * ht.fr_RH_THIGH_X_fr_RH_SHANK; + tmpSum += inertiaProps.getMass_RH_SHANK() * + (iit::rbd::Utils::transform(base_X_RH_HAA_chain, inertiaProps.getCOM_RH_SHANK())); + + tmpSum *= SCALAR_T(1.0)/ inertiaProps.getTotalMass(); + return tmpSum; + } + + template + typename iit::rbd::Core::Vector3 getWholeBodyCOM( + const dyn::tpl::InertiaProperties::Trait> &inertiaProps, + const tpl::JointState &q, + tpl::HomogeneousTransforms::Trait> &ht) { + // First updates the coordinate transforms that will be used by the routine + ht.fr_base_X_fr_LF_HIP(q); + ht.fr_base_X_fr_RF_HIP(q); + ht.fr_base_X_fr_LH_HIP(q); + ht.fr_base_X_fr_RH_HIP(q); + ht.fr_LF_HIP_X_fr_LF_THIGH(q); + ht.fr_LF_THIGH_X_fr_LF_SHANK(q); + ht.fr_RF_HIP_X_fr_RF_THIGH(q); + ht.fr_RF_THIGH_X_fr_RF_SHANK(q); + ht.fr_LH_HIP_X_fr_LH_THIGH(q); + ht.fr_LH_THIGH_X_fr_LH_SHANK(q); + ht.fr_RH_HIP_X_fr_RH_THIGH(q); + ht.fr_RH_THIGH_X_fr_RH_SHANK(q); + + // The actual calculus + return getWholeBodyCOM(inertiaProps, ht); + } + + +} // namespace camel +} // namespace iit \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.h new file mode 100644 index 000000000..79c3f95b0 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/miscellaneous.h @@ -0,0 +1,50 @@ +#ifndef IIT_ROBCOGEN__CAMEL_MISCELLANEOUS_H_ +#define IIT_ROBCOGEN__CAMEL_MISCELLANEOUS_H_ + +#include "inertia_properties.h" +#include "transforms.h" +#include + +namespace iit { +namespace camel { + +/** \name Center of mass calculation + * Computes the Center Of Mass (COM) position of the whole robot, in + * base coordinates. + * + * Common parameters are the inertia properties of the robot and the set + * of homogeneous coordinate transforms. If a joint status variable is + * also passed, then the transforms are updated accordingly; otherwise, + * they are not modified before being used. + */ +///@{ +/** + * \param inertia the inertia properties of the links of the robot + * \param transforms the homogeneous coordinate transforms of the robot + * \return the position of the Center Of Mass of the whole robot, expressed + * in base coordinates + */ +template +typename iit::rbd::Core::Vector3 getWholeBodyCOM( + const dyn::tpl::InertiaProperties::Trait>& inertia, + const tpl::HomogeneousTransforms::Trait>& transforms); +/** + * \param inertia the inertia properties of the links of the robot + * \param q the joint status vector describing the configuration of the robot + * \param transforms the homogeneous coordinate transforms of the robot + * \return the position of the Center Of Mass of the whole robot, expressed + * in base coordinates + */ +template +typename iit::rbd::Core::Vector3 getWholeBodyCOM( + const dyn::tpl::InertiaProperties::Trait>& inertia, + const tpl::JointState& q, + tpl::HomogeneousTransforms::Trait>& transforms); +///@} + +} +} + +#include "miscellaneous.cpp" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/traits.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/traits.h new file mode 100644 index 000000000..80e951952 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/traits.h @@ -0,0 +1,67 @@ +#ifndef IIT_ROBOGEN__CAMEL_TRAITS_H_ +#define IIT_ROBOGEN__CAMEL_TRAITS_H_ + +#include "declarations.h" +#include "transforms.h" +#include "inverse_dynamics.h" +#include "forward_dynamics.h" +#include "jsim.h" +#include "inertia_properties.h" +#include "jacobians.h" +#include + + +namespace iit { +namespace camel { + +namespace tpl { + +template +struct Traits { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef SCALAR S; + + typedef typename camel::JointIdentifiers JointID; + typedef typename camel::LinkIdentifiers LinkID; + typedef typename iit::rbd::tpl::TraitSelector::Trait Trait; + + typedef typename camel::tpl::JointState JointState; + + + + typedef typename camel::tpl::HomogeneousTransforms HomogeneousTransforms; + typedef typename camel::tpl::MotionTransforms MotionTransforms; + typedef typename camel::tpl::ForceTransforms ForceTransforms; + typedef typename camel::tpl::Jacobians Jacobians; + + typedef typename iit::camel::dyn::tpl::InertiaProperties InertiaProperties; + typedef typename iit::camel::dyn::tpl::ForwardDynamics FwdDynEngine; + typedef typename iit::camel::dyn::tpl::InverseDynamics InvDynEngine; + typedef typename iit::camel::dyn::tpl::JSIM JSIM; + + static const int joints_count = camel::jointsCount; + static const int links_count = camel::linksCount; + static const bool floating_base = true; + + static inline const JointID* orderedJointIDs(); + static inline const LinkID* orderedLinkIDs(); +}; + +template +inline const typename Traits::JointID* Traits::orderedJointIDs() { + return camel::orderedJointIDs; +} +template +inline const typename Traits::LinkID* Traits::orderedLinkIDs() { + return camel::orderedLinkIDs; +} + +} + +typedef tpl::Traits Traits; // default instantiation - backward compatibility... + +} +} + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.h new file mode 100644 index 000000000..38cc90347 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.h @@ -0,0 +1,1431 @@ +#ifndef CAMEL_TRANSFORMS_H_ +#define CAMEL_TRANSFORMS_H_ + +#include +#include +#include "declarations.h" +#include +#include "kinematics_parameters.h" + +namespace iit { +namespace camel { + +template +class TransformMotion : public iit::rbd::SpatialTransformBase, M> { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +template +class TransformForce : public iit::rbd::SpatialTransformBase, M> { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +template +class TransformHomogeneous : public iit::rbd::HomogeneousTransformBase, M> { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +namespace tpl { + + +/** + * The class for the 6-by-6 coordinates transformation matrices for + * spatial motion vectors. + */ +template +class MotionTransforms { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef typename TRAIT::Scalar Scalar; + + typedef JointState JState; + class Dummy {}; + typedef typename TransformMotion::MatrixType MatrixType; +public: + class Type_fr_base_X_fr_LF_FOOT : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_FOOT(); + const Type_fr_base_X_fr_LF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LF_FOOT_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_FOOT_X_fr_base(); + const Type_fr_LF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_FOOT : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_FOOT(); + const Type_fr_base_X_fr_LH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LH_FOOT_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_FOOT_X_fr_base(); + const Type_fr_LH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_FOOT : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_FOOT(); + const Type_fr_base_X_fr_RF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RF_FOOT_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_FOOT_X_fr_base(); + const Type_fr_RF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_FOOT : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_FOOT(); + const Type_fr_base_X_fr_RH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RH_FOOT_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_FOOT_X_fr_base(); + const Type_fr_RH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HAA : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HAA(); + const Type_fr_base_X_fr_LF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HFE(); + const Type_fr_base_X_fr_LF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_KFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_KFE(); + const Type_fr_base_X_fr_LF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HAA : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HAA(); + const Type_fr_base_X_fr_LH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HFE(); + const Type_fr_base_X_fr_LH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_KFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_KFE(); + const Type_fr_base_X_fr_LH_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HAA : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HAA(); + const Type_fr_base_X_fr_RF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HFE(); + const Type_fr_base_X_fr_RF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_KFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_KFE(); + const Type_fr_base_X_fr_RF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HAA : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HAA(); + const Type_fr_base_X_fr_RH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HFE(); + const Type_fr_base_X_fr_RH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_KFE : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_KFE(); + const Type_fr_base_X_fr_RH_KFE& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_base(); + const Type_fr_LF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HIP(); + const Type_fr_base_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_HIP(); + const Type_fr_LF_THIGH_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_LF_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_LF_THIGH(); + const Type_fr_LF_HIP_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_SHANK_X_fr_LF_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_SHANK_X_fr_LF_THIGH(); + const Type_fr_LF_SHANK_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_SHANK : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_SHANK(); + const Type_fr_LF_THIGH_X_fr_LF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_base(); + const Type_fr_RF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HIP(); + const Type_fr_base_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_HIP(); + const Type_fr_RF_THIGH_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_RF_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_RF_THIGH(); + const Type_fr_RF_HIP_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_SHANK_X_fr_RF_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_SHANK_X_fr_RF_THIGH(); + const Type_fr_RF_SHANK_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_SHANK : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_SHANK(); + const Type_fr_RF_THIGH_X_fr_RF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_base(); + const Type_fr_LH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HIP(); + const Type_fr_base_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_HIP(); + const Type_fr_LH_THIGH_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_LH_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_LH_THIGH(); + const Type_fr_LH_HIP_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_SHANK_X_fr_LH_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_SHANK_X_fr_LH_THIGH(); + const Type_fr_LH_SHANK_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_SHANK : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_SHANK(); + const Type_fr_LH_THIGH_X_fr_LH_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_base : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_base(); + const Type_fr_RH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HIP(); + const Type_fr_base_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_HIP : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_HIP(); + const Type_fr_RH_THIGH_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_RH_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_RH_THIGH(); + const Type_fr_RH_HIP_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_SHANK_X_fr_RH_THIGH : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_SHANK_X_fr_RH_THIGH(); + const Type_fr_RH_SHANK_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_SHANK : public TransformMotion + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_SHANK(); + const Type_fr_RH_THIGH_X_fr_RH_SHANK& update(const JState&); + protected: + }; + +public: + MotionTransforms(); + void updateParameters(); + Type_fr_base_X_fr_LF_FOOT fr_base_X_fr_LF_FOOT; + Type_fr_LF_FOOT_X_fr_base fr_LF_FOOT_X_fr_base; + Type_fr_base_X_fr_LH_FOOT fr_base_X_fr_LH_FOOT; + Type_fr_LH_FOOT_X_fr_base fr_LH_FOOT_X_fr_base; + Type_fr_base_X_fr_RF_FOOT fr_base_X_fr_RF_FOOT; + Type_fr_RF_FOOT_X_fr_base fr_RF_FOOT_X_fr_base; + Type_fr_base_X_fr_RH_FOOT fr_base_X_fr_RH_FOOT; + Type_fr_RH_FOOT_X_fr_base fr_RH_FOOT_X_fr_base; + Type_fr_base_X_fr_LF_HAA fr_base_X_fr_LF_HAA; + Type_fr_base_X_fr_LF_HFE fr_base_X_fr_LF_HFE; + Type_fr_base_X_fr_LF_KFE fr_base_X_fr_LF_KFE; + Type_fr_base_X_fr_LH_HAA fr_base_X_fr_LH_HAA; + Type_fr_base_X_fr_LH_HFE fr_base_X_fr_LH_HFE; + Type_fr_base_X_fr_LH_KFE fr_base_X_fr_LH_KFE; + Type_fr_base_X_fr_RF_HAA fr_base_X_fr_RF_HAA; + Type_fr_base_X_fr_RF_HFE fr_base_X_fr_RF_HFE; + Type_fr_base_X_fr_RF_KFE fr_base_X_fr_RF_KFE; + Type_fr_base_X_fr_RH_HAA fr_base_X_fr_RH_HAA; + Type_fr_base_X_fr_RH_HFE fr_base_X_fr_RH_HFE; + Type_fr_base_X_fr_RH_KFE fr_base_X_fr_RH_KFE; + Type_fr_LF_HIP_X_fr_base fr_LF_HIP_X_fr_base; + Type_fr_base_X_fr_LF_HIP fr_base_X_fr_LF_HIP; + Type_fr_LF_THIGH_X_fr_LF_HIP fr_LF_THIGH_X_fr_LF_HIP; + Type_fr_LF_HIP_X_fr_LF_THIGH fr_LF_HIP_X_fr_LF_THIGH; + Type_fr_LF_SHANK_X_fr_LF_THIGH fr_LF_SHANK_X_fr_LF_THIGH; + Type_fr_LF_THIGH_X_fr_LF_SHANK fr_LF_THIGH_X_fr_LF_SHANK; + Type_fr_RF_HIP_X_fr_base fr_RF_HIP_X_fr_base; + Type_fr_base_X_fr_RF_HIP fr_base_X_fr_RF_HIP; + Type_fr_RF_THIGH_X_fr_RF_HIP fr_RF_THIGH_X_fr_RF_HIP; + Type_fr_RF_HIP_X_fr_RF_THIGH fr_RF_HIP_X_fr_RF_THIGH; + Type_fr_RF_SHANK_X_fr_RF_THIGH fr_RF_SHANK_X_fr_RF_THIGH; + Type_fr_RF_THIGH_X_fr_RF_SHANK fr_RF_THIGH_X_fr_RF_SHANK; + Type_fr_LH_HIP_X_fr_base fr_LH_HIP_X_fr_base; + Type_fr_base_X_fr_LH_HIP fr_base_X_fr_LH_HIP; + Type_fr_LH_THIGH_X_fr_LH_HIP fr_LH_THIGH_X_fr_LH_HIP; + Type_fr_LH_HIP_X_fr_LH_THIGH fr_LH_HIP_X_fr_LH_THIGH; + Type_fr_LH_SHANK_X_fr_LH_THIGH fr_LH_SHANK_X_fr_LH_THIGH; + Type_fr_LH_THIGH_X_fr_LH_SHANK fr_LH_THIGH_X_fr_LH_SHANK; + Type_fr_RH_HIP_X_fr_base fr_RH_HIP_X_fr_base; + Type_fr_base_X_fr_RH_HIP fr_base_X_fr_RH_HIP; + Type_fr_RH_THIGH_X_fr_RH_HIP fr_RH_THIGH_X_fr_RH_HIP; + Type_fr_RH_HIP_X_fr_RH_THIGH fr_RH_HIP_X_fr_RH_THIGH; + Type_fr_RH_SHANK_X_fr_RH_THIGH fr_RH_SHANK_X_fr_RH_THIGH; + Type_fr_RH_THIGH_X_fr_RH_SHANK fr_RH_THIGH_X_fr_RH_SHANK; + +protected: + +}; //class 'MotionTransforms' + +/** + * The class for the 6-by-6 coordinates transformation matrices for + * spatial force vectors. + */ +template +class ForceTransforms { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef typename TRAIT::Scalar Scalar; + + typedef JointState JState; + class Dummy {}; + typedef typename TransformForce::MatrixType MatrixType; +public: + class Type_fr_base_X_fr_LF_FOOT : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_FOOT(); + const Type_fr_base_X_fr_LF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LF_FOOT_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_FOOT_X_fr_base(); + const Type_fr_LF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_FOOT : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_FOOT(); + const Type_fr_base_X_fr_LH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LH_FOOT_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_FOOT_X_fr_base(); + const Type_fr_LH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_FOOT : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_FOOT(); + const Type_fr_base_X_fr_RF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RF_FOOT_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_FOOT_X_fr_base(); + const Type_fr_RF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_FOOT : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_FOOT(); + const Type_fr_base_X_fr_RH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RH_FOOT_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_FOOT_X_fr_base(); + const Type_fr_RH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HAA : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HAA(); + const Type_fr_base_X_fr_LF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HFE(); + const Type_fr_base_X_fr_LF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_KFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_KFE(); + const Type_fr_base_X_fr_LF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HAA : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HAA(); + const Type_fr_base_X_fr_LH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HFE(); + const Type_fr_base_X_fr_LH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_KFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_KFE(); + const Type_fr_base_X_fr_LH_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HAA : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HAA(); + const Type_fr_base_X_fr_RF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HFE(); + const Type_fr_base_X_fr_RF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_KFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_KFE(); + const Type_fr_base_X_fr_RF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HAA : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HAA(); + const Type_fr_base_X_fr_RH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HFE(); + const Type_fr_base_X_fr_RH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_KFE : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_KFE(); + const Type_fr_base_X_fr_RH_KFE& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_base(); + const Type_fr_LF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HIP(); + const Type_fr_base_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_HIP(); + const Type_fr_LF_THIGH_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_LF_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_LF_THIGH(); + const Type_fr_LF_HIP_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_SHANK_X_fr_LF_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_SHANK_X_fr_LF_THIGH(); + const Type_fr_LF_SHANK_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_SHANK : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_SHANK(); + const Type_fr_LF_THIGH_X_fr_LF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_base(); + const Type_fr_RF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HIP(); + const Type_fr_base_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_HIP(); + const Type_fr_RF_THIGH_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_RF_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_RF_THIGH(); + const Type_fr_RF_HIP_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_SHANK_X_fr_RF_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_SHANK_X_fr_RF_THIGH(); + const Type_fr_RF_SHANK_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_SHANK : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_SHANK(); + const Type_fr_RF_THIGH_X_fr_RF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_base(); + const Type_fr_LH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HIP(); + const Type_fr_base_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_HIP(); + const Type_fr_LH_THIGH_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_LH_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_LH_THIGH(); + const Type_fr_LH_HIP_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_SHANK_X_fr_LH_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_SHANK_X_fr_LH_THIGH(); + const Type_fr_LH_SHANK_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_SHANK : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_SHANK(); + const Type_fr_LH_THIGH_X_fr_LH_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_base : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_base(); + const Type_fr_RH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HIP(); + const Type_fr_base_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_HIP : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_HIP(); + const Type_fr_RH_THIGH_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_RH_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_RH_THIGH(); + const Type_fr_RH_HIP_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_SHANK_X_fr_RH_THIGH : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_SHANK_X_fr_RH_THIGH(); + const Type_fr_RH_SHANK_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_SHANK : public TransformForce + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_SHANK(); + const Type_fr_RH_THIGH_X_fr_RH_SHANK& update(const JState&); + protected: + }; + +public: + ForceTransforms(); + void updateParameters(); + Type_fr_base_X_fr_LF_FOOT fr_base_X_fr_LF_FOOT; + Type_fr_LF_FOOT_X_fr_base fr_LF_FOOT_X_fr_base; + Type_fr_base_X_fr_LH_FOOT fr_base_X_fr_LH_FOOT; + Type_fr_LH_FOOT_X_fr_base fr_LH_FOOT_X_fr_base; + Type_fr_base_X_fr_RF_FOOT fr_base_X_fr_RF_FOOT; + Type_fr_RF_FOOT_X_fr_base fr_RF_FOOT_X_fr_base; + Type_fr_base_X_fr_RH_FOOT fr_base_X_fr_RH_FOOT; + Type_fr_RH_FOOT_X_fr_base fr_RH_FOOT_X_fr_base; + Type_fr_base_X_fr_LF_HAA fr_base_X_fr_LF_HAA; + Type_fr_base_X_fr_LF_HFE fr_base_X_fr_LF_HFE; + Type_fr_base_X_fr_LF_KFE fr_base_X_fr_LF_KFE; + Type_fr_base_X_fr_LH_HAA fr_base_X_fr_LH_HAA; + Type_fr_base_X_fr_LH_HFE fr_base_X_fr_LH_HFE; + Type_fr_base_X_fr_LH_KFE fr_base_X_fr_LH_KFE; + Type_fr_base_X_fr_RF_HAA fr_base_X_fr_RF_HAA; + Type_fr_base_X_fr_RF_HFE fr_base_X_fr_RF_HFE; + Type_fr_base_X_fr_RF_KFE fr_base_X_fr_RF_KFE; + Type_fr_base_X_fr_RH_HAA fr_base_X_fr_RH_HAA; + Type_fr_base_X_fr_RH_HFE fr_base_X_fr_RH_HFE; + Type_fr_base_X_fr_RH_KFE fr_base_X_fr_RH_KFE; + Type_fr_LF_HIP_X_fr_base fr_LF_HIP_X_fr_base; + Type_fr_base_X_fr_LF_HIP fr_base_X_fr_LF_HIP; + Type_fr_LF_THIGH_X_fr_LF_HIP fr_LF_THIGH_X_fr_LF_HIP; + Type_fr_LF_HIP_X_fr_LF_THIGH fr_LF_HIP_X_fr_LF_THIGH; + Type_fr_LF_SHANK_X_fr_LF_THIGH fr_LF_SHANK_X_fr_LF_THIGH; + Type_fr_LF_THIGH_X_fr_LF_SHANK fr_LF_THIGH_X_fr_LF_SHANK; + Type_fr_RF_HIP_X_fr_base fr_RF_HIP_X_fr_base; + Type_fr_base_X_fr_RF_HIP fr_base_X_fr_RF_HIP; + Type_fr_RF_THIGH_X_fr_RF_HIP fr_RF_THIGH_X_fr_RF_HIP; + Type_fr_RF_HIP_X_fr_RF_THIGH fr_RF_HIP_X_fr_RF_THIGH; + Type_fr_RF_SHANK_X_fr_RF_THIGH fr_RF_SHANK_X_fr_RF_THIGH; + Type_fr_RF_THIGH_X_fr_RF_SHANK fr_RF_THIGH_X_fr_RF_SHANK; + Type_fr_LH_HIP_X_fr_base fr_LH_HIP_X_fr_base; + Type_fr_base_X_fr_LH_HIP fr_base_X_fr_LH_HIP; + Type_fr_LH_THIGH_X_fr_LH_HIP fr_LH_THIGH_X_fr_LH_HIP; + Type_fr_LH_HIP_X_fr_LH_THIGH fr_LH_HIP_X_fr_LH_THIGH; + Type_fr_LH_SHANK_X_fr_LH_THIGH fr_LH_SHANK_X_fr_LH_THIGH; + Type_fr_LH_THIGH_X_fr_LH_SHANK fr_LH_THIGH_X_fr_LH_SHANK; + Type_fr_RH_HIP_X_fr_base fr_RH_HIP_X_fr_base; + Type_fr_base_X_fr_RH_HIP fr_base_X_fr_RH_HIP; + Type_fr_RH_THIGH_X_fr_RH_HIP fr_RH_THIGH_X_fr_RH_HIP; + Type_fr_RH_HIP_X_fr_RH_THIGH fr_RH_HIP_X_fr_RH_THIGH; + Type_fr_RH_SHANK_X_fr_RH_THIGH fr_RH_SHANK_X_fr_RH_THIGH; + Type_fr_RH_THIGH_X_fr_RH_SHANK fr_RH_THIGH_X_fr_RH_SHANK; + +protected: + +}; //class 'ForceTransforms' + +/** + * The class with the homogeneous (4x4) coordinates transformation + * matrices. + */ +template +class HomogeneousTransforms { +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef typename TRAIT::Scalar Scalar; + + typedef JointState JState; + class Dummy {}; + typedef typename TransformHomogeneous::MatrixType MatrixType; +public: + class Type_fr_base_X_fr_LF_FOOT : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_FOOT(); + const Type_fr_base_X_fr_LF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LF_FOOT_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_FOOT_X_fr_base(); + const Type_fr_LF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_FOOT : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_FOOT(); + const Type_fr_base_X_fr_LH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_LH_FOOT_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_FOOT_X_fr_base(); + const Type_fr_LH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_FOOT : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_FOOT(); + const Type_fr_base_X_fr_RF_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RF_FOOT_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_FOOT_X_fr_base(); + const Type_fr_RF_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_FOOT : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_FOOT(); + const Type_fr_base_X_fr_RH_FOOT& update(const JState&); + protected: + }; + + class Type_fr_RH_FOOT_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_FOOT_X_fr_base(); + const Type_fr_RH_FOOT_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HAA : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HAA(); + const Type_fr_base_X_fr_LF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HFE(); + const Type_fr_base_X_fr_LF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_KFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_KFE(); + const Type_fr_base_X_fr_LF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HAA : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HAA(); + const Type_fr_base_X_fr_LH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HFE(); + const Type_fr_base_X_fr_LH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_KFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_KFE(); + const Type_fr_base_X_fr_LH_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HAA : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HAA(); + const Type_fr_base_X_fr_RF_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HFE(); + const Type_fr_base_X_fr_RF_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_KFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_KFE(); + const Type_fr_base_X_fr_RF_KFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HAA : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HAA(); + const Type_fr_base_X_fr_RH_HAA& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HFE(); + const Type_fr_base_X_fr_RH_HFE& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_KFE : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_KFE(); + const Type_fr_base_X_fr_RH_KFE& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_base(); + const Type_fr_LF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LF_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LF_HIP(); + const Type_fr_base_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_HIP(); + const Type_fr_LF_THIGH_X_fr_LF_HIP& update(const JState&); + protected: + }; + + class Type_fr_LF_HIP_X_fr_LF_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_HIP_X_fr_LF_THIGH(); + const Type_fr_LF_HIP_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_SHANK_X_fr_LF_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_SHANK_X_fr_LF_THIGH(); + const Type_fr_LF_SHANK_X_fr_LF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LF_THIGH_X_fr_LF_SHANK : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LF_THIGH_X_fr_LF_SHANK(); + const Type_fr_LF_THIGH_X_fr_LF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_base(); + const Type_fr_RF_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RF_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RF_HIP(); + const Type_fr_base_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_HIP(); + const Type_fr_RF_THIGH_X_fr_RF_HIP& update(const JState&); + protected: + }; + + class Type_fr_RF_HIP_X_fr_RF_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_HIP_X_fr_RF_THIGH(); + const Type_fr_RF_HIP_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_SHANK_X_fr_RF_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_SHANK_X_fr_RF_THIGH(); + const Type_fr_RF_SHANK_X_fr_RF_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RF_THIGH_X_fr_RF_SHANK : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RF_THIGH_X_fr_RF_SHANK(); + const Type_fr_RF_THIGH_X_fr_RF_SHANK& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_base(); + const Type_fr_LH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_LH_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_LH_HIP(); + const Type_fr_base_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_HIP(); + const Type_fr_LH_THIGH_X_fr_LH_HIP& update(const JState&); + protected: + }; + + class Type_fr_LH_HIP_X_fr_LH_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_HIP_X_fr_LH_THIGH(); + const Type_fr_LH_HIP_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_SHANK_X_fr_LH_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_SHANK_X_fr_LH_THIGH(); + const Type_fr_LH_SHANK_X_fr_LH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_LH_THIGH_X_fr_LH_SHANK : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_LH_THIGH_X_fr_LH_SHANK(); + const Type_fr_LH_THIGH_X_fr_LH_SHANK& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_base : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_base(); + const Type_fr_RH_HIP_X_fr_base& update(const JState&); + protected: + }; + + class Type_fr_base_X_fr_RH_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_base_X_fr_RH_HIP(); + const Type_fr_base_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_HIP : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_HIP(); + const Type_fr_RH_THIGH_X_fr_RH_HIP& update(const JState&); + protected: + }; + + class Type_fr_RH_HIP_X_fr_RH_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_HIP_X_fr_RH_THIGH(); + const Type_fr_RH_HIP_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_SHANK_X_fr_RH_THIGH : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_SHANK_X_fr_RH_THIGH(); + const Type_fr_RH_SHANK_X_fr_RH_THIGH& update(const JState&); + protected: + }; + + class Type_fr_RH_THIGH_X_fr_RH_SHANK : public TransformHomogeneous + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Type_fr_RH_THIGH_X_fr_RH_SHANK(); + const Type_fr_RH_THIGH_X_fr_RH_SHANK& update(const JState&); + protected: + }; + +public: + HomogeneousTransforms(); + void updateParameters(); + Type_fr_base_X_fr_LF_FOOT fr_base_X_fr_LF_FOOT; + Type_fr_LF_FOOT_X_fr_base fr_LF_FOOT_X_fr_base; + Type_fr_base_X_fr_LH_FOOT fr_base_X_fr_LH_FOOT; + Type_fr_LH_FOOT_X_fr_base fr_LH_FOOT_X_fr_base; + Type_fr_base_X_fr_RF_FOOT fr_base_X_fr_RF_FOOT; + Type_fr_RF_FOOT_X_fr_base fr_RF_FOOT_X_fr_base; + Type_fr_base_X_fr_RH_FOOT fr_base_X_fr_RH_FOOT; + Type_fr_RH_FOOT_X_fr_base fr_RH_FOOT_X_fr_base; + Type_fr_base_X_fr_LF_HAA fr_base_X_fr_LF_HAA; + Type_fr_base_X_fr_LF_HFE fr_base_X_fr_LF_HFE; + Type_fr_base_X_fr_LF_KFE fr_base_X_fr_LF_KFE; + Type_fr_base_X_fr_LH_HAA fr_base_X_fr_LH_HAA; + Type_fr_base_X_fr_LH_HFE fr_base_X_fr_LH_HFE; + Type_fr_base_X_fr_LH_KFE fr_base_X_fr_LH_KFE; + Type_fr_base_X_fr_RF_HAA fr_base_X_fr_RF_HAA; + Type_fr_base_X_fr_RF_HFE fr_base_X_fr_RF_HFE; + Type_fr_base_X_fr_RF_KFE fr_base_X_fr_RF_KFE; + Type_fr_base_X_fr_RH_HAA fr_base_X_fr_RH_HAA; + Type_fr_base_X_fr_RH_HFE fr_base_X_fr_RH_HFE; + Type_fr_base_X_fr_RH_KFE fr_base_X_fr_RH_KFE; + Type_fr_LF_HIP_X_fr_base fr_LF_HIP_X_fr_base; + Type_fr_base_X_fr_LF_HIP fr_base_X_fr_LF_HIP; + Type_fr_LF_THIGH_X_fr_LF_HIP fr_LF_THIGH_X_fr_LF_HIP; + Type_fr_LF_HIP_X_fr_LF_THIGH fr_LF_HIP_X_fr_LF_THIGH; + Type_fr_LF_SHANK_X_fr_LF_THIGH fr_LF_SHANK_X_fr_LF_THIGH; + Type_fr_LF_THIGH_X_fr_LF_SHANK fr_LF_THIGH_X_fr_LF_SHANK; + Type_fr_RF_HIP_X_fr_base fr_RF_HIP_X_fr_base; + Type_fr_base_X_fr_RF_HIP fr_base_X_fr_RF_HIP; + Type_fr_RF_THIGH_X_fr_RF_HIP fr_RF_THIGH_X_fr_RF_HIP; + Type_fr_RF_HIP_X_fr_RF_THIGH fr_RF_HIP_X_fr_RF_THIGH; + Type_fr_RF_SHANK_X_fr_RF_THIGH fr_RF_SHANK_X_fr_RF_THIGH; + Type_fr_RF_THIGH_X_fr_RF_SHANK fr_RF_THIGH_X_fr_RF_SHANK; + Type_fr_LH_HIP_X_fr_base fr_LH_HIP_X_fr_base; + Type_fr_base_X_fr_LH_HIP fr_base_X_fr_LH_HIP; + Type_fr_LH_THIGH_X_fr_LH_HIP fr_LH_THIGH_X_fr_LH_HIP; + Type_fr_LH_HIP_X_fr_LH_THIGH fr_LH_HIP_X_fr_LH_THIGH; + Type_fr_LH_SHANK_X_fr_LH_THIGH fr_LH_SHANK_X_fr_LH_THIGH; + Type_fr_LH_THIGH_X_fr_LH_SHANK fr_LH_THIGH_X_fr_LH_SHANK; + Type_fr_RH_HIP_X_fr_base fr_RH_HIP_X_fr_base; + Type_fr_base_X_fr_RH_HIP fr_base_X_fr_RH_HIP; + Type_fr_RH_THIGH_X_fr_RH_HIP fr_RH_THIGH_X_fr_RH_HIP; + Type_fr_RH_HIP_X_fr_RH_THIGH fr_RH_HIP_X_fr_RH_THIGH; + Type_fr_RH_SHANK_X_fr_RH_THIGH fr_RH_SHANK_X_fr_RH_THIGH; + Type_fr_RH_THIGH_X_fr_RH_SHANK fr_RH_THIGH_X_fr_RH_SHANK; + +protected: + +}; //class 'HomogeneousTransforms' + +} + +using MotionTransforms = tpl::MotionTransforms; +using ForceTransforms = tpl::ForceTransforms; +using HomogeneousTransforms = tpl::HomogeneousTransforms; + +} +} + +#include "transforms.impl.h" + +#endif diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.impl.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.impl.h new file mode 100644 index 000000000..733b107e4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/test/camel/generated/transforms.impl.h @@ -0,0 +1,6058 @@ + +// Constructors +template +iit::camel::tpl::MotionTransforms::MotionTransforms + () + : + fr_base_X_fr_LF_FOOT(), + fr_LF_FOOT_X_fr_base(), + fr_base_X_fr_LH_FOOT(), + fr_LH_FOOT_X_fr_base(), + fr_base_X_fr_RF_FOOT(), + fr_RF_FOOT_X_fr_base(), + fr_base_X_fr_RH_FOOT(), + fr_RH_FOOT_X_fr_base(), + fr_base_X_fr_LF_HAA(), + fr_base_X_fr_LF_HFE(), + fr_base_X_fr_LF_KFE(), + fr_base_X_fr_LH_HAA(), + fr_base_X_fr_LH_HFE(), + fr_base_X_fr_LH_KFE(), + fr_base_X_fr_RF_HAA(), + fr_base_X_fr_RF_HFE(), + fr_base_X_fr_RF_KFE(), + fr_base_X_fr_RH_HAA(), + fr_base_X_fr_RH_HFE(), + fr_base_X_fr_RH_KFE(), + fr_LF_HIP_X_fr_base(), + fr_base_X_fr_LF_HIP(), + fr_LF_THIGH_X_fr_LF_HIP(), + fr_LF_HIP_X_fr_LF_THIGH(), + fr_LF_SHANK_X_fr_LF_THIGH(), + fr_LF_THIGH_X_fr_LF_SHANK(), + fr_RF_HIP_X_fr_base(), + fr_base_X_fr_RF_HIP(), + fr_RF_THIGH_X_fr_RF_HIP(), + fr_RF_HIP_X_fr_RF_THIGH(), + fr_RF_SHANK_X_fr_RF_THIGH(), + fr_RF_THIGH_X_fr_RF_SHANK(), + fr_LH_HIP_X_fr_base(), + fr_base_X_fr_LH_HIP(), + fr_LH_THIGH_X_fr_LH_HIP(), + fr_LH_HIP_X_fr_LH_THIGH(), + fr_LH_SHANK_X_fr_LH_THIGH(), + fr_LH_THIGH_X_fr_LH_SHANK(), + fr_RH_HIP_X_fr_base(), + fr_base_X_fr_RH_HIP(), + fr_RH_THIGH_X_fr_RH_HIP(), + fr_RH_HIP_X_fr_RH_THIGH(), + fr_RH_SHANK_X_fr_RH_THIGH(), + fr_RH_THIGH_X_fr_RH_SHANK() +{ + updateParameters(); +} +template +void iit::camel::tpl::MotionTransforms::updateParameters() { +} + +template +iit::camel::tpl::ForceTransforms::ForceTransforms + () + : + fr_base_X_fr_LF_FOOT(), + fr_LF_FOOT_X_fr_base(), + fr_base_X_fr_LH_FOOT(), + fr_LH_FOOT_X_fr_base(), + fr_base_X_fr_RF_FOOT(), + fr_RF_FOOT_X_fr_base(), + fr_base_X_fr_RH_FOOT(), + fr_RH_FOOT_X_fr_base(), + fr_base_X_fr_LF_HAA(), + fr_base_X_fr_LF_HFE(), + fr_base_X_fr_LF_KFE(), + fr_base_X_fr_LH_HAA(), + fr_base_X_fr_LH_HFE(), + fr_base_X_fr_LH_KFE(), + fr_base_X_fr_RF_HAA(), + fr_base_X_fr_RF_HFE(), + fr_base_X_fr_RF_KFE(), + fr_base_X_fr_RH_HAA(), + fr_base_X_fr_RH_HFE(), + fr_base_X_fr_RH_KFE(), + fr_LF_HIP_X_fr_base(), + fr_base_X_fr_LF_HIP(), + fr_LF_THIGH_X_fr_LF_HIP(), + fr_LF_HIP_X_fr_LF_THIGH(), + fr_LF_SHANK_X_fr_LF_THIGH(), + fr_LF_THIGH_X_fr_LF_SHANK(), + fr_RF_HIP_X_fr_base(), + fr_base_X_fr_RF_HIP(), + fr_RF_THIGH_X_fr_RF_HIP(), + fr_RF_HIP_X_fr_RF_THIGH(), + fr_RF_SHANK_X_fr_RF_THIGH(), + fr_RF_THIGH_X_fr_RF_SHANK(), + fr_LH_HIP_X_fr_base(), + fr_base_X_fr_LH_HIP(), + fr_LH_THIGH_X_fr_LH_HIP(), + fr_LH_HIP_X_fr_LH_THIGH(), + fr_LH_SHANK_X_fr_LH_THIGH(), + fr_LH_THIGH_X_fr_LH_SHANK(), + fr_RH_HIP_X_fr_base(), + fr_base_X_fr_RH_HIP(), + fr_RH_THIGH_X_fr_RH_HIP(), + fr_RH_HIP_X_fr_RH_THIGH(), + fr_RH_SHANK_X_fr_RH_THIGH(), + fr_RH_THIGH_X_fr_RH_SHANK() +{ + updateParameters(); +} +template +void iit::camel::tpl::ForceTransforms::updateParameters() { +} + +template +iit::camel::tpl::HomogeneousTransforms::HomogeneousTransforms + () + : + fr_base_X_fr_LF_FOOT(), + fr_LF_FOOT_X_fr_base(), + fr_base_X_fr_LH_FOOT(), + fr_LH_FOOT_X_fr_base(), + fr_base_X_fr_RF_FOOT(), + fr_RF_FOOT_X_fr_base(), + fr_base_X_fr_RH_FOOT(), + fr_RH_FOOT_X_fr_base(), + fr_base_X_fr_LF_HAA(), + fr_base_X_fr_LF_HFE(), + fr_base_X_fr_LF_KFE(), + fr_base_X_fr_LH_HAA(), + fr_base_X_fr_LH_HFE(), + fr_base_X_fr_LH_KFE(), + fr_base_X_fr_RF_HAA(), + fr_base_X_fr_RF_HFE(), + fr_base_X_fr_RF_KFE(), + fr_base_X_fr_RH_HAA(), + fr_base_X_fr_RH_HFE(), + fr_base_X_fr_RH_KFE(), + fr_LF_HIP_X_fr_base(), + fr_base_X_fr_LF_HIP(), + fr_LF_THIGH_X_fr_LF_HIP(), + fr_LF_HIP_X_fr_LF_THIGH(), + fr_LF_SHANK_X_fr_LF_THIGH(), + fr_LF_THIGH_X_fr_LF_SHANK(), + fr_RF_HIP_X_fr_base(), + fr_base_X_fr_RF_HIP(), + fr_RF_THIGH_X_fr_RF_HIP(), + fr_RF_HIP_X_fr_RF_THIGH(), + fr_RF_SHANK_X_fr_RF_THIGH(), + fr_RF_THIGH_X_fr_RF_SHANK(), + fr_LH_HIP_X_fr_base(), + fr_base_X_fr_LH_HIP(), + fr_LH_THIGH_X_fr_LH_HIP(), + fr_LH_HIP_X_fr_LH_THIGH(), + fr_LH_SHANK_X_fr_LH_THIGH(), + fr_LH_THIGH_X_fr_LH_SHANK(), + fr_RH_HIP_X_fr_base(), + fr_base_X_fr_RH_HIP(), + fr_RH_THIGH_X_fr_RH_HIP(), + fr_RH_HIP_X_fr_RH_THIGH(), + fr_RH_SHANK_X_fr_RH_THIGH(), + fr_RH_THIGH_X_fr_RH_SHANK() +{ + updateParameters(); +} +template +void iit::camel::tpl::HomogeneousTransforms::updateParameters() { +} + +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_FOOT::Type_fr_base_X_fr_LF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_FOOT& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_FOOT::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,2) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(1,0) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,0) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,1) = s_q_LF_HAA_; + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(3,0) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * c_q_LF_HFE_) * s_q_LF_KFE_) + ((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(3,1) = (((((( 0.08795 * c_q_LF_HFE_) - ( 0.33797 * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((( 0.08795 * s_q_LF_HFE_) + ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)) + ( 0.285 * c_q_LF_HFE_)) + ( 0.104 * s_q_LF_HAA_)); + (*this)(3,2) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * s_q_LF_KFE_) + (((( 0.104 * c_q_LF_HAA_) + 0.19716) * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(3,3) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(3,5) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(4,0) = (((((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * c_q_LF_HAA_)); + (*this)(4,1) = ((((((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_)) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(4,2) = ((((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * s_q_LF_KFE_) + (((( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * c_q_LF_HAA_)); + (*this)(4,3) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,0) = ((((((( 0.19716 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * s_q_LF_HAA_)); + (*this)(5,1) = (((((((- 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)) + ( 0.3598 * c_q_LF_HAA_)); + (*this)(5,2) = ((((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * s_q_LF_KFE_) + (((((- 0.19716 * c_q_LF_HAA_) - 0.104) * s_q_LF_HFE_) - (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * s_q_LF_HAA_)); + (*this)(5,3) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,4) = s_q_LF_HAA_; + (*this)(5,5) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_FOOT_X_fr_base::Type_fr_LF_FOOT_X_fr_base() +{ + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(4,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_FOOT_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_LF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,1) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,2) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(2,0) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(2,1) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(3,0) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * c_q_LF_HFE_) * s_q_LF_KFE_) + ((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(3,1) = (((((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * c_q_LF_HAA_)); + (*this)(3,2) = ((((((( 0.19716 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * s_q_LF_HAA_)); + (*this)(3,3) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(3,4) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(3,5) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(4,0) = (((((( 0.08795 * c_q_LF_HFE_) - ( 0.33797 * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((( 0.08795 * s_q_LF_HFE_) + ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)) + ( 0.285 * c_q_LF_HFE_)) + ( 0.104 * s_q_LF_HAA_)); + (*this)(4,1) = ((((((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_)) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(4,2) = (((((((- 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)) + ( 0.3598 * c_q_LF_HAA_)); + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = s_q_LF_HAA_; + (*this)(5,0) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * s_q_LF_KFE_) + (((( 0.104 * c_q_LF_HAA_) + 0.19716) * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,1) = ((((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * s_q_LF_KFE_) + (((( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * c_q_LF_HAA_)); + (*this)(5,2) = ((((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * s_q_LF_KFE_) + (((((- 0.19716 * c_q_LF_HAA_) - 0.104) * s_q_LF_HFE_) - (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * s_q_LF_HAA_)); + (*this)(5,3) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(5,4) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,5) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_FOOT::Type_fr_base_X_fr_LH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_FOOT& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_FOOT::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,2) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(1,0) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,0) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,1) = s_q_LH_HAA_; + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(3,0) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * c_q_LH_HFE_) * s_q_LH_KFE_) + ((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(3,1) = ((((((- 0.33797 * s_q_LH_HFE_) - ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.33797 * c_q_LH_HFE_) - ( 0.08795 * s_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.285 * c_q_LH_HFE_)) + ( 0.104 * s_q_LH_HAA_)); + (*this)(3,2) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * s_q_LH_KFE_) + (((( 0.104 * c_q_LH_HAA_) + 0.19716) * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(3,3) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(3,5) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(4,0) = ((((((- 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * c_q_LH_HAA_)); + (*this)(4,1) = ((((((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_)) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(4,2) = (((((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * s_q_LH_KFE_) + (((( 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * c_q_LH_HAA_)); + (*this)(4,3) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,0) = ((((((( 0.19716 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * s_q_LH_HAA_)); + (*this)(5,1) = ((((((( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_)) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(5,2) = (((((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * s_q_LH_KFE_) + (((((- 0.19716 * c_q_LH_HAA_) - 0.104) * s_q_LH_HFE_) + (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * s_q_LH_HAA_)); + (*this)(5,3) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,4) = s_q_LH_HAA_; + (*this)(5,5) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_FOOT_X_fr_base::Type_fr_LH_FOOT_X_fr_base() +{ + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(4,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_FOOT_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_LH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,1) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,2) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(2,0) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(2,1) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(3,0) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * c_q_LH_HFE_) * s_q_LH_KFE_) + ((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(3,1) = ((((((- 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * c_q_LH_HAA_)); + (*this)(3,2) = ((((((( 0.19716 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * s_q_LH_HAA_)); + (*this)(3,3) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(3,4) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(3,5) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(4,0) = ((((((- 0.33797 * s_q_LH_HFE_) - ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.33797 * c_q_LH_HFE_) - ( 0.08795 * s_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.285 * c_q_LH_HFE_)) + ( 0.104 * s_q_LH_HAA_)); + (*this)(4,1) = ((((((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_)) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(4,2) = ((((((( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_)) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = s_q_LH_HAA_; + (*this)(5,0) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * s_q_LH_KFE_) + (((( 0.104 * c_q_LH_HAA_) + 0.19716) * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,1) = (((((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * s_q_LH_KFE_) + (((( 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * c_q_LH_HAA_)); + (*this)(5,2) = (((((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * s_q_LH_KFE_) + (((((- 0.19716 * c_q_LH_HAA_) - 0.104) * s_q_LH_HFE_) + (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * s_q_LH_HAA_)); + (*this)(5,3) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(5,4) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,5) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_FOOT::Type_fr_base_X_fr_RF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_FOOT& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_FOOT::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,2) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(1,0) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,0) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,1) = s_q_RF_HAA_; + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(3,0) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * c_q_RF_HFE_) * s_q_RF_KFE_) + (((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(3,1) = (((((( 0.08795 * c_q_RF_HFE_) - ( 0.33797 * s_q_RF_HFE_)) * s_q_RF_KFE_) + ((( 0.08795 * s_q_RF_HFE_) + ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)) + ( 0.285 * c_q_RF_HFE_)) - ( 0.104 * s_q_RF_HAA_)); + (*this)(3,2) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * s_q_RF_KFE_) + ((((- 0.104 * c_q_RF_HAA_) - 0.19716) * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(3,3) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(3,5) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(4,0) = (((((( 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * c_q_RF_HAA_)); + (*this)(4,1) = ((((((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_)) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(4,2) = ((((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * s_q_RF_KFE_) + ((((- 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * c_q_RF_HAA_)); + (*this)(4,3) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,0) = (((((((- 0.19716 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * s_q_RF_HAA_)); + (*this)(5,1) = (((((((- 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)) + ( 0.3598 * c_q_RF_HAA_)); + (*this)(5,2) = ((((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * s_q_RF_KFE_) + ((((( 0.19716 * c_q_RF_HAA_) + 0.104) * s_q_RF_HFE_) - (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * s_q_RF_HAA_)); + (*this)(5,3) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,4) = s_q_RF_HAA_; + (*this)(5,5) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_FOOT_X_fr_base::Type_fr_RF_FOOT_X_fr_base() +{ + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(4,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_FOOT_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_RF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,1) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,2) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(2,0) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(2,1) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(3,0) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * c_q_RF_HFE_) * s_q_RF_KFE_) + (((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(3,1) = (((((( 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * c_q_RF_HAA_)); + (*this)(3,2) = (((((((- 0.19716 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * s_q_RF_HAA_)); + (*this)(3,3) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(3,4) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(3,5) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(4,0) = (((((( 0.08795 * c_q_RF_HFE_) - ( 0.33797 * s_q_RF_HFE_)) * s_q_RF_KFE_) + ((( 0.08795 * s_q_RF_HFE_) + ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)) + ( 0.285 * c_q_RF_HFE_)) - ( 0.104 * s_q_RF_HAA_)); + (*this)(4,1) = ((((((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_)) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(4,2) = (((((((- 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)) + ( 0.3598 * c_q_RF_HAA_)); + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = s_q_RF_HAA_; + (*this)(5,0) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * s_q_RF_KFE_) + ((((- 0.104 * c_q_RF_HAA_) - 0.19716) * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,1) = ((((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * s_q_RF_KFE_) + ((((- 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * c_q_RF_HAA_)); + (*this)(5,2) = ((((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * s_q_RF_KFE_) + ((((( 0.19716 * c_q_RF_HAA_) + 0.104) * s_q_RF_HFE_) - (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * s_q_RF_HAA_)); + (*this)(5,3) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(5,4) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,5) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_FOOT::Type_fr_base_X_fr_RH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_FOOT& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_FOOT::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,2) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(1,0) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,0) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,1) = s_q_RH_HAA_; + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(3,0) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * c_q_RH_HFE_) * s_q_RH_KFE_) + (((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(3,1) = ((((((- 0.33797 * s_q_RH_HFE_) - ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.33797 * c_q_RH_HFE_) - ( 0.08795 * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.285 * c_q_RH_HFE_)) - ( 0.104 * s_q_RH_HAA_)); + (*this)(3,2) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * s_q_RH_KFE_) + ((((- 0.104 * c_q_RH_HAA_) - 0.19716) * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(3,3) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(3,5) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(4,0) = (((((( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * c_q_RH_HAA_)); + (*this)(4,1) = ((((((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_)) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(4,2) = (((((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * s_q_RH_KFE_) + (((( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * c_q_RH_HAA_)); + (*this)(4,3) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,0) = (((((((- 0.19716 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * s_q_RH_HAA_)); + (*this)(5,1) = ((((((( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_)) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(5,2) = (((((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * s_q_RH_KFE_) + ((((( 0.19716 * c_q_RH_HAA_) + 0.104) * s_q_RH_HFE_) + (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * s_q_RH_HAA_)); + (*this)(5,3) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,4) = s_q_RH_HAA_; + (*this)(5,5) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_FOOT_X_fr_base::Type_fr_RH_FOOT_X_fr_base() +{ + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(4,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_FOOT_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_RH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,1) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,2) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(2,0) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(2,1) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(3,0) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * c_q_RH_HFE_) * s_q_RH_KFE_) + (((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(3,1) = (((((( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * c_q_RH_HAA_)); + (*this)(3,2) = (((((((- 0.19716 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * s_q_RH_HAA_)); + (*this)(3,3) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(3,4) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(3,5) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(4,0) = ((((((- 0.33797 * s_q_RH_HFE_) - ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.33797 * c_q_RH_HFE_) - ( 0.08795 * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.285 * c_q_RH_HFE_)) - ( 0.104 * s_q_RH_HAA_)); + (*this)(4,1) = ((((((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_)) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(4,2) = ((((((( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_)) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = s_q_RH_HAA_; + (*this)(5,0) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * s_q_RH_KFE_) + ((((- 0.104 * c_q_RH_HAA_) - 0.19716) * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,1) = (((((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * s_q_RH_KFE_) + (((( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * c_q_RH_HAA_)); + (*this)(5,2) = (((((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * s_q_RH_KFE_) + ((((( 0.19716 * c_q_RH_HAA_) + 0.104) * s_q_RH_HFE_) + (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * s_q_RH_HAA_)); + (*this)(5,3) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(5,4) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,5) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HAA::Type_fr_base_X_fr_LF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = - 0.104; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0.2999; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0.2999; + (*this)(5,2) = - 0.104; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HAA& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HFE::Type_fr_base_X_fr_LF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,3) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HFE::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(1,1) = s_q_LF_HAA_; + (*this)(1,2) = c_q_LF_HAA_; + (*this)(2,1) = - c_q_LF_HAA_; + (*this)(2,2) = s_q_LF_HAA_; + (*this)(3,1) = ((- 0.104 * c_q_LF_HAA_) - 0.08381); + (*this)(3,2) = ( 0.104 * s_q_LF_HAA_); + (*this)(4,0) = ( 0.08381 * s_q_LF_HAA_); + (*this)(4,1) = ( 0.3598 * c_q_LF_HAA_); + (*this)(4,2) = (- 0.3598 * s_q_LF_HAA_); + (*this)(4,4) = s_q_LF_HAA_; + (*this)(4,5) = c_q_LF_HAA_; + (*this)(5,0) = ((- 0.08381 * c_q_LF_HAA_) - 0.104); + (*this)(5,1) = ( 0.3598 * s_q_LF_HAA_); + (*this)(5,2) = ( 0.3598 * c_q_LF_HAA_); + (*this)(5,4) = - c_q_LF_HAA_; + (*this)(5,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_KFE::Type_fr_base_X_fr_LF_KFE() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_KFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_KFE::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = c_q_LF_HFE_; + (*this)(0,1) = - s_q_LF_HFE_; + (*this)(1,0) = ( s_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(1,1) = ( s_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(1,2) = c_q_LF_HAA_; + (*this)(2,0) = (- c_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(2,1) = (- c_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(2,2) = s_q_LF_HAA_; + (*this)(3,0) = (((- 0.104 * c_q_LF_HAA_) - 0.18411) * s_q_LF_HFE_); + (*this)(3,1) = (((- 0.104 * c_q_LF_HAA_) - 0.18411) * c_q_LF_HFE_); + (*this)(3,2) = (( 0.285 * c_q_LF_HFE_) + ( 0.104 * s_q_LF_HAA_)); + (*this)(3,3) = c_q_LF_HFE_; + (*this)(3,4) = - s_q_LF_HFE_; + (*this)(4,0) = (((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.18411 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)); + (*this)(4,1) = ((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.18411 * s_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(4,2) = ((( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(4,3) = ( s_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(4,4) = ( s_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(4,5) = c_q_LF_HAA_; + (*this)(5,0) = (((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.18411 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)); + (*this)(5,1) = (((( 0.18411 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)); + (*this)(5,2) = (( 0.3598 * c_q_LF_HAA_) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(5,3) = (- c_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(5,4) = (- c_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(5,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HAA::Type_fr_base_X_fr_LH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = - 0.104; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = - 0.2999; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = - 0.2999; + (*this)(5,2) = - 0.104; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HAA& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HFE::Type_fr_base_X_fr_LH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,3) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HFE::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(1,1) = s_q_LH_HAA_; + (*this)(1,2) = c_q_LH_HAA_; + (*this)(2,1) = - c_q_LH_HAA_; + (*this)(2,2) = s_q_LH_HAA_; + (*this)(3,1) = ((- 0.104 * c_q_LH_HAA_) - 0.08381); + (*this)(3,2) = ( 0.104 * s_q_LH_HAA_); + (*this)(4,0) = ( 0.08381 * s_q_LH_HAA_); + (*this)(4,1) = (- 0.3598 * c_q_LH_HAA_); + (*this)(4,2) = ( 0.3598 * s_q_LH_HAA_); + (*this)(4,4) = s_q_LH_HAA_; + (*this)(4,5) = c_q_LH_HAA_; + (*this)(5,0) = ((- 0.08381 * c_q_LH_HAA_) - 0.104); + (*this)(5,1) = (- 0.3598 * s_q_LH_HAA_); + (*this)(5,2) = (- 0.3598 * c_q_LH_HAA_); + (*this)(5,4) = - c_q_LH_HAA_; + (*this)(5,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_KFE::Type_fr_base_X_fr_LH_KFE() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_KFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_KFE::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = c_q_LH_HFE_; + (*this)(0,1) = - s_q_LH_HFE_; + (*this)(1,0) = ( s_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(1,1) = ( s_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(1,2) = c_q_LH_HAA_; + (*this)(2,0) = (- c_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(2,1) = (- c_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(2,2) = s_q_LH_HAA_; + (*this)(3,0) = (((- 0.104 * c_q_LH_HAA_) - 0.18411) * s_q_LH_HFE_); + (*this)(3,1) = (((- 0.104 * c_q_LH_HAA_) - 0.18411) * c_q_LH_HFE_); + (*this)(3,2) = (( 0.285 * c_q_LH_HFE_) + ( 0.104 * s_q_LH_HAA_)); + (*this)(3,3) = c_q_LH_HFE_; + (*this)(3,4) = - s_q_LH_HFE_; + (*this)(4,0) = ((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.18411 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)); + (*this)(4,1) = (((- 0.18411 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)); + (*this)(4,2) = ((( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(4,3) = ( s_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(4,4) = ( s_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(4,5) = c_q_LH_HAA_; + (*this)(5,0) = ((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.18411 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)); + (*this)(5,1) = (((( 0.18411 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)); + (*this)(5,2) = (((- 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(5,3) = (- c_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(5,4) = (- c_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(5,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HAA::Type_fr_base_X_fr_RF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0.104; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0.2999; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0.2999; + (*this)(5,2) = 0.104; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HAA& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HFE::Type_fr_base_X_fr_RF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,3) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HFE::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(1,1) = s_q_RF_HAA_; + (*this)(1,2) = c_q_RF_HAA_; + (*this)(2,1) = - c_q_RF_HAA_; + (*this)(2,2) = s_q_RF_HAA_; + (*this)(3,1) = (( 0.104 * c_q_RF_HAA_) + 0.08381); + (*this)(3,2) = (- 0.104 * s_q_RF_HAA_); + (*this)(4,0) = (- 0.08381 * s_q_RF_HAA_); + (*this)(4,1) = ( 0.3598 * c_q_RF_HAA_); + (*this)(4,2) = (- 0.3598 * s_q_RF_HAA_); + (*this)(4,4) = s_q_RF_HAA_; + (*this)(4,5) = c_q_RF_HAA_; + (*this)(5,0) = (( 0.08381 * c_q_RF_HAA_) + 0.104); + (*this)(5,1) = ( 0.3598 * s_q_RF_HAA_); + (*this)(5,2) = ( 0.3598 * c_q_RF_HAA_); + (*this)(5,4) = - c_q_RF_HAA_; + (*this)(5,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_KFE::Type_fr_base_X_fr_RF_KFE() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_KFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_KFE::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = c_q_RF_HFE_; + (*this)(0,1) = - s_q_RF_HFE_; + (*this)(1,0) = ( s_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(1,1) = ( s_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(1,2) = c_q_RF_HAA_; + (*this)(2,0) = (- c_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(2,1) = (- c_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(2,2) = s_q_RF_HAA_; + (*this)(3,0) = ((( 0.104 * c_q_RF_HAA_) + 0.18411) * s_q_RF_HFE_); + (*this)(3,1) = ((( 0.104 * c_q_RF_HAA_) + 0.18411) * c_q_RF_HFE_); + (*this)(3,2) = (( 0.285 * c_q_RF_HFE_) - ( 0.104 * s_q_RF_HAA_)); + (*this)(3,3) = c_q_RF_HFE_; + (*this)(3,4) = - s_q_RF_HFE_; + (*this)(4,0) = (((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.18411 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)); + (*this)(4,1) = ((( 0.18411 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)); + (*this)(4,2) = ((( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(4,3) = ( s_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(4,4) = ( s_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(4,5) = c_q_RF_HAA_; + (*this)(5,0) = (((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.18411 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)); + (*this)(5,1) = ((((- 0.18411 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)); + (*this)(5,2) = (( 0.3598 * c_q_RF_HAA_) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)); + (*this)(5,3) = (- c_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(5,4) = (- c_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(5,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HAA::Type_fr_base_X_fr_RH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0.104; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = - 0.2999; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = - 0.2999; + (*this)(5,2) = 0.104; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HAA& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HFE::Type_fr_base_X_fr_RH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,3) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HFE::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(1,1) = s_q_RH_HAA_; + (*this)(1,2) = c_q_RH_HAA_; + (*this)(2,1) = - c_q_RH_HAA_; + (*this)(2,2) = s_q_RH_HAA_; + (*this)(3,1) = (( 0.104 * c_q_RH_HAA_) + 0.08381); + (*this)(3,2) = (- 0.104 * s_q_RH_HAA_); + (*this)(4,0) = (- 0.08381 * s_q_RH_HAA_); + (*this)(4,1) = (- 0.3598 * c_q_RH_HAA_); + (*this)(4,2) = ( 0.3598 * s_q_RH_HAA_); + (*this)(4,4) = s_q_RH_HAA_; + (*this)(4,5) = c_q_RH_HAA_; + (*this)(5,0) = (( 0.08381 * c_q_RH_HAA_) + 0.104); + (*this)(5,1) = (- 0.3598 * s_q_RH_HAA_); + (*this)(5,2) = (- 0.3598 * c_q_RH_HAA_); + (*this)(5,4) = - c_q_RH_HAA_; + (*this)(5,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_KFE::Type_fr_base_X_fr_RH_KFE() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_KFE& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_KFE::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = c_q_RH_HFE_; + (*this)(0,1) = - s_q_RH_HFE_; + (*this)(1,0) = ( s_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(1,1) = ( s_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(1,2) = c_q_RH_HAA_; + (*this)(2,0) = (- c_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(2,1) = (- c_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(2,2) = s_q_RH_HAA_; + (*this)(3,0) = ((( 0.104 * c_q_RH_HAA_) + 0.18411) * s_q_RH_HFE_); + (*this)(3,1) = ((( 0.104 * c_q_RH_HAA_) + 0.18411) * c_q_RH_HFE_); + (*this)(3,2) = (( 0.285 * c_q_RH_HFE_) - ( 0.104 * s_q_RH_HAA_)); + (*this)(3,3) = c_q_RH_HFE_; + (*this)(3,4) = - s_q_RH_HFE_; + (*this)(4,0) = ((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.18411 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)); + (*this)(4,1) = ((( 0.18411 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)); + (*this)(4,2) = ((( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(4,3) = ( s_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(4,4) = ( s_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(4,5) = c_q_RH_HAA_; + (*this)(5,0) = ((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.18411 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)); + (*this)(5,1) = ((((- 0.18411 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)); + (*this)(5,2) = (((- 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(5,3) = (- c_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(5,4) = (- c_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(5,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_base::Type_fr_LF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,3) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = - 0.104; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,1) = s_q_LF_HAA_; + (*this)(0,2) = - c_q_LF_HAA_; + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(3,0) = (- 0.104 * c_q_LF_HAA_); + (*this)(3,1) = ( 0.2999 * c_q_LF_HAA_); + (*this)(3,2) = ( 0.2999 * s_q_LF_HAA_); + (*this)(3,4) = s_q_LF_HAA_; + (*this)(3,5) = - c_q_LF_HAA_; + (*this)(4,0) = ( 0.104 * s_q_LF_HAA_); + (*this)(4,1) = (- 0.2999 * s_q_LF_HAA_); + (*this)(4,2) = ( 0.2999 * c_q_LF_HAA_); + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HIP::Type_fr_base_X_fr_LF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = - 0.104; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HIP& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(1,0) = s_q_LF_HAA_; + (*this)(1,1) = c_q_LF_HAA_; + (*this)(2,0) = - c_q_LF_HAA_; + (*this)(2,1) = s_q_LF_HAA_; + (*this)(3,0) = (- 0.104 * c_q_LF_HAA_); + (*this)(3,1) = ( 0.104 * s_q_LF_HAA_); + (*this)(4,0) = ( 0.2999 * c_q_LF_HAA_); + (*this)(4,1) = (- 0.2999 * s_q_LF_HAA_); + (*this)(4,3) = s_q_LF_HAA_; + (*this)(4,4) = c_q_LF_HAA_; + (*this)(5,0) = ( 0.2999 * s_q_LF_HAA_); + (*this)(5,1) = ( 0.2999 * c_q_LF_HAA_); + (*this)(5,3) = - c_q_LF_HAA_; + (*this)(5,4) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::Type_fr_LF_THIGH_X_fr_LF_HIP() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,1) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = - 0.0599; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP& iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,2) = c_q_LF_HFE_; + (*this)(1,0) = c_q_LF_HFE_; + (*this)(1,2) = - s_q_LF_HFE_; + (*this)(3,0) = ( 0.08381 * c_q_LF_HFE_); + (*this)(3,1) = ( 0.0599 * s_q_LF_HFE_); + (*this)(3,2) = (- 0.08381 * s_q_LF_HFE_); + (*this)(3,3) = s_q_LF_HFE_; + (*this)(3,5) = c_q_LF_HFE_; + (*this)(4,0) = (- 0.08381 * s_q_LF_HFE_); + (*this)(4,1) = ( 0.0599 * c_q_LF_HFE_); + (*this)(4,2) = (- 0.08381 * c_q_LF_HFE_); + (*this)(4,3) = c_q_LF_HFE_; + (*this)(4,5) = - s_q_LF_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::Type_fr_LF_HIP_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = - 0.0599; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,1) = c_q_LF_HFE_; + (*this)(2,0) = c_q_LF_HFE_; + (*this)(2,1) = - s_q_LF_HFE_; + (*this)(3,0) = ( 0.08381 * c_q_LF_HFE_); + (*this)(3,1) = (- 0.08381 * s_q_LF_HFE_); + (*this)(3,3) = s_q_LF_HFE_; + (*this)(3,4) = c_q_LF_HFE_; + (*this)(4,0) = ( 0.0599 * s_q_LF_HFE_); + (*this)(4,1) = ( 0.0599 * c_q_LF_HFE_); + (*this)(5,0) = (- 0.08381 * s_q_LF_HFE_); + (*this)(5,1) = (- 0.08381 * c_q_LF_HFE_); + (*this)(5,3) = c_q_LF_HFE_; + (*this)(5,4) = - s_q_LF_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::Type_fr_LF_SHANK_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0.285; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = s_q_LF_KFE_; + (*this)(1,0) = - s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + (*this)(3,0) = (- 0.1003 * s_q_LF_KFE_); + (*this)(3,1) = ( 0.1003 * c_q_LF_KFE_); + (*this)(3,2) = (- 0.285 * c_q_LF_KFE_); + (*this)(3,3) = c_q_LF_KFE_; + (*this)(3,4) = s_q_LF_KFE_; + (*this)(4,0) = (- 0.1003 * c_q_LF_KFE_); + (*this)(4,1) = (- 0.1003 * s_q_LF_KFE_); + (*this)(4,2) = ( 0.285 * s_q_LF_KFE_); + (*this)(4,3) = - s_q_LF_KFE_; + (*this)(4,4) = c_q_LF_KFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::Type_fr_LF_THIGH_X_fr_LF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.285; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK& iit::camel::tpl::MotionTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = - s_q_LF_KFE_; + (*this)(1,0) = s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + (*this)(3,0) = (- 0.1003 * s_q_LF_KFE_); + (*this)(3,1) = (- 0.1003 * c_q_LF_KFE_); + (*this)(3,3) = c_q_LF_KFE_; + (*this)(3,4) = - s_q_LF_KFE_; + (*this)(4,0) = ( 0.1003 * c_q_LF_KFE_); + (*this)(4,1) = (- 0.1003 * s_q_LF_KFE_); + (*this)(4,3) = s_q_LF_KFE_; + (*this)(4,4) = c_q_LF_KFE_; + (*this)(5,0) = (- 0.285 * c_q_LF_KFE_); + (*this)(5,1) = ( 0.285 * s_q_LF_KFE_); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_base::Type_fr_RF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,3) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0.104; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,1) = s_q_RF_HAA_; + (*this)(0,2) = - c_q_RF_HAA_; + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(3,0) = ( 0.104 * c_q_RF_HAA_); + (*this)(3,1) = ( 0.2999 * c_q_RF_HAA_); + (*this)(3,2) = ( 0.2999 * s_q_RF_HAA_); + (*this)(3,4) = s_q_RF_HAA_; + (*this)(3,5) = - c_q_RF_HAA_; + (*this)(4,0) = (- 0.104 * s_q_RF_HAA_); + (*this)(4,1) = (- 0.2999 * s_q_RF_HAA_); + (*this)(4,2) = ( 0.2999 * c_q_RF_HAA_); + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HIP::Type_fr_base_X_fr_RF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0.104; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HIP& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(1,0) = s_q_RF_HAA_; + (*this)(1,1) = c_q_RF_HAA_; + (*this)(2,0) = - c_q_RF_HAA_; + (*this)(2,1) = s_q_RF_HAA_; + (*this)(3,0) = ( 0.104 * c_q_RF_HAA_); + (*this)(3,1) = (- 0.104 * s_q_RF_HAA_); + (*this)(4,0) = ( 0.2999 * c_q_RF_HAA_); + (*this)(4,1) = (- 0.2999 * s_q_RF_HAA_); + (*this)(4,3) = s_q_RF_HAA_; + (*this)(4,4) = c_q_RF_HAA_; + (*this)(5,0) = ( 0.2999 * s_q_RF_HAA_); + (*this)(5,1) = ( 0.2999 * c_q_RF_HAA_); + (*this)(5,3) = - c_q_RF_HAA_; + (*this)(5,4) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::Type_fr_RF_THIGH_X_fr_RF_HIP() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,1) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = - 0.0599; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP& iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,2) = c_q_RF_HFE_; + (*this)(1,0) = c_q_RF_HFE_; + (*this)(1,2) = - s_q_RF_HFE_; + (*this)(3,0) = (- 0.08381 * c_q_RF_HFE_); + (*this)(3,1) = ( 0.0599 * s_q_RF_HFE_); + (*this)(3,2) = ( 0.08381 * s_q_RF_HFE_); + (*this)(3,3) = s_q_RF_HFE_; + (*this)(3,5) = c_q_RF_HFE_; + (*this)(4,0) = ( 0.08381 * s_q_RF_HFE_); + (*this)(4,1) = ( 0.0599 * c_q_RF_HFE_); + (*this)(4,2) = ( 0.08381 * c_q_RF_HFE_); + (*this)(4,3) = c_q_RF_HFE_; + (*this)(4,5) = - s_q_RF_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::Type_fr_RF_HIP_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = - 0.0599; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,1) = c_q_RF_HFE_; + (*this)(2,0) = c_q_RF_HFE_; + (*this)(2,1) = - s_q_RF_HFE_; + (*this)(3,0) = (- 0.08381 * c_q_RF_HFE_); + (*this)(3,1) = ( 0.08381 * s_q_RF_HFE_); + (*this)(3,3) = s_q_RF_HFE_; + (*this)(3,4) = c_q_RF_HFE_; + (*this)(4,0) = ( 0.0599 * s_q_RF_HFE_); + (*this)(4,1) = ( 0.0599 * c_q_RF_HFE_); + (*this)(5,0) = ( 0.08381 * s_q_RF_HFE_); + (*this)(5,1) = ( 0.08381 * c_q_RF_HFE_); + (*this)(5,3) = c_q_RF_HFE_; + (*this)(5,4) = - s_q_RF_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::Type_fr_RF_SHANK_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0.285; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = s_q_RF_KFE_; + (*this)(1,0) = - s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + (*this)(3,0) = ( 0.1003 * s_q_RF_KFE_); + (*this)(3,1) = (- 0.1003 * c_q_RF_KFE_); + (*this)(3,2) = (- 0.285 * c_q_RF_KFE_); + (*this)(3,3) = c_q_RF_KFE_; + (*this)(3,4) = s_q_RF_KFE_; + (*this)(4,0) = ( 0.1003 * c_q_RF_KFE_); + (*this)(4,1) = ( 0.1003 * s_q_RF_KFE_); + (*this)(4,2) = ( 0.285 * s_q_RF_KFE_); + (*this)(4,3) = - s_q_RF_KFE_; + (*this)(4,4) = c_q_RF_KFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::Type_fr_RF_THIGH_X_fr_RF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.285; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK& iit::camel::tpl::MotionTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = - s_q_RF_KFE_; + (*this)(1,0) = s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + (*this)(3,0) = ( 0.1003 * s_q_RF_KFE_); + (*this)(3,1) = ( 0.1003 * c_q_RF_KFE_); + (*this)(3,3) = c_q_RF_KFE_; + (*this)(3,4) = - s_q_RF_KFE_; + (*this)(4,0) = (- 0.1003 * c_q_RF_KFE_); + (*this)(4,1) = ( 0.1003 * s_q_RF_KFE_); + (*this)(4,3) = s_q_RF_KFE_; + (*this)(4,4) = c_q_RF_KFE_; + (*this)(5,0) = (- 0.285 * c_q_RF_KFE_); + (*this)(5,1) = ( 0.285 * s_q_RF_KFE_); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_base::Type_fr_LH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,3) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = - 0.104; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,1) = s_q_LH_HAA_; + (*this)(0,2) = - c_q_LH_HAA_; + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(3,0) = (- 0.104 * c_q_LH_HAA_); + (*this)(3,1) = (- 0.2999 * c_q_LH_HAA_); + (*this)(3,2) = (- 0.2999 * s_q_LH_HAA_); + (*this)(3,4) = s_q_LH_HAA_; + (*this)(3,5) = - c_q_LH_HAA_; + (*this)(4,0) = ( 0.104 * s_q_LH_HAA_); + (*this)(4,1) = ( 0.2999 * s_q_LH_HAA_); + (*this)(4,2) = (- 0.2999 * c_q_LH_HAA_); + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HIP::Type_fr_base_X_fr_LH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = - 0.104; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HIP& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(1,0) = s_q_LH_HAA_; + (*this)(1,1) = c_q_LH_HAA_; + (*this)(2,0) = - c_q_LH_HAA_; + (*this)(2,1) = s_q_LH_HAA_; + (*this)(3,0) = (- 0.104 * c_q_LH_HAA_); + (*this)(3,1) = ( 0.104 * s_q_LH_HAA_); + (*this)(4,0) = (- 0.2999 * c_q_LH_HAA_); + (*this)(4,1) = ( 0.2999 * s_q_LH_HAA_); + (*this)(4,3) = s_q_LH_HAA_; + (*this)(4,4) = c_q_LH_HAA_; + (*this)(5,0) = (- 0.2999 * s_q_LH_HAA_); + (*this)(5,1) = (- 0.2999 * c_q_LH_HAA_); + (*this)(5,3) = - c_q_LH_HAA_; + (*this)(5,4) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::Type_fr_LH_THIGH_X_fr_LH_HIP() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,1) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0.0599; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP& iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,2) = c_q_LH_HFE_; + (*this)(1,0) = c_q_LH_HFE_; + (*this)(1,2) = - s_q_LH_HFE_; + (*this)(3,0) = ( 0.08381 * c_q_LH_HFE_); + (*this)(3,1) = (- 0.0599 * s_q_LH_HFE_); + (*this)(3,2) = (- 0.08381 * s_q_LH_HFE_); + (*this)(3,3) = s_q_LH_HFE_; + (*this)(3,5) = c_q_LH_HFE_; + (*this)(4,0) = (- 0.08381 * s_q_LH_HFE_); + (*this)(4,1) = (- 0.0599 * c_q_LH_HFE_); + (*this)(4,2) = (- 0.08381 * c_q_LH_HFE_); + (*this)(4,3) = c_q_LH_HFE_; + (*this)(4,5) = - s_q_LH_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::Type_fr_LH_HIP_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.0599; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,1) = c_q_LH_HFE_; + (*this)(2,0) = c_q_LH_HFE_; + (*this)(2,1) = - s_q_LH_HFE_; + (*this)(3,0) = ( 0.08381 * c_q_LH_HFE_); + (*this)(3,1) = (- 0.08381 * s_q_LH_HFE_); + (*this)(3,3) = s_q_LH_HFE_; + (*this)(3,4) = c_q_LH_HFE_; + (*this)(4,0) = (- 0.0599 * s_q_LH_HFE_); + (*this)(4,1) = (- 0.0599 * c_q_LH_HFE_); + (*this)(5,0) = (- 0.08381 * s_q_LH_HFE_); + (*this)(5,1) = (- 0.08381 * c_q_LH_HFE_); + (*this)(5,3) = c_q_LH_HFE_; + (*this)(5,4) = - s_q_LH_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::Type_fr_LH_SHANK_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0.285; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = s_q_LH_KFE_; + (*this)(1,0) = - s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + (*this)(3,0) = (- 0.1003 * s_q_LH_KFE_); + (*this)(3,1) = ( 0.1003 * c_q_LH_KFE_); + (*this)(3,2) = (- 0.285 * c_q_LH_KFE_); + (*this)(3,3) = c_q_LH_KFE_; + (*this)(3,4) = s_q_LH_KFE_; + (*this)(4,0) = (- 0.1003 * c_q_LH_KFE_); + (*this)(4,1) = (- 0.1003 * s_q_LH_KFE_); + (*this)(4,2) = ( 0.285 * s_q_LH_KFE_); + (*this)(4,3) = - s_q_LH_KFE_; + (*this)(4,4) = c_q_LH_KFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::Type_fr_LH_THIGH_X_fr_LH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.285; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK& iit::camel::tpl::MotionTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = - s_q_LH_KFE_; + (*this)(1,0) = s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + (*this)(3,0) = (- 0.1003 * s_q_LH_KFE_); + (*this)(3,1) = (- 0.1003 * c_q_LH_KFE_); + (*this)(3,3) = c_q_LH_KFE_; + (*this)(3,4) = - s_q_LH_KFE_; + (*this)(4,0) = ( 0.1003 * c_q_LH_KFE_); + (*this)(4,1) = (- 0.1003 * s_q_LH_KFE_); + (*this)(4,3) = s_q_LH_KFE_; + (*this)(4,4) = c_q_LH_KFE_; + (*this)(5,0) = (- 0.285 * c_q_LH_KFE_); + (*this)(5,1) = ( 0.285 * s_q_LH_KFE_); + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_base::Type_fr_RH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,3) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0.104; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_base& iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,1) = s_q_RH_HAA_; + (*this)(0,2) = - c_q_RH_HAA_; + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(3,0) = ( 0.104 * c_q_RH_HAA_); + (*this)(3,1) = (- 0.2999 * c_q_RH_HAA_); + (*this)(3,2) = (- 0.2999 * s_q_RH_HAA_); + (*this)(3,4) = s_q_RH_HAA_; + (*this)(3,5) = - c_q_RH_HAA_; + (*this)(4,0) = (- 0.104 * s_q_RH_HAA_); + (*this)(4,1) = ( 0.2999 * s_q_RH_HAA_); + (*this)(4,2) = (- 0.2999 * c_q_RH_HAA_); + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HIP::Type_fr_base_X_fr_RH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0.104; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HIP& iit::camel::tpl::MotionTransforms::Type_fr_base_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(1,0) = s_q_RH_HAA_; + (*this)(1,1) = c_q_RH_HAA_; + (*this)(2,0) = - c_q_RH_HAA_; + (*this)(2,1) = s_q_RH_HAA_; + (*this)(3,0) = ( 0.104 * c_q_RH_HAA_); + (*this)(3,1) = (- 0.104 * s_q_RH_HAA_); + (*this)(4,0) = (- 0.2999 * c_q_RH_HAA_); + (*this)(4,1) = ( 0.2999 * s_q_RH_HAA_); + (*this)(4,3) = s_q_RH_HAA_; + (*this)(4,4) = c_q_RH_HAA_; + (*this)(5,0) = (- 0.2999 * s_q_RH_HAA_); + (*this)(5,1) = (- 0.2999 * c_q_RH_HAA_); + (*this)(5,3) = - c_q_RH_HAA_; + (*this)(5,4) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::Type_fr_RH_THIGH_X_fr_RH_HIP() +{ + (*this)(0,1) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,1) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,4) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0.0599; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP& iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,2) = c_q_RH_HFE_; + (*this)(1,0) = c_q_RH_HFE_; + (*this)(1,2) = - s_q_RH_HFE_; + (*this)(3,0) = (- 0.08381 * c_q_RH_HFE_); + (*this)(3,1) = (- 0.0599 * s_q_RH_HFE_); + (*this)(3,2) = ( 0.08381 * s_q_RH_HFE_); + (*this)(3,3) = s_q_RH_HFE_; + (*this)(3,5) = c_q_RH_HFE_; + (*this)(4,0) = ( 0.08381 * s_q_RH_HFE_); + (*this)(4,1) = (- 0.0599 * c_q_RH_HFE_); + (*this)(4,2) = ( 0.08381 * c_q_RH_HFE_); + (*this)(4,3) = c_q_RH_HFE_; + (*this)(4,5) = - s_q_RH_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::Type_fr_RH_HIP_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.0599; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,1) = c_q_RH_HFE_; + (*this)(2,0) = c_q_RH_HFE_; + (*this)(2,1) = - s_q_RH_HFE_; + (*this)(3,0) = (- 0.08381 * c_q_RH_HFE_); + (*this)(3,1) = ( 0.08381 * s_q_RH_HFE_); + (*this)(3,3) = s_q_RH_HFE_; + (*this)(3,4) = c_q_RH_HFE_; + (*this)(4,0) = (- 0.0599 * s_q_RH_HFE_); + (*this)(4,1) = (- 0.0599 * c_q_RH_HFE_); + (*this)(5,0) = ( 0.08381 * s_q_RH_HFE_); + (*this)(5,1) = ( 0.08381 * c_q_RH_HFE_); + (*this)(5,3) = c_q_RH_HFE_; + (*this)(5,4) = - s_q_RH_HFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::Type_fr_RH_SHANK_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,5) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0.285; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH& iit::camel::tpl::MotionTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = s_q_RH_KFE_; + (*this)(1,0) = - s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + (*this)(3,0) = ( 0.1003 * s_q_RH_KFE_); + (*this)(3,1) = (- 0.1003 * c_q_RH_KFE_); + (*this)(3,2) = (- 0.285 * c_q_RH_KFE_); + (*this)(3,3) = c_q_RH_KFE_; + (*this)(3,4) = s_q_RH_KFE_; + (*this)(4,0) = ( 0.1003 * c_q_RH_KFE_); + (*this)(4,1) = ( 0.1003 * s_q_RH_KFE_); + (*this)(4,2) = ( 0.285 * s_q_RH_KFE_); + (*this)(4,3) = - s_q_RH_KFE_; + (*this)(4,4) = c_q_RH_KFE_; + return *this; +} +template +iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::Type_fr_RH_THIGH_X_fr_RH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,2) = 0.285; + (*this)(3,5) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK& iit::camel::tpl::MotionTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = - s_q_RH_KFE_; + (*this)(1,0) = s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + (*this)(3,0) = ( 0.1003 * s_q_RH_KFE_); + (*this)(3,1) = ( 0.1003 * c_q_RH_KFE_); + (*this)(3,3) = c_q_RH_KFE_; + (*this)(3,4) = - s_q_RH_KFE_; + (*this)(4,0) = (- 0.1003 * c_q_RH_KFE_); + (*this)(4,1) = ( 0.1003 * s_q_RH_KFE_); + (*this)(4,3) = s_q_RH_KFE_; + (*this)(4,4) = c_q_RH_KFE_; + (*this)(5,0) = (- 0.285 * c_q_RH_KFE_); + (*this)(5,1) = ( 0.285 * s_q_RH_KFE_); + return *this; +} + +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_FOOT::Type_fr_base_X_fr_LF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_FOOT& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_FOOT::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,2) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(0,3) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * c_q_LF_HFE_) * s_q_LF_KFE_) + ((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,4) = (((((( 0.08795 * c_q_LF_HFE_) - ( 0.33797 * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((( 0.08795 * s_q_LF_HFE_) + ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)) + ( 0.285 * c_q_LF_HFE_)) + ( 0.104 * s_q_LF_HAA_)); + (*this)(0,5) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * s_q_LF_KFE_) + (((( 0.104 * c_q_LF_HAA_) + 0.19716) * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,0) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,3) = (((((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * c_q_LF_HAA_)); + (*this)(1,4) = ((((((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_)) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(1,5) = ((((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * s_q_LF_KFE_) + (((( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * c_q_LF_HAA_)); + (*this)(2,0) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,1) = s_q_LF_HAA_; + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(2,3) = ((((((( 0.19716 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * s_q_LF_HAA_)); + (*this)(2,4) = (((((((- 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)) + ( 0.3598 * c_q_LF_HAA_)); + (*this)(2,5) = ((((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * s_q_LF_KFE_) + (((((- 0.19716 * c_q_LF_HAA_) - 0.104) * s_q_LF_HFE_) - (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * s_q_LF_HAA_)); + (*this)(3,3) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(3,5) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(4,3) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,3) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,4) = s_q_LF_HAA_; + (*this)(5,5) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_FOOT_X_fr_base::Type_fr_LF_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_FOOT_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_LF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,1) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,2) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,3) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * c_q_LF_HFE_) * s_q_LF_KFE_) + ((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,4) = (((((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * c_q_LF_HAA_)); + (*this)(0,5) = ((((((( 0.19716 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * c_q_LF_KFE_)) - ( 0.33797 * s_q_LF_HAA_)); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(1,3) = (((((( 0.08795 * c_q_LF_HFE_) - ( 0.33797 * s_q_LF_HFE_)) * s_q_LF_KFE_) + ((( 0.08795 * s_q_LF_HFE_) + ( 0.33797 * c_q_LF_HFE_)) * c_q_LF_KFE_)) + ( 0.285 * c_q_LF_HFE_)) + ( 0.104 * s_q_LF_HAA_)); + (*this)(1,4) = ((((((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_)) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(1,5) = (((((((- 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)) + ( 0.3598 * c_q_LF_HAA_)); + (*this)(2,0) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(2,1) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(2,3) = (((((- 0.104 * c_q_LF_HAA_) - 0.19716) * s_q_LF_HFE_) * s_q_LF_KFE_) + (((( 0.104 * c_q_LF_HAA_) + 0.19716) * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,4) = ((((((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.19716 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)) * s_q_LF_KFE_) + (((( 0.19716 * s_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * c_q_LF_HAA_)); + (*this)(2,5) = ((((((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.19716 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)) * s_q_LF_KFE_) + (((((- 0.19716 * c_q_LF_HAA_) - 0.104) * s_q_LF_HFE_) - (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.08795 * s_q_LF_HAA_)); + (*this)(3,3) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(3,4) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(3,5) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = s_q_LF_HAA_; + (*this)(5,3) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(5,4) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(5,5) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_FOOT::Type_fr_base_X_fr_LH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_FOOT& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_FOOT::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,2) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(0,3) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * c_q_LH_HFE_) * s_q_LH_KFE_) + ((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,4) = ((((((- 0.33797 * s_q_LH_HFE_) - ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.33797 * c_q_LH_HFE_) - ( 0.08795 * s_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.285 * c_q_LH_HFE_)) + ( 0.104 * s_q_LH_HAA_)); + (*this)(0,5) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * s_q_LH_KFE_) + (((( 0.104 * c_q_LH_HAA_) + 0.19716) * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,0) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,3) = ((((((- 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * c_q_LH_HAA_)); + (*this)(1,4) = ((((((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_)) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(1,5) = (((((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * s_q_LH_KFE_) + (((( 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * c_q_LH_HAA_)); + (*this)(2,0) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,1) = s_q_LH_HAA_; + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(2,3) = ((((((( 0.19716 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * s_q_LH_HAA_)); + (*this)(2,4) = ((((((( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_)) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(2,5) = (((((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * s_q_LH_KFE_) + (((((- 0.19716 * c_q_LH_HAA_) - 0.104) * s_q_LH_HFE_) + (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * s_q_LH_HAA_)); + (*this)(3,3) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(3,5) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(4,3) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,3) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,4) = s_q_LH_HAA_; + (*this)(5,5) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_FOOT_X_fr_base::Type_fr_LH_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_FOOT_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_LH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,1) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,2) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,3) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * c_q_LH_HFE_) * s_q_LH_KFE_) + ((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,4) = ((((((- 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * c_q_LH_HAA_)); + (*this)(0,5) = ((((((( 0.19716 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * c_q_LH_KFE_)) - ( 0.33797 * s_q_LH_HAA_)); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(1,3) = ((((((- 0.33797 * s_q_LH_HFE_) - ( 0.08795 * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((( 0.33797 * c_q_LH_HFE_) - ( 0.08795 * s_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.285 * c_q_LH_HFE_)) + ( 0.104 * s_q_LH_HAA_)); + (*this)(1,4) = ((((((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_)) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(1,5) = ((((((( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + ((((- 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_)) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(2,0) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(2,1) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(2,3) = (((((- 0.104 * c_q_LH_HAA_) - 0.19716) * s_q_LH_HFE_) * s_q_LH_KFE_) + (((( 0.104 * c_q_LH_HAA_) + 0.19716) * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,4) = (((((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.19716 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)) * s_q_LH_KFE_) + (((( 0.19716 * s_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * c_q_LH_HAA_)); + (*this)(2,5) = (((((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.19716 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)) * s_q_LH_KFE_) + (((((- 0.19716 * c_q_LH_HAA_) - 0.104) * s_q_LH_HFE_) + (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) + ( 0.08795 * s_q_LH_HAA_)); + (*this)(3,3) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(3,4) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(3,5) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = s_q_LH_HAA_; + (*this)(5,3) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(5,4) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(5,5) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_FOOT::Type_fr_base_X_fr_RF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_FOOT& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_FOOT::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,2) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(0,3) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * c_q_RF_HFE_) * s_q_RF_KFE_) + (((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,4) = (((((( 0.08795 * c_q_RF_HFE_) - ( 0.33797 * s_q_RF_HFE_)) * s_q_RF_KFE_) + ((( 0.08795 * s_q_RF_HFE_) + ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)) + ( 0.285 * c_q_RF_HFE_)) - ( 0.104 * s_q_RF_HAA_)); + (*this)(0,5) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * s_q_RF_KFE_) + ((((- 0.104 * c_q_RF_HAA_) - 0.19716) * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,0) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,3) = (((((( 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * c_q_RF_HAA_)); + (*this)(1,4) = ((((((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_)) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(1,5) = ((((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * s_q_RF_KFE_) + ((((- 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * c_q_RF_HAA_)); + (*this)(2,0) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,1) = s_q_RF_HAA_; + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(2,3) = (((((((- 0.19716 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * s_q_RF_HAA_)); + (*this)(2,4) = (((((((- 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)) + ( 0.3598 * c_q_RF_HAA_)); + (*this)(2,5) = ((((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * s_q_RF_KFE_) + ((((( 0.19716 * c_q_RF_HAA_) + 0.104) * s_q_RF_HFE_) - (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * s_q_RF_HAA_)); + (*this)(3,3) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(3,5) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(4,3) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,3) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,4) = s_q_RF_HAA_; + (*this)(5,5) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_FOOT_X_fr_base::Type_fr_RF_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_FOOT_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_RF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,1) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,2) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,3) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * c_q_RF_HFE_) * s_q_RF_KFE_) + (((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,4) = (((((( 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * c_q_RF_HAA_)); + (*this)(0,5) = (((((((- 0.19716 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * c_q_RF_KFE_)) - ( 0.33797 * s_q_RF_HAA_)); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(1,3) = (((((( 0.08795 * c_q_RF_HFE_) - ( 0.33797 * s_q_RF_HFE_)) * s_q_RF_KFE_) + ((( 0.08795 * s_q_RF_HFE_) + ( 0.33797 * c_q_RF_HFE_)) * c_q_RF_KFE_)) + ( 0.285 * c_q_RF_HFE_)) - ( 0.104 * s_q_RF_HAA_)); + (*this)(1,4) = ((((((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_)) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(1,5) = (((((((- 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)) + ( 0.3598 * c_q_RF_HAA_)); + (*this)(2,0) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(2,1) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(2,3) = ((((( 0.104 * c_q_RF_HAA_) + 0.19716) * s_q_RF_HFE_) * s_q_RF_KFE_) + ((((- 0.104 * c_q_RF_HAA_) - 0.19716) * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,4) = ((((((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.19716 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)) * s_q_RF_KFE_) + ((((- 0.19716 * s_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * c_q_RF_HAA_)); + (*this)(2,5) = ((((((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.19716 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)) * s_q_RF_KFE_) + ((((( 0.19716 * c_q_RF_HAA_) + 0.104) * s_q_RF_HFE_) - (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.08795 * s_q_RF_HAA_)); + (*this)(3,3) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(3,4) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(3,5) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = s_q_RF_HAA_; + (*this)(5,3) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(5,4) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(5,5) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_FOOT::Type_fr_base_X_fr_RH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_FOOT& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_FOOT::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,2) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(0,3) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * c_q_RH_HFE_) * s_q_RH_KFE_) + (((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,4) = ((((((- 0.33797 * s_q_RH_HFE_) - ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.33797 * c_q_RH_HFE_) - ( 0.08795 * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.285 * c_q_RH_HFE_)) - ( 0.104 * s_q_RH_HAA_)); + (*this)(0,5) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * s_q_RH_KFE_) + ((((- 0.104 * c_q_RH_HAA_) - 0.19716) * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,0) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,3) = (((((( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * c_q_RH_HAA_)); + (*this)(1,4) = ((((((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_)) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(1,5) = (((((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * s_q_RH_KFE_) + (((( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * c_q_RH_HAA_)); + (*this)(2,0) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,1) = s_q_RH_HAA_; + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(2,3) = (((((((- 0.19716 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * s_q_RH_HAA_)); + (*this)(2,4) = ((((((( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_)) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(2,5) = (((((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * s_q_RH_KFE_) + ((((( 0.19716 * c_q_RH_HAA_) + 0.104) * s_q_RH_HFE_) + (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * s_q_RH_HAA_)); + (*this)(3,3) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(3,5) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(4,3) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,3) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,4) = s_q_RH_HAA_; + (*this)(5,5) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_FOOT_X_fr_base::Type_fr_RH_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_FOOT_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_RH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,1) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,2) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,3) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * c_q_RH_HFE_) * s_q_RH_KFE_) + (((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,4) = (((((( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * c_q_RH_HAA_)); + (*this)(0,5) = (((((((- 0.19716 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * c_q_RH_KFE_)) - ( 0.33797 * s_q_RH_HAA_)); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(1,3) = ((((((- 0.33797 * s_q_RH_HFE_) - ( 0.08795 * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((( 0.33797 * c_q_RH_HFE_) - ( 0.08795 * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.285 * c_q_RH_HFE_)) - ( 0.104 * s_q_RH_HAA_)); + (*this)(1,4) = ((((((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_)) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(1,5) = ((((((( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + ((((- 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_)) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(2,0) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(2,1) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(2,3) = ((((( 0.104 * c_q_RH_HAA_) + 0.19716) * s_q_RH_HFE_) * s_q_RH_KFE_) + ((((- 0.104 * c_q_RH_HAA_) - 0.19716) * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,4) = (((((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)) * s_q_RH_KFE_) + (((( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.19716 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * c_q_RH_HAA_)); + (*this)(2,5) = (((((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.19716 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)) * s_q_RH_KFE_) + ((((( 0.19716 * c_q_RH_HAA_) + 0.104) * s_q_RH_HFE_) + (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) + ( 0.08795 * s_q_RH_HAA_)); + (*this)(3,3) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(3,4) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(3,5) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = s_q_RH_HAA_; + (*this)(5,3) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(5,4) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(5,5) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HAA::Type_fr_base_X_fr_LF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.104; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.2999; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0.2999; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HAA& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HFE::Type_fr_base_X_fr_LF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HFE::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,4) = ((- 0.104 * c_q_LF_HAA_) - 0.08381); + (*this)(0,5) = ( 0.104 * s_q_LF_HAA_); + (*this)(1,1) = s_q_LF_HAA_; + (*this)(1,2) = c_q_LF_HAA_; + (*this)(1,3) = ( 0.08381 * s_q_LF_HAA_); + (*this)(1,4) = ( 0.3598 * c_q_LF_HAA_); + (*this)(1,5) = (- 0.3598 * s_q_LF_HAA_); + (*this)(2,1) = - c_q_LF_HAA_; + (*this)(2,2) = s_q_LF_HAA_; + (*this)(2,3) = ((- 0.08381 * c_q_LF_HAA_) - 0.104); + (*this)(2,4) = ( 0.3598 * s_q_LF_HAA_); + (*this)(2,5) = ( 0.3598 * c_q_LF_HAA_); + (*this)(4,4) = s_q_LF_HAA_; + (*this)(4,5) = c_q_LF_HAA_; + (*this)(5,4) = - c_q_LF_HAA_; + (*this)(5,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_KFE::Type_fr_base_X_fr_LF_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_KFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_KFE::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = c_q_LF_HFE_; + (*this)(0,1) = - s_q_LF_HFE_; + (*this)(0,3) = (((- 0.104 * c_q_LF_HAA_) - 0.18411) * s_q_LF_HFE_); + (*this)(0,4) = (((- 0.104 * c_q_LF_HAA_) - 0.18411) * c_q_LF_HFE_); + (*this)(0,5) = (( 0.285 * c_q_LF_HFE_) + ( 0.104 * s_q_LF_HAA_)); + (*this)(1,0) = ( s_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(1,1) = ( s_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(1,2) = c_q_LF_HAA_; + (*this)(1,3) = (((( 0.3598 * c_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.18411 * s_q_LF_HAA_) * c_q_LF_HFE_)) - ( 0.285 * c_q_LF_HAA_)); + (*this)(1,4) = ((( 0.3598 * c_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.18411 * s_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(1,5) = ((( 0.285 * s_q_LF_HAA_) * s_q_LF_HFE_) - ( 0.3598 * s_q_LF_HAA_)); + (*this)(2,0) = (- c_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(2,1) = (- c_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(2,2) = s_q_LF_HAA_; + (*this)(2,3) = (((( 0.3598 * s_q_LF_HAA_) * s_q_LF_HFE_) + (((- 0.18411 * c_q_LF_HAA_) - 0.104) * c_q_LF_HFE_)) - ( 0.285 * s_q_LF_HAA_)); + (*this)(2,4) = (((( 0.18411 * c_q_LF_HAA_) + 0.104) * s_q_LF_HFE_) + (( 0.3598 * s_q_LF_HAA_) * c_q_LF_HFE_)); + (*this)(2,5) = (( 0.3598 * c_q_LF_HAA_) - (( 0.285 * c_q_LF_HAA_) * s_q_LF_HFE_)); + (*this)(3,3) = c_q_LF_HFE_; + (*this)(3,4) = - s_q_LF_HFE_; + (*this)(4,3) = ( s_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(4,4) = ( s_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(4,5) = c_q_LF_HAA_; + (*this)(5,3) = (- c_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(5,4) = (- c_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(5,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HAA::Type_fr_base_X_fr_LH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.104; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.2999; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = - 0.2999; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HAA& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HFE::Type_fr_base_X_fr_LH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HFE::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,4) = ((- 0.104 * c_q_LH_HAA_) - 0.08381); + (*this)(0,5) = ( 0.104 * s_q_LH_HAA_); + (*this)(1,1) = s_q_LH_HAA_; + (*this)(1,2) = c_q_LH_HAA_; + (*this)(1,3) = ( 0.08381 * s_q_LH_HAA_); + (*this)(1,4) = (- 0.3598 * c_q_LH_HAA_); + (*this)(1,5) = ( 0.3598 * s_q_LH_HAA_); + (*this)(2,1) = - c_q_LH_HAA_; + (*this)(2,2) = s_q_LH_HAA_; + (*this)(2,3) = ((- 0.08381 * c_q_LH_HAA_) - 0.104); + (*this)(2,4) = (- 0.3598 * s_q_LH_HAA_); + (*this)(2,5) = (- 0.3598 * c_q_LH_HAA_); + (*this)(4,4) = s_q_LH_HAA_; + (*this)(4,5) = c_q_LH_HAA_; + (*this)(5,4) = - c_q_LH_HAA_; + (*this)(5,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_KFE::Type_fr_base_X_fr_LH_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_KFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_KFE::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = c_q_LH_HFE_; + (*this)(0,1) = - s_q_LH_HFE_; + (*this)(0,3) = (((- 0.104 * c_q_LH_HAA_) - 0.18411) * s_q_LH_HFE_); + (*this)(0,4) = (((- 0.104 * c_q_LH_HAA_) - 0.18411) * c_q_LH_HFE_); + (*this)(0,5) = (( 0.285 * c_q_LH_HFE_) + ( 0.104 * s_q_LH_HAA_)); + (*this)(1,0) = ( s_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(1,1) = ( s_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(1,2) = c_q_LH_HAA_; + (*this)(1,3) = ((((- 0.3598 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.18411 * s_q_LH_HAA_) * c_q_LH_HFE_)) - ( 0.285 * c_q_LH_HAA_)); + (*this)(1,4) = (((- 0.18411 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.3598 * c_q_LH_HAA_) * c_q_LH_HFE_)); + (*this)(1,5) = ((( 0.285 * s_q_LH_HAA_) * s_q_LH_HFE_) + ( 0.3598 * s_q_LH_HAA_)); + (*this)(2,0) = (- c_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(2,1) = (- c_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(2,2) = s_q_LH_HAA_; + (*this)(2,3) = ((((- 0.3598 * s_q_LH_HAA_) * s_q_LH_HFE_) + (((- 0.18411 * c_q_LH_HAA_) - 0.104) * c_q_LH_HFE_)) - ( 0.285 * s_q_LH_HAA_)); + (*this)(2,4) = (((( 0.18411 * c_q_LH_HAA_) + 0.104) * s_q_LH_HFE_) - (( 0.3598 * s_q_LH_HAA_) * c_q_LH_HFE_)); + (*this)(2,5) = (((- 0.285 * c_q_LH_HAA_) * s_q_LH_HFE_) - ( 0.3598 * c_q_LH_HAA_)); + (*this)(3,3) = c_q_LH_HFE_; + (*this)(3,4) = - s_q_LH_HFE_; + (*this)(4,3) = ( s_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(4,4) = ( s_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(4,5) = c_q_LH_HAA_; + (*this)(5,3) = (- c_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(5,4) = (- c_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(5,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HAA::Type_fr_base_X_fr_RF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.104; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.2999; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0.2999; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HAA& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HFE::Type_fr_base_X_fr_RF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HFE::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,4) = (( 0.104 * c_q_RF_HAA_) + 0.08381); + (*this)(0,5) = (- 0.104 * s_q_RF_HAA_); + (*this)(1,1) = s_q_RF_HAA_; + (*this)(1,2) = c_q_RF_HAA_; + (*this)(1,3) = (- 0.08381 * s_q_RF_HAA_); + (*this)(1,4) = ( 0.3598 * c_q_RF_HAA_); + (*this)(1,5) = (- 0.3598 * s_q_RF_HAA_); + (*this)(2,1) = - c_q_RF_HAA_; + (*this)(2,2) = s_q_RF_HAA_; + (*this)(2,3) = (( 0.08381 * c_q_RF_HAA_) + 0.104); + (*this)(2,4) = ( 0.3598 * s_q_RF_HAA_); + (*this)(2,5) = ( 0.3598 * c_q_RF_HAA_); + (*this)(4,4) = s_q_RF_HAA_; + (*this)(4,5) = c_q_RF_HAA_; + (*this)(5,4) = - c_q_RF_HAA_; + (*this)(5,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_KFE::Type_fr_base_X_fr_RF_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_KFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_KFE::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = c_q_RF_HFE_; + (*this)(0,1) = - s_q_RF_HFE_; + (*this)(0,3) = ((( 0.104 * c_q_RF_HAA_) + 0.18411) * s_q_RF_HFE_); + (*this)(0,4) = ((( 0.104 * c_q_RF_HAA_) + 0.18411) * c_q_RF_HFE_); + (*this)(0,5) = (( 0.285 * c_q_RF_HFE_) - ( 0.104 * s_q_RF_HAA_)); + (*this)(1,0) = ( s_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(1,1) = ( s_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(1,2) = c_q_RF_HAA_; + (*this)(1,3) = (((( 0.3598 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.18411 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.285 * c_q_RF_HAA_)); + (*this)(1,4) = ((( 0.18411 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.3598 * c_q_RF_HAA_) * c_q_RF_HFE_)); + (*this)(1,5) = ((( 0.285 * s_q_RF_HAA_) * s_q_RF_HFE_) - ( 0.3598 * s_q_RF_HAA_)); + (*this)(2,0) = (- c_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(2,1) = (- c_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(2,2) = s_q_RF_HAA_; + (*this)(2,3) = (((( 0.3598 * s_q_RF_HAA_) * s_q_RF_HFE_) + ((( 0.18411 * c_q_RF_HAA_) + 0.104) * c_q_RF_HFE_)) - ( 0.285 * s_q_RF_HAA_)); + (*this)(2,4) = ((((- 0.18411 * c_q_RF_HAA_) - 0.104) * s_q_RF_HFE_) + (( 0.3598 * s_q_RF_HAA_) * c_q_RF_HFE_)); + (*this)(2,5) = (( 0.3598 * c_q_RF_HAA_) - (( 0.285 * c_q_RF_HAA_) * s_q_RF_HFE_)); + (*this)(3,3) = c_q_RF_HFE_; + (*this)(3,4) = - s_q_RF_HFE_; + (*this)(4,3) = ( s_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(4,4) = ( s_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(4,5) = c_q_RF_HAA_; + (*this)(5,3) = (- c_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(5,4) = (- c_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(5,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HAA::Type_fr_base_X_fr_RH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.104; + (*this)(0,4) = 0; + (*this)(0,5) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.2999; + (*this)(1,4) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = - 0.2999; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 1.0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = - 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HAA& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HFE::Type_fr_base_X_fr_RH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; + (*this)(3,4) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HFE::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,4) = (( 0.104 * c_q_RH_HAA_) + 0.08381); + (*this)(0,5) = (- 0.104 * s_q_RH_HAA_); + (*this)(1,1) = s_q_RH_HAA_; + (*this)(1,2) = c_q_RH_HAA_; + (*this)(1,3) = (- 0.08381 * s_q_RH_HAA_); + (*this)(1,4) = (- 0.3598 * c_q_RH_HAA_); + (*this)(1,5) = ( 0.3598 * s_q_RH_HAA_); + (*this)(2,1) = - c_q_RH_HAA_; + (*this)(2,2) = s_q_RH_HAA_; + (*this)(2,3) = (( 0.08381 * c_q_RH_HAA_) + 0.104); + (*this)(2,4) = (- 0.3598 * s_q_RH_HAA_); + (*this)(2,5) = (- 0.3598 * c_q_RH_HAA_); + (*this)(4,4) = s_q_RH_HAA_; + (*this)(4,5) = c_q_RH_HAA_; + (*this)(5,4) = - c_q_RH_HAA_; + (*this)(5,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_KFE::Type_fr_base_X_fr_RH_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_KFE& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_KFE::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = c_q_RH_HFE_; + (*this)(0,1) = - s_q_RH_HFE_; + (*this)(0,3) = ((( 0.104 * c_q_RH_HAA_) + 0.18411) * s_q_RH_HFE_); + (*this)(0,4) = ((( 0.104 * c_q_RH_HAA_) + 0.18411) * c_q_RH_HFE_); + (*this)(0,5) = (( 0.285 * c_q_RH_HFE_) - ( 0.104 * s_q_RH_HAA_)); + (*this)(1,0) = ( s_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(1,1) = ( s_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(1,2) = c_q_RH_HAA_; + (*this)(1,3) = ((((- 0.3598 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.18411 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.285 * c_q_RH_HAA_)); + (*this)(1,4) = ((( 0.18411 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.3598 * c_q_RH_HAA_) * c_q_RH_HFE_)); + (*this)(1,5) = ((( 0.285 * s_q_RH_HAA_) * s_q_RH_HFE_) + ( 0.3598 * s_q_RH_HAA_)); + (*this)(2,0) = (- c_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(2,1) = (- c_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(2,2) = s_q_RH_HAA_; + (*this)(2,3) = ((((- 0.3598 * s_q_RH_HAA_) * s_q_RH_HFE_) + ((( 0.18411 * c_q_RH_HAA_) + 0.104) * c_q_RH_HFE_)) - ( 0.285 * s_q_RH_HAA_)); + (*this)(2,4) = ((((- 0.18411 * c_q_RH_HAA_) - 0.104) * s_q_RH_HFE_) - (( 0.3598 * s_q_RH_HAA_) * c_q_RH_HFE_)); + (*this)(2,5) = (((- 0.285 * c_q_RH_HAA_) * s_q_RH_HFE_) - ( 0.3598 * c_q_RH_HAA_)); + (*this)(3,3) = c_q_RH_HFE_; + (*this)(3,4) = - s_q_RH_HFE_; + (*this)(4,3) = ( s_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(4,4) = ( s_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(4,5) = c_q_RH_HAA_; + (*this)(5,3) = (- c_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(5,4) = (- c_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(5,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_base::Type_fr_LF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,1) = s_q_LF_HAA_; + (*this)(0,2) = - c_q_LF_HAA_; + (*this)(0,3) = (- 0.104 * c_q_LF_HAA_); + (*this)(0,4) = ( 0.2999 * c_q_LF_HAA_); + (*this)(0,5) = ( 0.2999 * s_q_LF_HAA_); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(1,3) = ( 0.104 * s_q_LF_HAA_); + (*this)(1,4) = (- 0.2999 * s_q_LF_HAA_); + (*this)(1,5) = ( 0.2999 * c_q_LF_HAA_); + (*this)(3,4) = s_q_LF_HAA_; + (*this)(3,5) = - c_q_LF_HAA_; + (*this)(4,4) = c_q_LF_HAA_; + (*this)(4,5) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HIP::Type_fr_base_X_fr_LF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HIP& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,3) = (- 0.104 * c_q_LF_HAA_); + (*this)(0,4) = ( 0.104 * s_q_LF_HAA_); + (*this)(1,0) = s_q_LF_HAA_; + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,3) = ( 0.2999 * c_q_LF_HAA_); + (*this)(1,4) = (- 0.2999 * s_q_LF_HAA_); + (*this)(2,0) = - c_q_LF_HAA_; + (*this)(2,1) = s_q_LF_HAA_; + (*this)(2,3) = ( 0.2999 * s_q_LF_HAA_); + (*this)(2,4) = ( 0.2999 * c_q_LF_HAA_); + (*this)(4,3) = s_q_LF_HAA_; + (*this)(4,4) = c_q_LF_HAA_; + (*this)(5,3) = - c_q_LF_HAA_; + (*this)(5,4) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::Type_fr_LF_THIGH_X_fr_LF_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.0599; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP& iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,2) = c_q_LF_HFE_; + (*this)(0,3) = ( 0.08381 * c_q_LF_HFE_); + (*this)(0,4) = ( 0.0599 * s_q_LF_HFE_); + (*this)(0,5) = (- 0.08381 * s_q_LF_HFE_); + (*this)(1,0) = c_q_LF_HFE_; + (*this)(1,2) = - s_q_LF_HFE_; + (*this)(1,3) = (- 0.08381 * s_q_LF_HFE_); + (*this)(1,4) = ( 0.0599 * c_q_LF_HFE_); + (*this)(1,5) = (- 0.08381 * c_q_LF_HFE_); + (*this)(3,3) = s_q_LF_HFE_; + (*this)(3,5) = c_q_LF_HFE_; + (*this)(4,3) = c_q_LF_HFE_; + (*this)(4,5) = - s_q_LF_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::Type_fr_LF_HIP_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,5) = - 0.0599; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,1) = c_q_LF_HFE_; + (*this)(0,3) = ( 0.08381 * c_q_LF_HFE_); + (*this)(0,4) = (- 0.08381 * s_q_LF_HFE_); + (*this)(1,3) = ( 0.0599 * s_q_LF_HFE_); + (*this)(1,4) = ( 0.0599 * c_q_LF_HFE_); + (*this)(2,0) = c_q_LF_HFE_; + (*this)(2,1) = - s_q_LF_HFE_; + (*this)(2,3) = (- 0.08381 * s_q_LF_HFE_); + (*this)(2,4) = (- 0.08381 * c_q_LF_HFE_); + (*this)(3,3) = s_q_LF_HFE_; + (*this)(3,4) = c_q_LF_HFE_; + (*this)(5,3) = c_q_LF_HFE_; + (*this)(5,4) = - s_q_LF_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::Type_fr_LF_SHANK_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.285; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = s_q_LF_KFE_; + (*this)(0,3) = (- 0.1003 * s_q_LF_KFE_); + (*this)(0,4) = ( 0.1003 * c_q_LF_KFE_); + (*this)(0,5) = (- 0.285 * c_q_LF_KFE_); + (*this)(1,0) = - s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + (*this)(1,3) = (- 0.1003 * c_q_LF_KFE_); + (*this)(1,4) = (- 0.1003 * s_q_LF_KFE_); + (*this)(1,5) = ( 0.285 * s_q_LF_KFE_); + (*this)(3,3) = c_q_LF_KFE_; + (*this)(3,4) = s_q_LF_KFE_; + (*this)(4,3) = - s_q_LF_KFE_; + (*this)(4,4) = c_q_LF_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::Type_fr_LF_THIGH_X_fr_LF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.285; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK& iit::camel::tpl::ForceTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = - s_q_LF_KFE_; + (*this)(0,3) = (- 0.1003 * s_q_LF_KFE_); + (*this)(0,4) = (- 0.1003 * c_q_LF_KFE_); + (*this)(1,0) = s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + (*this)(1,3) = ( 0.1003 * c_q_LF_KFE_); + (*this)(1,4) = (- 0.1003 * s_q_LF_KFE_); + (*this)(2,3) = (- 0.285 * c_q_LF_KFE_); + (*this)(2,4) = ( 0.285 * s_q_LF_KFE_); + (*this)(3,3) = c_q_LF_KFE_; + (*this)(3,4) = - s_q_LF_KFE_; + (*this)(4,3) = s_q_LF_KFE_; + (*this)(4,4) = c_q_LF_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_base::Type_fr_RF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,1) = s_q_RF_HAA_; + (*this)(0,2) = - c_q_RF_HAA_; + (*this)(0,3) = ( 0.104 * c_q_RF_HAA_); + (*this)(0,4) = ( 0.2999 * c_q_RF_HAA_); + (*this)(0,5) = ( 0.2999 * s_q_RF_HAA_); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(1,3) = (- 0.104 * s_q_RF_HAA_); + (*this)(1,4) = (- 0.2999 * s_q_RF_HAA_); + (*this)(1,5) = ( 0.2999 * c_q_RF_HAA_); + (*this)(3,4) = s_q_RF_HAA_; + (*this)(3,5) = - c_q_RF_HAA_; + (*this)(4,4) = c_q_RF_HAA_; + (*this)(4,5) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HIP::Type_fr_base_X_fr_RF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HIP& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,3) = ( 0.104 * c_q_RF_HAA_); + (*this)(0,4) = (- 0.104 * s_q_RF_HAA_); + (*this)(1,0) = s_q_RF_HAA_; + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,3) = ( 0.2999 * c_q_RF_HAA_); + (*this)(1,4) = (- 0.2999 * s_q_RF_HAA_); + (*this)(2,0) = - c_q_RF_HAA_; + (*this)(2,1) = s_q_RF_HAA_; + (*this)(2,3) = ( 0.2999 * s_q_RF_HAA_); + (*this)(2,4) = ( 0.2999 * c_q_RF_HAA_); + (*this)(4,3) = s_q_RF_HAA_; + (*this)(4,4) = c_q_RF_HAA_; + (*this)(5,3) = - c_q_RF_HAA_; + (*this)(5,4) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::Type_fr_RF_THIGH_X_fr_RF_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.0599; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP& iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,2) = c_q_RF_HFE_; + (*this)(0,3) = (- 0.08381 * c_q_RF_HFE_); + (*this)(0,4) = ( 0.0599 * s_q_RF_HFE_); + (*this)(0,5) = ( 0.08381 * s_q_RF_HFE_); + (*this)(1,0) = c_q_RF_HFE_; + (*this)(1,2) = - s_q_RF_HFE_; + (*this)(1,3) = ( 0.08381 * s_q_RF_HFE_); + (*this)(1,4) = ( 0.0599 * c_q_RF_HFE_); + (*this)(1,5) = ( 0.08381 * c_q_RF_HFE_); + (*this)(3,3) = s_q_RF_HFE_; + (*this)(3,5) = c_q_RF_HFE_; + (*this)(4,3) = c_q_RF_HFE_; + (*this)(4,5) = - s_q_RF_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::Type_fr_RF_HIP_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,5) = - 0.0599; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,1) = c_q_RF_HFE_; + (*this)(0,3) = (- 0.08381 * c_q_RF_HFE_); + (*this)(0,4) = ( 0.08381 * s_q_RF_HFE_); + (*this)(1,3) = ( 0.0599 * s_q_RF_HFE_); + (*this)(1,4) = ( 0.0599 * c_q_RF_HFE_); + (*this)(2,0) = c_q_RF_HFE_; + (*this)(2,1) = - s_q_RF_HFE_; + (*this)(2,3) = ( 0.08381 * s_q_RF_HFE_); + (*this)(2,4) = ( 0.08381 * c_q_RF_HFE_); + (*this)(3,3) = s_q_RF_HFE_; + (*this)(3,4) = c_q_RF_HFE_; + (*this)(5,3) = c_q_RF_HFE_; + (*this)(5,4) = - s_q_RF_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::Type_fr_RF_SHANK_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.285; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = s_q_RF_KFE_; + (*this)(0,3) = ( 0.1003 * s_q_RF_KFE_); + (*this)(0,4) = (- 0.1003 * c_q_RF_KFE_); + (*this)(0,5) = (- 0.285 * c_q_RF_KFE_); + (*this)(1,0) = - s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + (*this)(1,3) = ( 0.1003 * c_q_RF_KFE_); + (*this)(1,4) = ( 0.1003 * s_q_RF_KFE_); + (*this)(1,5) = ( 0.285 * s_q_RF_KFE_); + (*this)(3,3) = c_q_RF_KFE_; + (*this)(3,4) = s_q_RF_KFE_; + (*this)(4,3) = - s_q_RF_KFE_; + (*this)(4,4) = c_q_RF_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::Type_fr_RF_THIGH_X_fr_RF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.285; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK& iit::camel::tpl::ForceTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = - s_q_RF_KFE_; + (*this)(0,3) = ( 0.1003 * s_q_RF_KFE_); + (*this)(0,4) = ( 0.1003 * c_q_RF_KFE_); + (*this)(1,0) = s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + (*this)(1,3) = (- 0.1003 * c_q_RF_KFE_); + (*this)(1,4) = ( 0.1003 * s_q_RF_KFE_); + (*this)(2,3) = (- 0.285 * c_q_RF_KFE_); + (*this)(2,4) = ( 0.285 * s_q_RF_KFE_); + (*this)(3,3) = c_q_RF_KFE_; + (*this)(3,4) = - s_q_RF_KFE_; + (*this)(4,3) = s_q_RF_KFE_; + (*this)(4,4) = c_q_RF_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_base::Type_fr_LH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,1) = s_q_LH_HAA_; + (*this)(0,2) = - c_q_LH_HAA_; + (*this)(0,3) = (- 0.104 * c_q_LH_HAA_); + (*this)(0,4) = (- 0.2999 * c_q_LH_HAA_); + (*this)(0,5) = (- 0.2999 * s_q_LH_HAA_); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(1,3) = ( 0.104 * s_q_LH_HAA_); + (*this)(1,4) = ( 0.2999 * s_q_LH_HAA_); + (*this)(1,5) = (- 0.2999 * c_q_LH_HAA_); + (*this)(3,4) = s_q_LH_HAA_; + (*this)(3,5) = - c_q_LH_HAA_; + (*this)(4,4) = c_q_LH_HAA_; + (*this)(4,5) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HIP::Type_fr_base_X_fr_LH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = - 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HIP& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,3) = (- 0.104 * c_q_LH_HAA_); + (*this)(0,4) = ( 0.104 * s_q_LH_HAA_); + (*this)(1,0) = s_q_LH_HAA_; + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,3) = (- 0.2999 * c_q_LH_HAA_); + (*this)(1,4) = ( 0.2999 * s_q_LH_HAA_); + (*this)(2,0) = - c_q_LH_HAA_; + (*this)(2,1) = s_q_LH_HAA_; + (*this)(2,3) = (- 0.2999 * s_q_LH_HAA_); + (*this)(2,4) = (- 0.2999 * c_q_LH_HAA_); + (*this)(4,3) = s_q_LH_HAA_; + (*this)(4,4) = c_q_LH_HAA_; + (*this)(5,3) = - c_q_LH_HAA_; + (*this)(5,4) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::Type_fr_LH_THIGH_X_fr_LH_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.0599; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP& iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,2) = c_q_LH_HFE_; + (*this)(0,3) = ( 0.08381 * c_q_LH_HFE_); + (*this)(0,4) = (- 0.0599 * s_q_LH_HFE_); + (*this)(0,5) = (- 0.08381 * s_q_LH_HFE_); + (*this)(1,0) = c_q_LH_HFE_; + (*this)(1,2) = - s_q_LH_HFE_; + (*this)(1,3) = (- 0.08381 * s_q_LH_HFE_); + (*this)(1,4) = (- 0.0599 * c_q_LH_HFE_); + (*this)(1,5) = (- 0.08381 * c_q_LH_HFE_); + (*this)(3,3) = s_q_LH_HFE_; + (*this)(3,5) = c_q_LH_HFE_; + (*this)(4,3) = c_q_LH_HFE_; + (*this)(4,5) = - s_q_LH_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::Type_fr_LH_HIP_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.0599; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,1) = c_q_LH_HFE_; + (*this)(0,3) = ( 0.08381 * c_q_LH_HFE_); + (*this)(0,4) = (- 0.08381 * s_q_LH_HFE_); + (*this)(1,3) = (- 0.0599 * s_q_LH_HFE_); + (*this)(1,4) = (- 0.0599 * c_q_LH_HFE_); + (*this)(2,0) = c_q_LH_HFE_; + (*this)(2,1) = - s_q_LH_HFE_; + (*this)(2,3) = (- 0.08381 * s_q_LH_HFE_); + (*this)(2,4) = (- 0.08381 * c_q_LH_HFE_); + (*this)(3,3) = s_q_LH_HFE_; + (*this)(3,4) = c_q_LH_HFE_; + (*this)(5,3) = c_q_LH_HFE_; + (*this)(5,4) = - s_q_LH_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::Type_fr_LH_SHANK_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.285; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = s_q_LH_KFE_; + (*this)(0,3) = (- 0.1003 * s_q_LH_KFE_); + (*this)(0,4) = ( 0.1003 * c_q_LH_KFE_); + (*this)(0,5) = (- 0.285 * c_q_LH_KFE_); + (*this)(1,0) = - s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + (*this)(1,3) = (- 0.1003 * c_q_LH_KFE_); + (*this)(1,4) = (- 0.1003 * s_q_LH_KFE_); + (*this)(1,5) = ( 0.285 * s_q_LH_KFE_); + (*this)(3,3) = c_q_LH_KFE_; + (*this)(3,4) = s_q_LH_KFE_; + (*this)(4,3) = - s_q_LH_KFE_; + (*this)(4,4) = c_q_LH_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::Type_fr_LH_THIGH_X_fr_LH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.285; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK& iit::camel::tpl::ForceTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = - s_q_LH_KFE_; + (*this)(0,3) = (- 0.1003 * s_q_LH_KFE_); + (*this)(0,4) = (- 0.1003 * c_q_LH_KFE_); + (*this)(1,0) = s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + (*this)(1,3) = ( 0.1003 * c_q_LH_KFE_); + (*this)(1,4) = (- 0.1003 * s_q_LH_KFE_); + (*this)(2,3) = (- 0.285 * c_q_LH_KFE_); + (*this)(2,4) = ( 0.285 * s_q_LH_KFE_); + (*this)(3,3) = c_q_LH_KFE_; + (*this)(3,4) = - s_q_LH_KFE_; + (*this)(4,3) = s_q_LH_KFE_; + (*this)(4,4) = c_q_LH_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_base::Type_fr_RH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(2,4) = 0; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 1.0; + (*this)(5,4) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_base& iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,1) = s_q_RH_HAA_; + (*this)(0,2) = - c_q_RH_HAA_; + (*this)(0,3) = ( 0.104 * c_q_RH_HAA_); + (*this)(0,4) = (- 0.2999 * c_q_RH_HAA_); + (*this)(0,5) = (- 0.2999 * s_q_RH_HAA_); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(1,3) = (- 0.104 * s_q_RH_HAA_); + (*this)(1,4) = ( 0.2999 * s_q_RH_HAA_); + (*this)(1,5) = (- 0.2999 * c_q_RH_HAA_); + (*this)(3,4) = s_q_RH_HAA_; + (*this)(3,5) = - c_q_RH_HAA_; + (*this)(4,4) = c_q_RH_HAA_; + (*this)(4,5) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HIP::Type_fr_base_X_fr_RH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,5) = 0; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0.104; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 0; + (*this)(3,4) = 0; + (*this)(3,5) = 1.0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HIP& iit::camel::tpl::ForceTransforms::Type_fr_base_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,3) = ( 0.104 * c_q_RH_HAA_); + (*this)(0,4) = (- 0.104 * s_q_RH_HAA_); + (*this)(1,0) = s_q_RH_HAA_; + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,3) = (- 0.2999 * c_q_RH_HAA_); + (*this)(1,4) = ( 0.2999 * s_q_RH_HAA_); + (*this)(2,0) = - c_q_RH_HAA_; + (*this)(2,1) = s_q_RH_HAA_; + (*this)(2,3) = (- 0.2999 * s_q_RH_HAA_); + (*this)(2,4) = (- 0.2999 * c_q_RH_HAA_); + (*this)(4,3) = s_q_RH_HAA_; + (*this)(4,4) = c_q_RH_HAA_; + (*this)(5,3) = - c_q_RH_HAA_; + (*this)(5,4) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::Type_fr_RH_THIGH_X_fr_RH_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.0599; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,4) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,4) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 1.0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP& iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,2) = c_q_RH_HFE_; + (*this)(0,3) = (- 0.08381 * c_q_RH_HFE_); + (*this)(0,4) = (- 0.0599 * s_q_RH_HFE_); + (*this)(0,5) = ( 0.08381 * s_q_RH_HFE_); + (*this)(1,0) = c_q_RH_HFE_; + (*this)(1,2) = - s_q_RH_HFE_; + (*this)(1,3) = ( 0.08381 * s_q_RH_HFE_); + (*this)(1,4) = (- 0.0599 * c_q_RH_HFE_); + (*this)(1,5) = ( 0.08381 * c_q_RH_HFE_); + (*this)(3,3) = s_q_RH_HFE_; + (*this)(3,5) = c_q_RH_HFE_; + (*this)(4,3) = c_q_RH_HFE_; + (*this)(4,5) = - s_q_RH_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::Type_fr_RH_HIP_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.0599; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,5) = 0; + (*this)(2,2) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,3) = 0; + (*this)(4,4) = 0; + (*this)(4,5) = 1.0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,5) = 0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,1) = c_q_RH_HFE_; + (*this)(0,3) = (- 0.08381 * c_q_RH_HFE_); + (*this)(0,4) = ( 0.08381 * s_q_RH_HFE_); + (*this)(1,3) = (- 0.0599 * s_q_RH_HFE_); + (*this)(1,4) = (- 0.0599 * c_q_RH_HFE_); + (*this)(2,0) = c_q_RH_HFE_; + (*this)(2,1) = - s_q_RH_HFE_; + (*this)(2,3) = ( 0.08381 * s_q_RH_HFE_); + (*this)(2,4) = ( 0.08381 * c_q_RH_HFE_); + (*this)(3,3) = s_q_RH_HFE_; + (*this)(3,4) = c_q_RH_HFE_; + (*this)(5,3) = c_q_RH_HFE_; + (*this)(5,4) = - s_q_RH_HFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::Type_fr_RH_SHANK_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.285; + (*this)(2,4) = 0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH& iit::camel::tpl::ForceTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = s_q_RH_KFE_; + (*this)(0,3) = ( 0.1003 * s_q_RH_KFE_); + (*this)(0,4) = (- 0.1003 * c_q_RH_KFE_); + (*this)(0,5) = (- 0.285 * c_q_RH_KFE_); + (*this)(1,0) = - s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + (*this)(1,3) = ( 0.1003 * c_q_RH_KFE_); + (*this)(1,4) = ( 0.1003 * s_q_RH_KFE_); + (*this)(1,5) = ( 0.285 * s_q_RH_KFE_); + (*this)(3,3) = c_q_RH_KFE_; + (*this)(3,4) = s_q_RH_KFE_; + (*this)(4,3) = - s_q_RH_KFE_; + (*this)(4,4) = c_q_RH_KFE_; + return *this; +} +template +iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::Type_fr_RH_THIGH_X_fr_RH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,5) = 0.285; + (*this)(1,2) = 0; + (*this)(1,5) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,5) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,5) = 0; + (*this)(4,0) = 0; + (*this)(4,1) = 0; + (*this)(4,2) = 0; + (*this)(4,5) = 0; + (*this)(5,0) = 0; + (*this)(5,1) = 0; + (*this)(5,2) = 0; + (*this)(5,3) = 0; + (*this)(5,4) = 0; + (*this)(5,5) = 1.0; +} +template +const typename iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK& iit::camel::tpl::ForceTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = - s_q_RH_KFE_; + (*this)(0,3) = ( 0.1003 * s_q_RH_KFE_); + (*this)(0,4) = ( 0.1003 * c_q_RH_KFE_); + (*this)(1,0) = s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + (*this)(1,3) = (- 0.1003 * c_q_RH_KFE_); + (*this)(1,4) = ( 0.1003 * s_q_RH_KFE_); + (*this)(2,3) = (- 0.285 * c_q_RH_KFE_); + (*this)(2,4) = ( 0.285 * s_q_RH_KFE_); + (*this)(3,3) = c_q_RH_KFE_; + (*this)(3,4) = - s_q_RH_KFE_; + (*this)(4,3) = s_q_RH_KFE_; + (*this)(4,4) = c_q_RH_KFE_; + return *this; +} + +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_FOOT::Type_fr_base_X_fr_LF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_FOOT& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_FOOT::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,2) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(0,3) = ((((((- 0.08795 * s_q_LF_HFE_) - ( 0.33797 * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((( 0.08795 * c_q_LF_HFE_) - ( 0.33797 * s_q_LF_HFE_)) * c_q_LF_KFE_)) - ( 0.285 * s_q_LF_HFE_)) + 0.3598); + (*this)(1,0) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(1,3) = (((((((( 0.08795 * s_q_LF_HAA_) * c_q_LF_HFE_) - (( 0.33797 * s_q_LF_HAA_) * s_q_LF_HFE_)) * s_q_LF_KFE_) + (((( 0.08795 * s_q_LF_HAA_) * s_q_LF_HFE_) + (( 0.33797 * s_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) + (( 0.285 * s_q_LF_HAA_) * c_q_LF_HFE_)) + ( 0.19716 * c_q_LF_HAA_)) + 0.104); + (*this)(2,0) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,1) = s_q_LF_HAA_; + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(2,3) = ((((((( 0.33797 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.08795 * c_q_LF_HAA_) * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((- 0.08795 * c_q_LF_HAA_) * s_q_LF_HFE_) - (( 0.33797 * c_q_LF_HAA_) * c_q_LF_HFE_)) * c_q_LF_KFE_)) - (( 0.285 * c_q_LF_HAA_) * c_q_LF_HFE_)) + ( 0.19716 * s_q_LF_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_FOOT_X_fr_base::Type_fr_LF_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_FOOT_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_KFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_KFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = (( c_q_LF_HFE_ * c_q_LF_KFE_) - ( s_q_LF_HFE_ * s_q_LF_KFE_)); + (*this)(0,1) = ((( s_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) + (( s_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,2) = (((- c_q_LF_HAA_ * c_q_LF_HFE_) * s_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(0,3) = (((((( 0.3598 * s_q_LF_HFE_) - (( 0.104 * s_q_LF_HAA_) * c_q_LF_HFE_)) - 0.285) * s_q_LF_KFE_) + ((((- 0.104 * s_q_LF_HAA_) * s_q_LF_HFE_) - ( 0.3598 * c_q_LF_HFE_)) * c_q_LF_KFE_)) - 0.08795); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(1,3) = ((- 0.104 * c_q_LF_HAA_) - 0.19716); + (*this)(2,0) = (( c_q_LF_HFE_ * s_q_LF_KFE_) + ( s_q_LF_HFE_ * c_q_LF_KFE_)); + (*this)(2,1) = ((( s_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_) - (( s_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_)); + (*this)(2,2) = ((( c_q_LF_HAA_ * c_q_LF_HFE_) * c_q_LF_KFE_) - (( c_q_LF_HAA_ * s_q_LF_HFE_) * s_q_LF_KFE_)); + (*this)(2,3) = ((((((- 0.104 * s_q_LF_HAA_) * s_q_LF_HFE_) - ( 0.3598 * c_q_LF_HFE_)) * s_q_LF_KFE_) + ((((- 0.3598 * s_q_LF_HFE_) + (( 0.104 * s_q_LF_HAA_) * c_q_LF_HFE_)) + 0.285) * c_q_LF_KFE_)) + 0.33797); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_FOOT::Type_fr_base_X_fr_LH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_FOOT& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_FOOT::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,2) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(0,3) = (((((( 0.08795 * s_q_LH_HFE_) - ( 0.33797 * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((- 0.33797 * s_q_LH_HFE_) - ( 0.08795 * c_q_LH_HFE_)) * c_q_LH_KFE_)) - ( 0.285 * s_q_LH_HFE_)) - 0.3598); + (*this)(1,0) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(1,3) = ((((((((- 0.33797 * s_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.33797 * s_q_LH_HAA_) * c_q_LH_HFE_) - (( 0.08795 * s_q_LH_HAA_) * s_q_LH_HFE_)) * c_q_LH_KFE_)) + (( 0.285 * s_q_LH_HAA_) * c_q_LH_HFE_)) + ( 0.19716 * c_q_LH_HAA_)) + 0.104); + (*this)(2,0) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,1) = s_q_LH_HAA_; + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(2,3) = ((((((( 0.33797 * c_q_LH_HAA_) * s_q_LH_HFE_) + (( 0.08795 * c_q_LH_HAA_) * c_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.08795 * c_q_LH_HAA_) * s_q_LH_HFE_) - (( 0.33797 * c_q_LH_HAA_) * c_q_LH_HFE_)) * c_q_LH_KFE_)) - (( 0.285 * c_q_LH_HAA_) * c_q_LH_HFE_)) + ( 0.19716 * s_q_LH_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_FOOT_X_fr_base::Type_fr_LH_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_FOOT_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_KFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_KFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = (( c_q_LH_HFE_ * c_q_LH_KFE_) - ( s_q_LH_HFE_ * s_q_LH_KFE_)); + (*this)(0,1) = ((( s_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) + (( s_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,2) = (((- c_q_LH_HAA_ * c_q_LH_HFE_) * s_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(0,3) = ((((((- 0.3598 * s_q_LH_HFE_) - (( 0.104 * s_q_LH_HAA_) * c_q_LH_HFE_)) - 0.285) * s_q_LH_KFE_) + ((( 0.3598 * c_q_LH_HFE_) - (( 0.104 * s_q_LH_HAA_) * s_q_LH_HFE_)) * c_q_LH_KFE_)) + 0.08795); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(1,3) = ((- 0.104 * c_q_LH_HAA_) - 0.19716); + (*this)(2,0) = (( c_q_LH_HFE_ * s_q_LH_KFE_) + ( s_q_LH_HFE_ * c_q_LH_KFE_)); + (*this)(2,1) = ((( s_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_) - (( s_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_)); + (*this)(2,2) = ((( c_q_LH_HAA_ * c_q_LH_HFE_) * c_q_LH_KFE_) - (( c_q_LH_HAA_ * s_q_LH_HFE_) * s_q_LH_KFE_)); + (*this)(2,3) = ((((( 0.3598 * c_q_LH_HFE_) - (( 0.104 * s_q_LH_HAA_) * s_q_LH_HFE_)) * s_q_LH_KFE_) + (((( 0.3598 * s_q_LH_HFE_) + (( 0.104 * s_q_LH_HAA_) * c_q_LH_HFE_)) + 0.285) * c_q_LH_KFE_)) + 0.33797); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_FOOT::Type_fr_base_X_fr_RF_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_FOOT& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_FOOT::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,2) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(0,3) = ((((((- 0.08795 * s_q_RF_HFE_) - ( 0.33797 * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((( 0.08795 * c_q_RF_HFE_) - ( 0.33797 * s_q_RF_HFE_)) * c_q_RF_KFE_)) - ( 0.285 * s_q_RF_HFE_)) + 0.3598); + (*this)(1,0) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(1,3) = (((((((( 0.08795 * s_q_RF_HAA_) * c_q_RF_HFE_) - (( 0.33797 * s_q_RF_HAA_) * s_q_RF_HFE_)) * s_q_RF_KFE_) + (((( 0.08795 * s_q_RF_HAA_) * s_q_RF_HFE_) + (( 0.33797 * s_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) + (( 0.285 * s_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.19716 * c_q_RF_HAA_)) - 0.104); + (*this)(2,0) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,1) = s_q_RF_HAA_; + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(2,3) = ((((((( 0.33797 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.08795 * c_q_RF_HAA_) * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((- 0.08795 * c_q_RF_HAA_) * s_q_RF_HFE_) - (( 0.33797 * c_q_RF_HAA_) * c_q_RF_HFE_)) * c_q_RF_KFE_)) - (( 0.285 * c_q_RF_HAA_) * c_q_RF_HFE_)) - ( 0.19716 * s_q_RF_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_FOOT_X_fr_base::Type_fr_RF_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_FOOT_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_KFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_KFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = (( c_q_RF_HFE_ * c_q_RF_KFE_) - ( s_q_RF_HFE_ * s_q_RF_KFE_)); + (*this)(0,1) = ((( s_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) + (( s_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,2) = (((- c_q_RF_HAA_ * c_q_RF_HFE_) * s_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(0,3) = (((((( 0.3598 * s_q_RF_HFE_) + (( 0.104 * s_q_RF_HAA_) * c_q_RF_HFE_)) - 0.285) * s_q_RF_KFE_) + (((( 0.104 * s_q_RF_HAA_) * s_q_RF_HFE_) - ( 0.3598 * c_q_RF_HFE_)) * c_q_RF_KFE_)) - 0.08795); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(1,3) = (( 0.104 * c_q_RF_HAA_) + 0.19716); + (*this)(2,0) = (( c_q_RF_HFE_ * s_q_RF_KFE_) + ( s_q_RF_HFE_ * c_q_RF_KFE_)); + (*this)(2,1) = ((( s_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_) - (( s_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_)); + (*this)(2,2) = ((( c_q_RF_HAA_ * c_q_RF_HFE_) * c_q_RF_KFE_) - (( c_q_RF_HAA_ * s_q_RF_HFE_) * s_q_RF_KFE_)); + (*this)(2,3) = (((((( 0.104 * s_q_RF_HAA_) * s_q_RF_HFE_) - ( 0.3598 * c_q_RF_HFE_)) * s_q_RF_KFE_) + ((((- 0.3598 * s_q_RF_HFE_) - (( 0.104 * s_q_RF_HAA_) * c_q_RF_HFE_)) + 0.285) * c_q_RF_KFE_)) + 0.33797); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_FOOT::Type_fr_base_X_fr_RH_FOOT() +{ + (*this)(0,1) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_FOOT& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_FOOT::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,2) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(0,3) = (((((( 0.08795 * s_q_RH_HFE_) - ( 0.33797 * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((- 0.33797 * s_q_RH_HFE_) - ( 0.08795 * c_q_RH_HFE_)) * c_q_RH_KFE_)) - ( 0.285 * s_q_RH_HFE_)) - 0.3598); + (*this)(1,0) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(1,3) = ((((((((- 0.33797 * s_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.33797 * s_q_RH_HAA_) * c_q_RH_HFE_) - (( 0.08795 * s_q_RH_HAA_) * s_q_RH_HFE_)) * c_q_RH_KFE_)) + (( 0.285 * s_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.19716 * c_q_RH_HAA_)) - 0.104); + (*this)(2,0) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,1) = s_q_RH_HAA_; + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(2,3) = ((((((( 0.33797 * c_q_RH_HAA_) * s_q_RH_HFE_) + (( 0.08795 * c_q_RH_HAA_) * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.08795 * c_q_RH_HAA_) * s_q_RH_HFE_) - (( 0.33797 * c_q_RH_HAA_) * c_q_RH_HFE_)) * c_q_RH_KFE_)) - (( 0.285 * c_q_RH_HAA_) * c_q_RH_HFE_)) - ( 0.19716 * s_q_RH_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_FOOT_X_fr_base::Type_fr_RH_FOOT_X_fr_base() +{ + (*this)(1,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_FOOT_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_FOOT_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_KFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_KFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = (( c_q_RH_HFE_ * c_q_RH_KFE_) - ( s_q_RH_HFE_ * s_q_RH_KFE_)); + (*this)(0,1) = ((( s_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) + (( s_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,2) = (((- c_q_RH_HAA_ * c_q_RH_HFE_) * s_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(0,3) = ((((((- 0.3598 * s_q_RH_HFE_) + (( 0.104 * s_q_RH_HAA_) * c_q_RH_HFE_)) - 0.285) * s_q_RH_KFE_) + (((( 0.104 * s_q_RH_HAA_) * s_q_RH_HFE_) + ( 0.3598 * c_q_RH_HFE_)) * c_q_RH_KFE_)) + 0.08795); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(1,3) = (( 0.104 * c_q_RH_HAA_) + 0.19716); + (*this)(2,0) = (( c_q_RH_HFE_ * s_q_RH_KFE_) + ( s_q_RH_HFE_ * c_q_RH_KFE_)); + (*this)(2,1) = ((( s_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_) - (( s_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_)); + (*this)(2,2) = ((( c_q_RH_HAA_ * c_q_RH_HFE_) * c_q_RH_KFE_) - (( c_q_RH_HAA_ * s_q_RH_HFE_) * s_q_RH_KFE_)); + (*this)(2,3) = (((((( 0.104 * s_q_RH_HAA_) * s_q_RH_HFE_) + ( 0.3598 * c_q_RH_HFE_)) * s_q_RH_KFE_) + (((( 0.3598 * s_q_RH_HFE_) - (( 0.104 * s_q_RH_HAA_) * c_q_RH_HFE_)) + 0.285) * c_q_RH_KFE_)) + 0.33797); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HAA::Type_fr_base_X_fr_LF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.2999; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.104; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HAA& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HFE::Type_fr_base_X_fr_LF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0.3598; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HFE::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(1,1) = s_q_LF_HAA_; + (*this)(1,2) = c_q_LF_HAA_; + (*this)(1,3) = (( 0.08381 * c_q_LF_HAA_) + 0.104); + (*this)(2,1) = - c_q_LF_HAA_; + (*this)(2,2) = s_q_LF_HAA_; + (*this)(2,3) = ( 0.08381 * s_q_LF_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_KFE::Type_fr_base_X_fr_LF_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_KFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_KFE::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HFE_; + Scalar c_q_LF_HAA_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,0) = c_q_LF_HFE_; + (*this)(0,1) = - s_q_LF_HFE_; + (*this)(0,3) = ( 0.3598 - ( 0.285 * s_q_LF_HFE_)); + (*this)(1,0) = ( s_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(1,1) = ( s_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(1,2) = c_q_LF_HAA_; + (*this)(1,3) = (((( 0.285 * s_q_LF_HAA_) * c_q_LF_HFE_) + ( 0.18411 * c_q_LF_HAA_)) + 0.104); + (*this)(2,0) = (- c_q_LF_HAA_ * s_q_LF_HFE_); + (*this)(2,1) = (- c_q_LF_HAA_ * c_q_LF_HFE_); + (*this)(2,2) = s_q_LF_HAA_; + (*this)(2,3) = (( 0.18411 * s_q_LF_HAA_) - (( 0.285 * c_q_LF_HAA_) * c_q_LF_HFE_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HAA::Type_fr_base_X_fr_LH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.2999; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.104; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HAA& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HFE::Type_fr_base_X_fr_LH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = - 0.3598; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HFE::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(1,1) = s_q_LH_HAA_; + (*this)(1,2) = c_q_LH_HAA_; + (*this)(1,3) = (( 0.08381 * c_q_LH_HAA_) + 0.104); + (*this)(2,1) = - c_q_LH_HAA_; + (*this)(2,2) = s_q_LH_HAA_; + (*this)(2,3) = ( 0.08381 * s_q_LH_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_KFE::Type_fr_base_X_fr_LH_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_KFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_KFE::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HFE_; + Scalar c_q_LH_HAA_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,0) = c_q_LH_HFE_; + (*this)(0,1) = - s_q_LH_HFE_; + (*this)(0,3) = ((- 0.285 * s_q_LH_HFE_) - 0.3598); + (*this)(1,0) = ( s_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(1,1) = ( s_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(1,2) = c_q_LH_HAA_; + (*this)(1,3) = (((( 0.285 * s_q_LH_HAA_) * c_q_LH_HFE_) + ( 0.18411 * c_q_LH_HAA_)) + 0.104); + (*this)(2,0) = (- c_q_LH_HAA_ * s_q_LH_HFE_); + (*this)(2,1) = (- c_q_LH_HAA_ * c_q_LH_HFE_); + (*this)(2,2) = s_q_LH_HAA_; + (*this)(2,3) = (( 0.18411 * s_q_LH_HAA_) - (( 0.285 * c_q_LH_HAA_) * c_q_LH_HFE_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HAA::Type_fr_base_X_fr_RF_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.2999; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.104; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HAA& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HFE::Type_fr_base_X_fr_RF_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = 0.3598; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HFE::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(1,1) = s_q_RF_HAA_; + (*this)(1,2) = c_q_RF_HAA_; + (*this)(1,3) = ((- 0.08381 * c_q_RF_HAA_) - 0.104); + (*this)(2,1) = - c_q_RF_HAA_; + (*this)(2,2) = s_q_RF_HAA_; + (*this)(2,3) = (- 0.08381 * s_q_RF_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_KFE::Type_fr_base_X_fr_RF_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_KFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_KFE::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HFE_; + Scalar c_q_RF_HAA_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,0) = c_q_RF_HFE_; + (*this)(0,1) = - s_q_RF_HFE_; + (*this)(0,3) = ( 0.3598 - ( 0.285 * s_q_RF_HFE_)); + (*this)(1,0) = ( s_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(1,1) = ( s_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(1,2) = c_q_RF_HAA_; + (*this)(1,3) = (((( 0.285 * s_q_RF_HAA_) * c_q_RF_HFE_) - ( 0.18411 * c_q_RF_HAA_)) - 0.104); + (*this)(2,0) = (- c_q_RF_HAA_ * s_q_RF_HFE_); + (*this)(2,1) = (- c_q_RF_HAA_ * c_q_RF_HFE_); + (*this)(2,2) = s_q_RF_HAA_; + (*this)(2,3) = (((- 0.285 * c_q_RF_HAA_) * c_q_RF_HFE_) - ( 0.18411 * s_q_RF_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HAA::Type_fr_base_X_fr_RH_HAA() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.2999; + (*this)(1,0) = 0; + (*this)(1,1) = 1.0; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.104; + (*this)(2,0) = - 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HAA& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HAA::update(const JState& q) { + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HFE::Type_fr_base_X_fr_RH_HFE() +{ + (*this)(0,0) = 1.0; + (*this)(0,1) = 0; + (*this)(0,2) = 0; + (*this)(0,3) = - 0.3598; + (*this)(1,0) = 0; + (*this)(2,0) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HFE::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(1,1) = s_q_RH_HAA_; + (*this)(1,2) = c_q_RH_HAA_; + (*this)(1,3) = ((- 0.08381 * c_q_RH_HAA_) - 0.104); + (*this)(2,1) = - c_q_RH_HAA_; + (*this)(2,2) = s_q_RH_HAA_; + (*this)(2,3) = (- 0.08381 * s_q_RH_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_KFE::Type_fr_base_X_fr_RH_KFE() +{ + (*this)(0,2) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_KFE& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_KFE::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HFE_; + Scalar c_q_RH_HAA_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,0) = c_q_RH_HFE_; + (*this)(0,1) = - s_q_RH_HFE_; + (*this)(0,3) = ((- 0.285 * s_q_RH_HFE_) - 0.3598); + (*this)(1,0) = ( s_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(1,1) = ( s_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(1,2) = c_q_RH_HAA_; + (*this)(1,3) = (((( 0.285 * s_q_RH_HAA_) * c_q_RH_HFE_) - ( 0.18411 * c_q_RH_HAA_)) - 0.104); + (*this)(2,0) = (- c_q_RH_HAA_ * s_q_RH_HFE_); + (*this)(2,1) = (- c_q_RH_HAA_ * c_q_RH_HFE_); + (*this)(2,2) = s_q_RH_HAA_; + (*this)(2,3) = (((- 0.285 * c_q_RH_HAA_) * c_q_RH_HFE_) - ( 0.18411 * s_q_RH_HAA_)); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_base::Type_fr_LF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.2999; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(0,1) = s_q_LF_HAA_; + (*this)(0,2) = - c_q_LF_HAA_; + (*this)(0,3) = (- 0.104 * s_q_LF_HAA_); + (*this)(1,1) = c_q_LF_HAA_; + (*this)(1,2) = s_q_LF_HAA_; + (*this)(1,3) = (- 0.104 * c_q_LF_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HIP::Type_fr_base_X_fr_LF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.2999; + (*this)(1,2) = 0; + (*this)(1,3) = 0.104; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HAA_; + Scalar c_q_LF_HAA_; + + s_q_LF_HAA_ = TRAIT::sin( q(LF_HAA)); + c_q_LF_HAA_ = TRAIT::cos( q(LF_HAA)); + + (*this)(1,0) = s_q_LF_HAA_; + (*this)(1,1) = c_q_LF_HAA_; + (*this)(2,0) = - c_q_LF_HAA_; + (*this)(2,1) = s_q_LF_HAA_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::Type_fr_LF_THIGH_X_fr_LF_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.08381; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_HIP::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,2) = c_q_LF_HFE_; + (*this)(0,3) = (- 0.0599 * c_q_LF_HFE_); + (*this)(1,0) = c_q_LF_HFE_; + (*this)(1,2) = - s_q_LF_HFE_; + (*this)(1,3) = ( 0.0599 * s_q_LF_HFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::Type_fr_LF_HIP_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0.08381; + (*this)(2,2) = 0; + (*this)(2,3) = 0.0599; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_HIP_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_HFE_; + Scalar c_q_LF_HFE_; + + s_q_LF_HFE_ = TRAIT::sin( q(LF_HFE)); + c_q_LF_HFE_ = TRAIT::cos( q(LF_HFE)); + + (*this)(0,0) = s_q_LF_HFE_; + (*this)(0,1) = c_q_LF_HFE_; + (*this)(2,0) = c_q_LF_HFE_; + (*this)(2,1) = - s_q_LF_HFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::Type_fr_LF_SHANK_X_fr_LF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = - 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_SHANK_X_fr_LF_THIGH::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = s_q_LF_KFE_; + (*this)(0,3) = (- 0.285 * s_q_LF_KFE_); + (*this)(1,0) = - s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + (*this)(1,3) = (- 0.285 * c_q_LF_KFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::Type_fr_LF_THIGH_X_fr_LF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.285; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK& iit::camel::tpl::HomogeneousTransforms::Type_fr_LF_THIGH_X_fr_LF_SHANK::update(const JState& q) { + Scalar s_q_LF_KFE_; + Scalar c_q_LF_KFE_; + + s_q_LF_KFE_ = TRAIT::sin( q(LF_KFE)); + c_q_LF_KFE_ = TRAIT::cos( q(LF_KFE)); + + (*this)(0,0) = c_q_LF_KFE_; + (*this)(0,1) = - s_q_LF_KFE_; + (*this)(1,0) = s_q_LF_KFE_; + (*this)(1,1) = c_q_LF_KFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_base::Type_fr_RF_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.2999; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(0,1) = s_q_RF_HAA_; + (*this)(0,2) = - c_q_RF_HAA_; + (*this)(0,3) = ( 0.104 * s_q_RF_HAA_); + (*this)(1,1) = c_q_RF_HAA_; + (*this)(1,2) = s_q_RF_HAA_; + (*this)(1,3) = ( 0.104 * c_q_RF_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HIP::Type_fr_base_X_fr_RF_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = 0.2999; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.104; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HAA_; + Scalar c_q_RF_HAA_; + + s_q_RF_HAA_ = TRAIT::sin( q(RF_HAA)); + c_q_RF_HAA_ = TRAIT::cos( q(RF_HAA)); + + (*this)(1,0) = s_q_RF_HAA_; + (*this)(1,1) = c_q_RF_HAA_; + (*this)(2,0) = - c_q_RF_HAA_; + (*this)(2,1) = s_q_RF_HAA_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::Type_fr_RF_THIGH_X_fr_RF_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.08381; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_HIP::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,2) = c_q_RF_HFE_; + (*this)(0,3) = (- 0.0599 * c_q_RF_HFE_); + (*this)(1,0) = c_q_RF_HFE_; + (*this)(1,2) = - s_q_RF_HFE_; + (*this)(1,3) = ( 0.0599 * s_q_RF_HFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::Type_fr_RF_HIP_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = - 0.08381; + (*this)(2,2) = 0; + (*this)(2,3) = 0.0599; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_HIP_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_HFE_; + Scalar c_q_RF_HFE_; + + s_q_RF_HFE_ = TRAIT::sin( q(RF_HFE)); + c_q_RF_HFE_ = TRAIT::cos( q(RF_HFE)); + + (*this)(0,0) = s_q_RF_HFE_; + (*this)(0,1) = c_q_RF_HFE_; + (*this)(2,0) = c_q_RF_HFE_; + (*this)(2,1) = - s_q_RF_HFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::Type_fr_RF_SHANK_X_fr_RF_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_SHANK_X_fr_RF_THIGH::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = s_q_RF_KFE_; + (*this)(0,3) = (- 0.285 * s_q_RF_KFE_); + (*this)(1,0) = - s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + (*this)(1,3) = (- 0.285 * c_q_RF_KFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::Type_fr_RF_THIGH_X_fr_RF_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.285; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = - 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK& iit::camel::tpl::HomogeneousTransforms::Type_fr_RF_THIGH_X_fr_RF_SHANK::update(const JState& q) { + Scalar s_q_RF_KFE_; + Scalar c_q_RF_KFE_; + + s_q_RF_KFE_ = TRAIT::sin( q(RF_KFE)); + c_q_RF_KFE_ = TRAIT::cos( q(RF_KFE)); + + (*this)(0,0) = c_q_RF_KFE_; + (*this)(0,1) = - s_q_RF_KFE_; + (*this)(1,0) = s_q_RF_KFE_; + (*this)(1,1) = c_q_RF_KFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_base::Type_fr_LH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.2999; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(0,1) = s_q_LH_HAA_; + (*this)(0,2) = - c_q_LH_HAA_; + (*this)(0,3) = (- 0.104 * s_q_LH_HAA_); + (*this)(1,1) = c_q_LH_HAA_; + (*this)(1,2) = s_q_LH_HAA_; + (*this)(1,3) = (- 0.104 * c_q_LH_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HIP::Type_fr_base_X_fr_LH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.2999; + (*this)(1,2) = 0; + (*this)(1,3) = 0.104; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HAA_; + Scalar c_q_LH_HAA_; + + s_q_LH_HAA_ = TRAIT::sin( q(LH_HAA)); + c_q_LH_HAA_ = TRAIT::cos( q(LH_HAA)); + + (*this)(1,0) = s_q_LH_HAA_; + (*this)(1,1) = c_q_LH_HAA_; + (*this)(2,0) = - c_q_LH_HAA_; + (*this)(2,1) = s_q_LH_HAA_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::Type_fr_LH_THIGH_X_fr_LH_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.08381; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_HIP::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,2) = c_q_LH_HFE_; + (*this)(0,3) = ( 0.0599 * c_q_LH_HFE_); + (*this)(1,0) = c_q_LH_HFE_; + (*this)(1,2) = - s_q_LH_HFE_; + (*this)(1,3) = (- 0.0599 * s_q_LH_HFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::Type_fr_LH_HIP_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = 0.08381; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.0599; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_HIP_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_HFE_; + Scalar c_q_LH_HFE_; + + s_q_LH_HFE_ = TRAIT::sin( q(LH_HFE)); + c_q_LH_HFE_ = TRAIT::cos( q(LH_HFE)); + + (*this)(0,0) = s_q_LH_HFE_; + (*this)(0,1) = c_q_LH_HFE_; + (*this)(2,0) = c_q_LH_HFE_; + (*this)(2,1) = - s_q_LH_HFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::Type_fr_LH_SHANK_X_fr_LH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = - 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_SHANK_X_fr_LH_THIGH::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = s_q_LH_KFE_; + (*this)(0,3) = (- 0.285 * s_q_LH_KFE_); + (*this)(1,0) = - s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + (*this)(1,3) = (- 0.285 * c_q_LH_KFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::Type_fr_LH_THIGH_X_fr_LH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.285; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK& iit::camel::tpl::HomogeneousTransforms::Type_fr_LH_THIGH_X_fr_LH_SHANK::update(const JState& q) { + Scalar s_q_LH_KFE_; + Scalar c_q_LH_KFE_; + + s_q_LH_KFE_ = TRAIT::sin( q(LH_KFE)); + c_q_LH_KFE_ = TRAIT::cos( q(LH_KFE)); + + (*this)(0,0) = c_q_LH_KFE_; + (*this)(0,1) = - s_q_LH_KFE_; + (*this)(1,0) = s_q_LH_KFE_; + (*this)(1,1) = c_q_LH_KFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_base::Type_fr_RH_HIP_X_fr_base() +{ + (*this)(0,0) = 0; + (*this)(1,0) = 0; + (*this)(2,0) = 1.0; + (*this)(2,1) = 0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.2999; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_base& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_base::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(0,1) = s_q_RH_HAA_; + (*this)(0,2) = - c_q_RH_HAA_; + (*this)(0,3) = ( 0.104 * s_q_RH_HAA_); + (*this)(1,1) = c_q_RH_HAA_; + (*this)(1,2) = s_q_RH_HAA_; + (*this)(1,3) = ( 0.104 * c_q_RH_HAA_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HIP::Type_fr_base_X_fr_RH_HIP() +{ + (*this)(0,0) = 0; + (*this)(0,1) = 0; + (*this)(0,2) = 1.0; + (*this)(0,3) = - 0.2999; + (*this)(1,2) = 0; + (*this)(1,3) = - 0.104; + (*this)(2,2) = 0; + (*this)(2,3) = 0; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_base_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HAA_; + Scalar c_q_RH_HAA_; + + s_q_RH_HAA_ = TRAIT::sin( q(RH_HAA)); + c_q_RH_HAA_ = TRAIT::cos( q(RH_HAA)); + + (*this)(1,0) = s_q_RH_HAA_; + (*this)(1,1) = c_q_RH_HAA_; + (*this)(2,0) = - c_q_RH_HAA_; + (*this)(2,1) = s_q_RH_HAA_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::Type_fr_RH_THIGH_X_fr_RH_HIP() +{ + (*this)(0,1) = 0; + (*this)(1,1) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 1.0; + (*this)(2,2) = 0; + (*this)(2,3) = 0.08381; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_HIP::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,2) = c_q_RH_HFE_; + (*this)(0,3) = ( 0.0599 * c_q_RH_HFE_); + (*this)(1,0) = c_q_RH_HFE_; + (*this)(1,2) = - s_q_RH_HFE_; + (*this)(1,3) = (- 0.0599 * s_q_RH_HFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::Type_fr_RH_HIP_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,0) = 0; + (*this)(1,1) = 0; + (*this)(1,2) = 1.0; + (*this)(1,3) = - 0.08381; + (*this)(2,2) = 0; + (*this)(2,3) = - 0.0599; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_HIP_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_HFE_; + Scalar c_q_RH_HFE_; + + s_q_RH_HFE_ = TRAIT::sin( q(RH_HFE)); + c_q_RH_HFE_ = TRAIT::cos( q(RH_HFE)); + + (*this)(0,0) = s_q_RH_HFE_; + (*this)(0,1) = c_q_RH_HFE_; + (*this)(2,0) = c_q_RH_HFE_; + (*this)(2,1) = - s_q_RH_HFE_; + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::Type_fr_RH_SHANK_X_fr_RH_THIGH() +{ + (*this)(0,2) = 0; + (*this)(1,2) = 0; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_SHANK_X_fr_RH_THIGH::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = s_q_RH_KFE_; + (*this)(0,3) = (- 0.285 * s_q_RH_KFE_); + (*this)(1,0) = - s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + (*this)(1,3) = (- 0.285 * c_q_RH_KFE_); + return *this; +} +template +iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::Type_fr_RH_THIGH_X_fr_RH_SHANK() +{ + (*this)(0,2) = 0; + (*this)(0,3) = 0; + (*this)(1,2) = 0; + (*this)(1,3) = 0.285; + (*this)(2,0) = 0; + (*this)(2,1) = 0; + (*this)(2,2) = 1.0; + (*this)(2,3) = - 0.1003; + (*this)(3,0) = 0; + (*this)(3,1) = 0; + (*this)(3,2) = 0; + (*this)(3,3) = 1.0; +} +template +const typename iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK& iit::camel::tpl::HomogeneousTransforms::Type_fr_RH_THIGH_X_fr_RH_SHANK::update(const JState& q) { + Scalar s_q_RH_KFE_; + Scalar c_q_RH_KFE_; + + s_q_RH_KFE_ = TRAIT::sin( q(RH_KFE)); + c_q_RH_KFE_ = TRAIT::cos( q(RH_KFE)); + + (*this)(0,0) = c_q_RH_KFE_; + (*this)(0,1) = - s_q_RH_KFE_; + (*this)(1,0) = s_q_RH_KFE_; + (*this)(1,1) = c_q_RH_KFE_; + return *this; +} + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/anymal_camel_rsl.urdf b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/anymal_camel_rsl.urdf new file mode 100644 index 000000000..a93219f1b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/anymal_camel_rsl.urdf @@ -0,0 +1,1669 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1000000.0 + 100.0 + 0.8 + 0.8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1000000.0 + 100.0 + 0.8 + 0.8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1000000.0 + 100.0 + 0.8 + 0.8 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1000000.0 + 100.0 + 0.8 + 0.8 + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/frame_declaration_anymal_c.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/frame_declaration_anymal_c.info new file mode 100644 index 000000000..73d1222e5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_models/urdf/frame_declaration_anymal_c.info @@ -0,0 +1,64 @@ +root base + +left_front { + root LF_HAA + tip LF_FOOT + joints { + [0] LF_HAA + [1] LF_HFE + [2] LF_KFE + } +} + +right_front { + root RF_HAA + tip RF_FOOT + joints { + [0] RF_HAA + [1] RF_HFE + [2] RF_KFE + } +} + +left_hind { + root LH_HAA + tip LH_FOOT + joints { + [0] LH_HAA + [1] LH_HFE + [2] LH_KFE + } +} + +right_hind { + root RH_HAA + tip RH_FOOT + joints { + [0] RH_HAA + [1] RH_HFE + [2] RH_KFE + } +} + +collisions { + collisionSpheres { + [0] "LF_KFE, 0.08" + [1] "RF_KFE, 0.08" + [2] "LH_KFE, 0.08" + [3] "RH_KFE, 0.08" + } + collisionOffsets { + (0,0) -0.055 + (0,1) 0.0 + (0,2) 0.0 + (1,0) -0.055 + (1,1) 0.0 + (1,2) 0.0 + (2,0) -0.055 + (2,1) 0.0 + (2,2) 0.0 + (3,0) -0.055 + (3,1) 0.0 + (3,2) 0.0 + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/CMakeLists.txt new file mode 100644 index 000000000..c60700daa --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/CMakeLists.txt @@ -0,0 +1,132 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_anymal_mpc) + +find_package(catkin REQUIRED COMPONENTS + roslib + ocs2_anymal_models + ocs2_quadruped_interface +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +find_package(Boost REQUIRED COMPONENTS + filesystem +) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ocs2_anymal_models + ocs2_quadruped_interface + DEPENDS + Boost +) + +########### +## Build ## +########### + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +# Declare a C++ library +add_library(${PROJECT_NAME} + src/AnymalInterface.cpp +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +add_executable(${PROJECT_NAME}_mpc_node + src/AnymalMpcNode.cpp +) +add_dependencies(${PROJECT_NAME}_mpc_node + ${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME}_mpc_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +add_executable(${PROJECT_NAME}_dummy_mrt_node + src/AnymalDummyMRT.cpp +) +add_dependencies(${PROJECT_NAME}_dummy_mrt_node + ${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME}_dummy_mrt_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if (cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_mpc_node ${PROJECT_NAME}_dummy_mrt_node + SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include + CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include + CF_WERROR + ) +endif (cmake_clang_tools_FOUND) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(TARGETS ${PROJECT_NAME}_mpc_node ${PROJECT_NAME}_dummy_mrt_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(DIRECTORY config launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +catkin_add_nosetests(test) + +# Build unit tests +catkin_add_gtest(${PROJECT_NAME}_test + test/testProblemFormulation.cpp +) +target_link_libraries(${PROJECT_NAME}_test + ${PROJECT_NAME} + ${catkin_LIBRARIES} + gtest_main +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/frame_declaration.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/frame_declaration.info new file mode 100644 index 000000000..73d1222e5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/frame_declaration.info @@ -0,0 +1,64 @@ +root base + +left_front { + root LF_HAA + tip LF_FOOT + joints { + [0] LF_HAA + [1] LF_HFE + [2] LF_KFE + } +} + +right_front { + root RF_HAA + tip RF_FOOT + joints { + [0] RF_HAA + [1] RF_HFE + [2] RF_KFE + } +} + +left_hind { + root LH_HAA + tip LH_FOOT + joints { + [0] LH_HAA + [1] LH_HFE + [2] LH_KFE + } +} + +right_hind { + root RH_HAA + tip RH_FOOT + joints { + [0] RH_HAA + [1] RH_HFE + [2] RH_KFE + } +} + +collisions { + collisionSpheres { + [0] "LF_KFE, 0.08" + [1] "RF_KFE, 0.08" + [2] "LH_KFE, 0.08" + [3] "RH_KFE, 0.08" + } + collisionOffsets { + (0,0) -0.055 + (0,1) 0.0 + (0,2) 0.0 + (1,0) -0.055 + (1,1) 0.0 + (1,2) 0.0 + (2,0) -0.055 + (2,1) 0.0 + (2,2) 0.0 + (3,0) -0.055 + (3,1) 0.0 + (3,2) 0.0 + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/multiple_shooting.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/multiple_shooting.info new file mode 100644 index 000000000..2cefdf558 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/multiple_shooting.info @@ -0,0 +1,18 @@ +multiple_shooting +{ + dt 0.015 + sqpIteration 1 + deltaTol 1e-4 + g_max 1e-2 + g_min 1e-6 + inequalityConstraintMu 0.1 + inequalityConstraintDelta 5.0 + projectStateInputEqualityConstraints true + printSolverStatistics true + printSolverStatus false + printLinesearch false + useFeedbackPolicy true + integratorType RK2 + nThreads 4 + threadPriority 50 +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/targetCommand.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/targetCommand.info new file mode 100644 index 000000000..9fc51c8a7 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/targetCommand.info @@ -0,0 +1,20 @@ +targetDisplacementVelocity 0.5; +targetRotationVelocity 0.3; + +comHeight 0.57; + +defaultJointState +{ + (0,0) -0.25; LF_HAA + (1,0) 0.60; LF_HFE + (2,0) -0.85; LF_KFE + (3,0) 0.25; RF_HAA + (4,0) 0.60; RF_HFE + (5,0) -0.85; RF_KFE + (6,0) -0.25; LH_HAA + (7,0) -0.60; LH_HFE + (8,0) 0.85; LH_KFE + (9,0) 0.25; RH_HAA + (10,0) -0.60; RH_HFE + (11,0) 0.85; RH_KFE +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/task.info b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/task.info new file mode 100644 index 000000000..009f390bf --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/config/c_series/task.info @@ -0,0 +1,272 @@ +model_settings +{ + algorithm SQP + recompileLibraries false + robotName c_series + + analyticalInverseKinematics true + + frictionCoefficient 0.5 + gripperForce 0.0 ; [N] negative gripper force -> minimum force in normal direction + muFrictionCone 0.1 + deltaFrictionCone 5.0 + + muFootPlacement 0.1 ; magnitude scaling + deltaFootPlacement 0.01 ; [m] distance from constraint boundary where the barrier becomes quadratic. + + muSdf 2.5 + deltaSdf 0.005 + + muJointsPosition 0.1 + deltaJointsPosition 0.01 + muJointsVelocity 0.1 + deltaJointsVelocity 0.1 + muJointsTorque 1.0 + deltaJointsTorque 1.0 + + joint_lower_limits + { + (0,0) -0.70 ; LF_HAA + (1,0) -1e30 ; LF_HFE + (2,0) -2.70 ; LF_KFE + (3,0) -1e30 ; RF_HAA + (4,0) -1e30 ; RF_HFE + (5,0) -2.70 ; RF_KFE + (6,0) -0.70 ; LH_HAA + (7,0) -1e30 ; LH_HFE + (8,0) 0.00 ; LH_KFE + (9,0) -1e30 ; RH_HAA + (10,0) -1e30 ; RH_HFE + (11,0) 0.00 ; RH_KFE + } + + joint_upper_limits + { + (0,0) 1e30 ; LF_HAA + (1,0) 1e30 ; LF_HFE + (2,0) -0.00 ; LF_KFE + (3,0) 0.70 ; RF_HAA + (4,0) 1e30 ; RF_HFE + (5,0) -0.00 ; RF_KFE + (6,0) 1e30 ; LH_HAA + (7,0) 1e30 ; LH_HFE + (8,0) 2.70 ; LH_KFE + (9,0) 0.70 ; RH_HAA + (10,0) 1e30 ; RH_HFE + (11,0) 2.70 ; RH_KFE + } + + joint_velocity_limits + { + (0,0) 7.0 ; LF_HAA + (1,0) 7.0 ; LF_HFE + (2,0) 7.0 ; LF_KFE + (3,0) 7.0 ; RF_HAA + (4,0) 7.0 ; RF_HFE + (5,0) 7.0 ; RF_KFE + (6,0) 7.0 ; LH_HAA + (7,0) 7.0 ; LH_HFE + (8,0) 7.0 ; LH_KFE + (9,0) 7.0 ; RH_HAA + (10,0) 7.0 ; RH_HFE + (11,0) 7.0 ; RH_KFE + } + + joint_torque_limits + { + (0,0) 80.0 ; LF_HAA + (1,0) 80.0 ; LF_HFE + (2,0) 80.0 ; LF_KFE + (3,0) 80.0 ; RF_HAA + (4,0) 80.0 ; RF_HFE + (5,0) 80.0 ; RF_KFE + (6,0) 80.0 ; LH_HAA + (7,0) 80.0 ; LH_HFE + (8,0) 80.0 ; LH_KFE + (9,0) 80.0 ; RH_HAA + (10,0) 80.0 ; RH_HFE + (11,0) 80.0 ; RH_KFE + } + + swing_trajectory_settings + { + liftOffVelocity 0.2 + touchDownVelocity -0.4 + swingHeight 0.08 + touchdownAfterHorizon 0.2 + errorGain 20.0 + swingTimeScale 0.15 + sdfMidswingMargin 0.04 + terrainMargin 0.0 + previousFootholdFactor 0.333 + previousFootholdDeadzone 0.05 + previousFootholdTimeDeadzone 0.25 + } +} + +terrainPlane +{ + position + { + x 0.0; + y 0.0; + z 0.0; + } + orientation + { + roll 0.0; + pitch 0.0; + yaw 0.0; + } +} + +defaultModeSequenceTemplate +{ + modeSequence + { + [0] STANCE + } + switchingTimes + { + [0] 0.0 + [1] 1.0 + } +} + +; DDP settings +ddp +{ + algorithm SLQ + + nThreads 4 + threadPriority 50 + + maxNumIterations 1 + minRelCost 1e-1 + constraintTolerance 5e-3 + + displayInfo false + displayShortSummary false + checkNumericalStability false + debugPrintRollout false + debugCaching false + + AbsTolODE 1e-5 + RelTolODE 1e-3 + maxNumStepsPerSecond 10000 + timeStep 0.015 + backwardPassIntegratorType ODE45 + + constraintPenaltyInitialValue 20.0 + constraintPenaltyIncreaseRate 2.0 + + preComputeRiccatiTerms true + + useFeedbackPolicy true + + strategy LINE_SEARCH + lineSearch + { + minStepLength 1e-4 + maxStepLength 1.0 + hessianCorrectionStrategy DIAGONAL_SHIFT + hessianCorrectionMultiple 1e-5 + } +} + +; Rollout settings +rollout +{ + AbsTolODE 1e-5 + RelTolODE 1e-3 + timeStep 0.015 + integratorType ODE45 + maxNumStepsPerSecond 10000 + checkNumericalStability false +} + +mpc +{ + timeHorizon 1.0 + solutionTimeWindow -1 ; [s] + coldStart false + + debugPrint false + + mpcDesiredFrequency 20 ; [Hz] + mrtDesiredFrequency 400 ; [Hz] +} + +; initial state +initialRobotState +{ + ; orientation + (0,0) 0.0 ; x + (1,0) 0.0 ; y + (2,0) 0.0 ; z + + ; position + (3,0) 0.0 ; x + (4,0) 0.0 ; y + (5,0) 0.57 ; z + + ; angular velocity + (6,0) 0.0 ; x + (7,0) 0.0 ; y + (8,0) 0.0 ; z + + ; translational velocity + (9,0) 0.0 ; x + (10,0) 0.0 ; y + (11,0) 0.0 ; z + + ; joint state + (12,0) -0.25 ; LF_HAA + (13,0) 0.60 ; LF_HFE + (14,0) -0.85 ; LF_KFE + (15,0) 0.25 ; RF_HAA + (16,0) 0.60 ; RF_HFE + (17,0) -0.85 ; RF_KFE + (18,0) -0.25 ; LH_HAA + (19,0) -0.60 ; LH_HFE + (20,0) 0.85 ; LH_KFE + (21,0) 0.25 ; RH_HAA + (22,0) -0.60 ; RH_HFE + (23,0) 0.85 ; RH_KFE +} + +tracking_cost_weights +{ + ; Base + roll 100.0; + pitch 300.0; + yaw 300.0; + base_position_x 1000.0; + base_position_y 1000.0; + base_position_z 1500.0; + base_angular_vel_x 10.0; + base_angular_vel_y 30.0; + base_angular_vel_z 30.0; + base_linear_vel_x 15.0; + base_linear_vel_y 15.0; + base_linear_vel_z 30.0; + + ; Per leg + joint_position_HAA 2.0; + joint_position_HFE 2.0; + joint_position_KFE 1.0; + foot_position_x 60.0; + foot_position_y 60.0; + foot_position_z 60.0; + joint_velocity_HAA 0.02; + joint_velocity_HFE 0.02; + joint_velocity_KFE 0.01; + foot_velocity_x 10.0; + foot_velocity_y 10.0; + foot_velocity_z 10.0; + contact_force_x 0.001; + contact_force_y 0.001; + contact_force_z 0.001; +} + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/include/ocs2_anymal_mpc/AnymalInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/include/ocs2_anymal_mpc/AnymalInterface.h new file mode 100644 index 000000000..1e4f5c9b1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/include/ocs2_anymal_mpc/AnymalInterface.h @@ -0,0 +1,24 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +#include + +#include +#include + +namespace anymal { + +std::unique_ptr getAnymalInterface(const std::string& urdf, const std::string& taskFolder); + +std::unique_ptr getAnymalInterface(const std::string& urdf, + switched_model::QuadrupedInterface::Settings settings, + const FrameDeclaration& frameDeclaration); + +std::string getConfigFolder(const std::string& configName); + +std::string getTaskFilePath(const std::string& configName); + +} // end of namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/camel.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/camel.launch new file mode 100644 index 000000000..35b4c93b6 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/camel.launch @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/mpc.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/mpc.launch new file mode 100644 index 000000000..0db853937 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/launch/mpc.launch @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/package.xml new file mode 100644 index 000000000..f52ef3d87 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/package.xml @@ -0,0 +1,19 @@ + + + ocs2_anymal_mpc + 0.0.0 + The ocs2_anymal_mpc package + + farbod + + TODO + + catkin + + roslib + ocs2_anymal_models + ocs2_quadruped_interface + + ocs2_anymal_commands + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalDummyMRT.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalDummyMRT.cpp new file mode 100644 index 000000000..7a0554f83 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalDummyMRT.cpp @@ -0,0 +1,36 @@ +/* + * DummyMRT.cpp + * + * Created on: Apr 10, 2018 + * Author: farbod + */ + +#include +#include + +#include +#include "ocs2_anymal_mpc/AnymalInterface.h" + +int main(int argc, char* argv[]) { + std::vector programArgs{}; + ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() < 3) { + throw std::runtime_error("No robot name and config folder specified. Aborting."); + } + const std::string descriptionName(programArgs[1]); + const std::string configName(programArgs[2]); + + // Initialize ros node + ros::init(argc, argv, "anymal_mrt"); + ros::NodeHandle nodeHandle; + + std::string urdfString; + nodeHandle.getParam(descriptionName, urdfString); + + auto anymalInterface = anymal::getAnymalInterface(urdfString, anymal::getConfigFolder(configName)); + const auto mpcSettings = ocs2::mpc::loadSettings(anymal::getTaskFilePath(configName)); + quadrupedDummyNode(nodeHandle, *anymalInterface, &anymalInterface->getRollout(), mpcSettings.mrtDesiredFrequency_, + mpcSettings.mpcDesiredFrequency_); + + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalInterface.cpp new file mode 100644 index 000000000..872999cec --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalInterface.cpp @@ -0,0 +1,46 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_anymal_mpc/AnymalInterface.h" + +#include + +#include + +namespace anymal { + +std::unique_ptr getAnymalInterface(const std::string& urdf, const std::string& taskFolder) { + std::cerr << "Loading task file from: " << taskFolder << std::endl; + + return getAnymalInterface(urdf, switched_model::loadQuadrupedSettings(taskFolder + "/task.info"), + frameDeclarationFromFile(taskFolder + "/frame_declaration.info")); +} + +std::unique_ptr getAnymalInterface(const std::string& urdf, + switched_model::QuadrupedInterface::Settings settings, + const FrameDeclaration& frameDeclaration) { + std::unique_ptr invKin{nullptr}; + if (settings.modelSettings_.analyticalInverseKinematics_) { + invKin = getAnymalInverseKinematics(frameDeclaration, urdf); + } + auto kin = getAnymalKinematics(frameDeclaration, urdf); + auto kinAd = getAnymalKinematicsAd(frameDeclaration, urdf); + auto com = getAnymalComModel(frameDeclaration, urdf); + auto comAd = getAnymalComModelAd(frameDeclaration, urdf); + auto jointNames = getJointNames(frameDeclaration); + auto baseName = frameDeclaration.root; + + return std::unique_ptr(new switched_model::QuadrupedPointfootInterface( + *kin, *kinAd, *com, *comAd, invKin.get(), std::move(settings), std::move(jointNames), std::move(baseName))); +} + +std::string getConfigFolder(const std::string& configName) { + return ros::package::getPath("ocs2_anymal_mpc") + "/config/" + configName; +} + +std::string getTaskFilePath(const std::string& configName) { + return getConfigFolder(configName) + "/task.info"; +} + +} // namespace anymal diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalMpcNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalMpcNode.cpp new file mode 100644 index 000000000..e57519b1a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/src/AnymalMpcNode.cpp @@ -0,0 +1,52 @@ +/* + * AnymalMPC.cpp + * + * Created on: Apr 15, 2018 + * Author: farbod + */ + +#include +#include + +#include +#include +#include + +#include "ocs2_anymal_mpc/AnymalInterface.h" + +int main(int argc, char* argv[]) { + std::vector programArgs{}; + ros::removeROSArgs(argc, argv, programArgs); + if (programArgs.size() < 3) { + throw std::runtime_error("No robot name and config folder specified. Aborting."); + } + const std::string descriptionName(programArgs[1]); + const std::string configName(programArgs[2]); + + // Initialize ros node + ros::init(argc, argv, "anymal_mpc"); + ros::NodeHandle nodeHandle; + + std::string urdfString; + nodeHandle.getParam(descriptionName, urdfString); + + auto anymalInterface = anymal::getAnymalInterface(urdfString, anymal::getConfigFolder(configName)); + const auto mpcSettings = ocs2::mpc::loadSettings(anymal::getTaskFilePath(configName)); + + switch (anymalInterface->modelSettings().algorithm_) { + case switched_model::Algorithm::DDP: { + const auto ddpSettings = ocs2::ddp::loadSettings(anymal::getTaskFilePath(configName)); + auto mpcPtr = getDdpMpc(*anymalInterface, mpcSettings, ddpSettings); + quadrupedMpcNode(nodeHandle, *anymalInterface, std::move(mpcPtr)); + break; + } + case switched_model::Algorithm::SQP: { + const auto sqpSettings = ocs2::sqp::loadSettings(anymal::getConfigFolder(configName) + "/multiple_shooting.info"); + auto mpcPtr = getSqpMpc(*anymalInterface, mpcSettings, sqpSettings); + quadrupedMpcNode(nodeHandle, *anymalInterface, std::move(mpcPtr)); + break; + } + } + + return 0; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/test/testProblemFormulation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/test/testProblemFormulation.cpp new file mode 100644 index 000000000..c95dd0072 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_anymal_mpc/test/testProblemFormulation.cpp @@ -0,0 +1,158 @@ +// +// Created by rgrandia on 15.03.21. +// + +#include + +#include + +#include +#include + +class TestAnymalModel : public ::testing::Test { + public: + TestAnymalModel() { + const std::string configName("c_series"); + const std::string path(__FILE__); + const std::string dir = path.substr(0, path.find_last_of("/")); + const std::string configFolder = dir + "/../config/" + configName; + + // Get interface + anymalInterface = anymal::getAnymalInterface(anymal::getUrdfString(anymal::AnymalModel::Camel), configFolder); + + problem = anymalInterface->getOptimalControlProblem(); + + // Cost desired + ocs2::scalar_t initTime = 0.0; + ocs2::scalar_t finalTime = 1.0; + const ocs2::vector_t state = anymalInterface->getInitialState(); + const ocs2::vector_t input = ocs2::vector_t::Zero(switched_model::INPUT_DIM); + targetTrajectories = ocs2::TargetTrajectories{{initTime}, {state}, {input}}; + problem.targetTrajectoriesPtr = &targetTrajectories; + + // Initialize + anymalInterface->getReferenceManagerPtr()->preSolverRun(initTime, finalTime, state); + } + + std::unique_ptr anymalInterface; + ocs2::OptimalControlProblem problem; + ocs2::TargetTrajectories targetTrajectories; +}; + +TEST_F(TestAnymalModel, all) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.dynamicsPtr->linearApproximation(t, x, u); + } + timer.endTimer(); + std::cout << "Dynamics " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.equalityConstraintPtr->getLinearApproximation(t, x, u, *problem.preComputationPtr); + } + timer.endTimer(); + std::cout << "Constraints state-input " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + ocs2::approximateCost(problem, t, x, u); + } + timer.endTimer(); + std::cout << "Cost " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalModel, dynamics) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.dynamicsPtr->linearApproximation(t, x, u); + } + timer.endTimer(); + std::cout << "Dynamics " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalModel, precomputation) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.preComputationPtr->request(request, t, x, u); + } + timer.endTimer(); + std::cout << "Precomputation " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalModel, constraints_eq) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 1000000; + + constexpr auto request = ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + problem.equalityConstraintPtr->getLinearApproximation(t, x, u, *problem.preComputationPtr); + } + timer.endTimer(); + std::cout << "Constraints state-input " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalModel, cost) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Constraint + ocs2::Request::Approximation; + problem.preComputationPtr->request(request, t, x, u); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + ocs2::approximateCost(problem, t, x, u); + } + timer.endTimer(); + std::cout << "Cost " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} + +TEST_F(TestAnymalModel, terminalCost) { + ocs2::scalar_t t = 0.0; + const ocs2::vector_t x = anymalInterface->getInitialState(); + const ocs2::vector_t u = ocs2::vector_t::Zero(24); + ocs2::benchmark::RepeatedTimer timer; + int N = 100000; + + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Approximation; + problem.preComputationPtr->requestFinal(request, t, x); + + timer.startTimer(); + for (int i = 0; i < N; i++) { + ocs2::approximateFinalCost(problem, t, x); + } + timer.endTimer(); + std::cout << "Cost " << timer.getLastIntervalInMilliseconds() / N << " ms per call\n"; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/CMakeLists.txt new file mode 100644 index 000000000..359aaef44 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/CMakeLists.txt @@ -0,0 +1,102 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_quadruped_interface) + +## Catkin Dependencies +set(CATKIN_PACKAGE_DEPENDENCIES + ocs2_core + ocs2_ddp + ocs2_mpc + ocs2_sqp + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_interface + ocs2_anymal_commands + roscpp + tf + kdl_parser + robot_state_publisher + segmented_planes_terrain_model +) +find_package(catkin REQUIRED COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ${CATKIN_PACKAGE_DEPENDENCIES} + DEPENDS +) + +########### +## Build ## +########### + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +# Declare a C++ library +add_library(${PROJECT_NAME} + src/QuadrupedDummyNode.cpp + src/QuadrupedInterface.cpp + src/QuadrupedLogger.cpp + src/QuadrupedMpc.cpp + src/QuadrupedMpcNode.cpp + src/QuadrupedPointfootInterface.cpp + src/QuadrupedTfPublisher.cpp + src/QuadrupedVisualizer.cpp + src/SwingPlanningVisualizer.cpp + src/TerrainPlaneVisualizer.cpp + src/TerrainReceiver.cpp +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if(cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} + SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include + CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include + CF_WERROR + ) +endif(cmake_clang_tools_FOUND) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/config/config.rviz b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/config/config.rviz new file mode 100644 index 000000000..cb2b630b9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/config/config.rviz @@ -0,0 +1,1004 @@ +Panels: + - Class: rviz/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /Grid1/Offset1 + - /Desired Trajectory1/Feet Position Trajectories1 + - /Optimized Trajectory1/Feet Pose Trajectories1 + Splitter Ratio: 0.472075879573822 + Tree Height: 1682 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + - /CoGTrajectory1 + - /video_top1 + - /video_side1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 0.10000000149011612 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: world + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + LF_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + LF_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LF_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + LH_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LH_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link Tree Style: Links in Alphabetic Order + RF_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + RF_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RF_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_FOOT: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HAA: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_HIP: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_KFE: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_SHANK: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_THIGH: + Alpha: 1 + Show Axes: false + Show Trail: false + RH_hip_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_shank_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RH_thigh_fixed: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_inertia: + Alpha: 1 + Show Axes: false + Show Trail: false + battery: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bottom_shell: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_front_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_front_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_front_color_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_front_color_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_front_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_left_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_left_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_left_color_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_left_color_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_left_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_rear_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_rear_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_rear_color_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_rear_color_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_rear_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_right_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + depth_camera_right_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_right_color_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_right_color_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + depth_camera_right_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + docking_hatch_cover: + Alpha: 1 + Show Axes: false + Show Trail: false + face_front: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + face_rear: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + handle: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hatch: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lidar: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + lidar_cage: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + remote: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + top_shell: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_front_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_front_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + wide_angle_camera_rear_camera: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wide_angle_camera_rear_camera_parent: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: "ANYmal " + Robot Description: /ocs2_anymal_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Group + Displays: + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredBaseTrajectory + Name: Base Position Trajectory + Namespaces: + "": true + Queue Size: 1 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredVelTrajectory + Name: Base Velocity Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredAngVelTrajectory + Name: Base Angular Velocity Trajectory + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose Trajectory + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/desiredPoseTrajectory + Unreliable: false + Value: true + - Class: rviz/Group + Displays: + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/LF + Name: LF + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/RF + Name: RF + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/LH + Name: LH + Namespaces: + {} + Queue Size: 1 + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /ocs2_anymal/desiredFeetTrajectory/RH + Name: RH + Namespaces: + {} + Queue Size: 1 + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: ref footholds LF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/swing_planner/nominalFootholds_LF + Unreliable: false + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/swing_planner/trajectory_LF + Name: ref trajectory LF + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: false + Name: Feet Position Trajectories + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/LF + Name: LF + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/RF + Name: RF + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/LH + Name: LH + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/desiredFeetVelTrajectory/RH + Name: RH + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: false + Name: Feet Velocity Trajectories + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/LF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/LH + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/RF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/desiredFeetPoseTrajectory/RH + Unreliable: false + Value: true + Enabled: false + Name: Feet Pose Trajectories + Enabled: true + Name: Desired Trajectory + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose Trajectory + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/optimizedPoseTrajectory + Unreliable: false + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /ocs2_anymal/optimizedStateTrajectory + Name: State Trajectory + Namespaces: + Base Trajectory: true + EE Trajectories: true + Future footholds: true + Queue Size: 1 + Value: true + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/LF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: LH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/LH + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RF + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/RF + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.05000000074505806 + Axes Radius: 0.004999999888241291 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: RH + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/optimizedFeetPoseTrajectory/RH + Unreliable: false + Value: true + Enabled: false + Name: Feet Pose Trajectories + Enabled: true + Name: Optimized Trajectory + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.10000000149011612 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: CoM Pose + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: ocs2_anymal/currentPose + Unreliable: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /ocs2_anymal/currentState + Name: State + Namespaces: + Center of Pressure: true + EE Forces: true + EE Positions: true + Support Polygon: true + Queue Size: 1 + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.10000000149011612 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Feet Poses + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /ocs2_anymal/currentFeetPoses + Unreliable: false + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /ocs2_anymal/localTerrain + Name: LocalTerrain + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /ocs2_anymal/currentCollisionSpheres + Name: Collisions + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Name: Current + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Signed distance + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /convex_plane_decomposition_ros/signed_distance_field + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Class: grid_map_rviz_plugin/GridMap + Color: 200; 200; 200 + Color Layer: elevation + Color Transformer: GridMapLayer + ColorMap: default + Enabled: true + Grid Cell Decimation: 1 + Grid Line Thickness: 0.10000000149011612 + Height Layer: elevation + Height Transformer: GridMapLayer + History Length: 1 + Invert ColorMap: false + Max Color: 255; 255; 255 + Max Intensity: 10 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: GridMap + Show Grid Lines: true + Topic: /elevation_mapping/elevation_map_raw + Unreliable: false + Use ColorMap: true + Value: true + Enabled: true + Name: Terrain + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 2.5349531173706055 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0.8147555589675903 + Y: 0.34456419944763184 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3252030909061432 + Target Frame: + Yaw: 0.857906699180603 + Saved: + - Angle: 3.140000104904175 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: CoGTrajectory + Near Clip Distance: 0.009999999776482582 + Scale: 582.8400268554688 + Target Frame: + X: 0.16045600175857544 + Y: 0.09311659634113312 + - Angle: 6.260000228881836 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: video_top + Near Clip Distance: 0.009999999776482582 + Scale: 266.7760009765625 + Target Frame: + X: 2.279409885406494 + Y: -0.7245129942893982 + - Class: rviz/Orbit + Distance: 3.5650899410247803 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 4.226150035858154 + Y: -1.1256200075149536 + Z: 0.17035800218582153 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: video_side + Near Clip Distance: 0.009999999776482582 + Pitch: 0.434798002243042 + Target Frame: + Yaw: 5.150000095367432 + - Class: rviz/Orbit + Distance: 1.7256799936294556 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 0.09568200260400772 + Y: -0.16040100157260895 + Z: -0.31398600339889526 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: fixed_to_hyq + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3497979938983917 + Target Frame: base_link + Yaw: 5.114999771118164 +Window Geometry: + Displays: + collapsed: false + Height: 2086 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000003b70000078afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000b0fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e0000078a0000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012f00000432fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000043000004320000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003bf0000003efc0100000002fb0000000800540069006d00650000000000000003bf000008d800fffffffb0000000800540069006d0065010000000000000450000000000000000000000aad0000078a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 3696 + X: 3984 + Y: 0 diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedDummyNode.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedDummyNode.h new file mode 100644 index 000000000..f00d5f6a5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedDummyNode.h @@ -0,0 +1,15 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +#include + +#include "QuadrupedInterface.h" + +namespace switched_model { + +void quadrupedDummyNode(ros::NodeHandle& nodeHandle, const QuadrupedInterface& quadrupedInterface, const ocs2::RolloutBase* rolloutPtr, + double mrtDesiredFrequency, double mpcDesiredFrequency); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedInterface.h new file mode 100644 index 000000000..c6fb20371 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedInterface.h @@ -0,0 +1,155 @@ +/* + * QuadrupedInterface.h + * + * Created on: Feb 14, 2018 + * Author: farbod + */ + +#pragma once + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace switched_model { + +class QuadrupedInterface : public ocs2::RobotInterface { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + using com_model_t = ComModelBase; + using kinematic_model_t = KinematicsModelBase; + + using ad_com_model_t = ComModelBase; + using ad_kinematic_model_t = KinematicsModelBase; + + using synchronized_module_t = ocs2::SolverSynchronizedModule; + using synchronized_module_ptr_array_t = std::vector>; + + struct Settings { + ocs2::rollout::Settings rolloutSettings_; + ModelSettings modelSettings_; + MotionTrackingCost::Weights trackingWeights_; + SwingTrajectoryPlannerSettings swingTrajectoryPlannerSettings_; + TerrainPlane terrainPlane_; + state_vector_t initialState_; + Gait defaultGait_; + }; + + /** + * Constructor + * @param kinematicModel : Kinematics model + * @param adKinematicModel : Kinematics model templated on the auto-differentiation scalar + * @param comModel : Center of mass model + * @param adComModel : Center of mass model templated on the auto-differentiation scalar + * @param settings : settings + * @param jointNames : names of the joints in the order of the state vector + * @param baseName : names of the model root frame + */ + QuadrupedInterface(const kinematic_model_t& kinematicModel, const ad_kinematic_model_t& adKinematicModel, const com_model_t& comModel, + const ad_com_model_t& adComModel, const InverseKinematicsModelBase* inverseKinematics, Settings settings, + std::vector jointNames, std::string baseName); + + /** Destructor */ + ~QuadrupedInterface() override = default; + + /** Gets the switched-model mode schedule manager */ + std::shared_ptr getSwitchedModelModeScheduleManagerPtr() const { return modeScheduleManagerPtr_; } + + /** Gets the mode schedule manager */ + std::shared_ptr getReferenceManagerPtr() const override { return modeScheduleManagerPtr_; } + + /** Gets the dynamics parameter module*/ + std::shared_ptr getDynamicsParametersSynchronizedModulePtr() const { + return dynamicsParametersSynchronizedModulePtr_; + } + + const ocs2::OptimalControlProblem& getOptimalControlProblem() const override { return *problemPtr_; } + + /** Gets inverse kinematic model */ + const InverseKinematicsModelBase* getInverseKinematicModelPtr() const { return inverseKinematicModelPtr_.get(); } + + /** Gets kinematic model */ + const kinematic_model_t& getKinematicModel() const { return *kinematicModelPtr_; } + const ad_kinematic_model_t& getKinematicModelAd() const { return *adKinematicModelPtr_; } + + /** Gets center of mass model */ + const com_model_t& getComModel() const { return *comModelPtr_; } + const ad_com_model_t& getComModelAd() const { return *adComModelPtr_; } + + /** Gets the loaded initial state */ + state_vector_t& getInitialState() { return settings_.initialState_; } + const state_vector_t& getInitialState() const { return settings_.initialState_; } + + /** Access to rollout settings */ + const ocs2::rollout::Settings& rolloutSettings() const { return settings_.rolloutSettings_; } + + /** Access to model settings */ + const ModelSettings& modelSettings() const { return settings_.modelSettings_; }; + + /** Access to model names */ + const std::vector& getJointNames() const { return jointNames_; }; + const std::string& getBaseName() const { return baseName_; }; + + /** Access to cost settings */ + const MotionTrackingCost::Weights& costSettings() const { return settings_.trackingWeights_; }; + + /** Gets the rollout class */ + virtual const ocs2::RolloutBase& getRollout() const = 0; + + /** Gets the solver synchronized modules */ + const synchronized_module_ptr_array_t& getSynchronizedModules() const { return solverModules_; }; + + /** Append solver sync module to solverModules_*/ + void appendToSynchronizedModules(std::shared_ptr synchronizedModule) { + solverModules_.push_back(std::move(synchronizedModule)); + }; + + /** Cost approximation at the nominal state and input*/ + virtual const ScalarFunctionQuadraticApproximation& nominalCostApproximation() const = 0; + + protected: + std::unique_ptr problemPtr_; + + std::unique_ptr createPrecomputation() const; + std::unique_ptr createMotionTrackingCost() const; + std::unique_ptr createMotionTrackingTerminalCost(matrix_t Q) const; + std::unique_ptr createFootPlacementCost() const; + std::unique_ptr createCollisionAvoidanceCost() const; + std::unique_ptr createJointLimitsSoftConstraint() const; + std::unique_ptr createTorqueLimitsSoftConstraint(const joint_coordinate_t& nominalTorques) const; + std::unique_ptr createDynamics() const; + std::unique_ptr createZeroForceConstraint(size_t leg) const; + std::unique_ptr createFootNormalConstraint(size_t leg) const; + std::unique_ptr createEndEffectorVelocityConstraint(size_t leg) const; + std::unique_ptr createFrictionConeCost() const; + + private: + Settings settings_; + std::vector jointNames_; + std::string baseName_; + std::unique_ptr inverseKinematicModelPtr_; + std::unique_ptr kinematicModelPtr_; + std::unique_ptr adKinematicModelPtr_; + std::unique_ptr comModelPtr_; + std::unique_ptr adComModelPtr_; + synchronized_module_ptr_array_t solverModules_; + std::shared_ptr modeScheduleManagerPtr_; + std::shared_ptr dynamicsParametersSynchronizedModulePtr_; +}; + +/** Load the general quadruped settings from file. */ +QuadrupedInterface::Settings loadQuadrupedSettings(const std::string& pathToConfigFile); + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedLogger.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedLogger.h new file mode 100644 index 000000000..43389792c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedLogger.h @@ -0,0 +1,68 @@ +// +// Created by rgrandia on 05.11.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/ComModelBase.h" +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Simple logger for Quadruped observations. + * Logs a sequence of quadruped observations to a file. Has the option to log additional user-defined data. + * + * Can be either used stand-alone or as a dummy observer + */ +class QuadrupedLogger : public ocs2::DummyObserver { + public: + using com_model_t = ComModelBase; + using kinematic_model_t = KinematicsModelBase; + + QuadrupedLogger(std::string logFileName, const kinematic_model_t& kinematicModel, const com_model_t& comModel, + std::vector additionalColumns = {}); + + /** + * The destructor writes the buffered log data to file. + */ + ~QuadrupedLogger() override; + + /** + * Dummy observer interface. Forwards to the addline method + */ + void update(const ocs2::SystemObservation& observation, const ocs2::PrimalSolution& primalSolution, + const ocs2::CommandData& command) override { + addLine(observation); + } + + /** + * Adds a line to the log. If the observation time is already present in the log, the new line is dropped to avoid duplicates. + * The user data should match the amount of additional columns declared in the constructor. + */ + void addLine(const ocs2::SystemObservation& observation, const vector_t& additionalColumns = vector_t()); + + /** + * Generates names for {LF, RF, LH, RH} for the give pre and post fixes. + * @return {_LF_, ... , _LF_, _RF_, ... } + */ + static std::vector namesPerLeg(const std::string& prefix, const std::vector& postfixes); + + private: + std::string getLogHeader() const; + int getNumColumns() const; + + std::string logFileName_; + std::vector additionalColumns_; + + std::vector buffer_; + + std::unique_ptr kinematicModel_; + std::unique_ptr comModel_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpc.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpc.h new file mode 100644 index 000000000..bd315285f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpc.h @@ -0,0 +1,24 @@ +// +// Created by rgrandia on 06.07.21. +// + +#pragma once + +#include +#include +#include +#include + +#include "ocs2_quadruped_interface/QuadrupedInterface.h" + +namespace switched_model { + +/** Constructs an DDP MPC object */ +std::unique_ptr getDdpMpc(const QuadrupedInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::ddp::Settings& ddpSettings); + +/** Constructs an SQP MPC object */ +std::unique_ptr getSqpMpc(const QuadrupedInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::sqp::Settings& sqpSettings); + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpcNode.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpcNode.h new file mode 100644 index 000000000..19475a982 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedMpcNode.h @@ -0,0 +1,16 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +#include + +#include + +#include "QuadrupedInterface.h" + +namespace switched_model { + +void quadrupedMpcNode(ros::NodeHandle& nodeHandle, const QuadrupedInterface& quadrupedInterface, std::unique_ptr mpcPtr); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedPointfootInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedPointfootInterface.h new file mode 100644 index 000000000..274c0fbfc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedPointfootInterface.h @@ -0,0 +1,40 @@ +// +// Created by rgrandia on 19.03.20. +// + +#pragma once + +#include + +#include + +#include "ocs2_quadruped_interface/QuadrupedInterface.h" + +namespace switched_model { + +class QuadrupedPointfootInterface : public QuadrupedInterface { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + using QuadrupedInterface::synchronized_module_ptr_array_t; + + QuadrupedPointfootInterface(const kinematic_model_t& kinematicModel, const ad_kinematic_model_t& adKinematicModel, + const com_model_t& comModel, const ad_com_model_t& adComModel, + const InverseKinematicsModelBase* inverseKinematics, Settings settings, std::vector jointNames, + std::string baseName); + + ~QuadrupedPointfootInterface() override = default; + + const ocs2::TimeTriggeredRollout& getRollout() const override { return *timeTriggeredRolloutPtr_; }; + + const ComKinoInitializer& getInitializer() const override { return *initializerPtr_; } + + const ScalarFunctionQuadraticApproximation& nominalCostApproximation() const override { return nominalCostApproximation_; } + + private: + std::unique_ptr initializerPtr_; + std::unique_ptr timeTriggeredRolloutPtr_; + ScalarFunctionQuadraticApproximation nominalCostApproximation_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedTfPublisher.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedTfPublisher.h new file mode 100644 index 000000000..fab684845 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedTfPublisher.h @@ -0,0 +1,44 @@ +// +// Created by rgrandia on 10.03.22. +// + +#pragma once + +#include +#include +#include + +#include + +namespace switched_model { + +class QuadrupedTfPublisher { + public: + QuadrupedTfPublisher() = default; + + void launchNode(ros::NodeHandle& nodeHandle, const std::string& descriptionName, std::vector jointNames, + std::string baseName, const std::string& tfPrefix = ""); + + void publish(ros::Time timeStamp, const vector_t& state, const std::string& worldFrame); + + void publish(ros::Time timeStamp, const base_coordinate_t& basePose, const joint_coordinate_t& jointPositions, + const std::string& worldFrame); + + private: + void updateJointPositions(const joint_coordinate_t& jointPositions); + void updateBasePose(ros::Time timeStamp, const base_coordinate_t& basePose, const std::string& worldFrame); + + // Publishers + tf::TransformBroadcaster tfBroadcaster_; + std::unique_ptr robotStatePublisherPtr_; + + // Messages + std::string tfPrefix_ = ""; + std::string baseName_; + std::vector jointNames_; + std::map jointPositionsMap_; + geometry_msgs::TransformStamped baseToWorldTransform_; + ros::Time lastTimeStamp_ = ros::Time::now(); +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedVisualizer.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedVisualizer.h new file mode 100644 index 000000000..5a533279d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/QuadrupedVisualizer.h @@ -0,0 +1,100 @@ +// +// Created by rgrandia on 13.02.19. +// + +#pragma once + +#include +#include +#include + +#include +#include + +#include +#include + +#include "ocs2_quadruped_interface/QuadrupedTfPublisher.h" + +namespace switched_model { + +class QuadrupedVisualizer : public ocs2::DummyObserver { + public: + using kinematic_model_t = KinematicsModelBase; + + /** Visualization settings (publicly available) */ + std::string frameId_ = "world"; // Frame name all messages are published in + scalar_t footMarkerDiameter_ = 0.03; // Size of the spheres at the feet + scalar_t footAlphaWhenLifted_ = 0.3; // Alpha value when a foot is lifted. + scalar_t forceScale_ = 1000.0; // Vector scale in N/m + scalar_t velScale_ = 20.0; // Vector scale in m/s + scalar_t copMarkerDiameter_ = 0.03; // Size of the sphere at the center of pressure + scalar_t supportPolygonLineWidth_ = 0.005; // LineThickness for the support polygon + scalar_t trajectoryLineWidth_ = 0.01; // LineThickness for trajectories + feet_array_t feetColorMap_ = {ocs2::Color::blue, ocs2::Color::orange, ocs2::Color::yellow, + ocs2::Color::purple}; // Colors for markers per feet + + /** + * + * @param kinematicModel + * @param comModel + * @param n + * @param maxUpdateFrequency : maximum publish frequency measured in MPC time. + */ + QuadrupedVisualizer(const kinematic_model_t& kinematicModel, std::vector jointNames, std::string baseName, + ros::NodeHandle& n, scalar_t maxUpdateFrequency = 1000.0) + : kinematicModelPtr_(kinematicModel.clone()), + lastTime_(std::numeric_limits::lowest()), + minPublishTimeDifference_(1.0 / maxUpdateFrequency) { + launchVisualizerNode(n, std::move(jointNames), std::move(baseName)); + }; + + ~QuadrupedVisualizer() override = default; + + void update(const ocs2::SystemObservation& observation, const ocs2::PrimalSolution& primalSolution, + const ocs2::CommandData& command) override; + + void launchVisualizerNode(ros::NodeHandle& nodeHandle, std::vector jointNames, std::string baseName); + + void publishTrajectory(const std::vector& system_observation_array, scalar_t speed = 1.0); + + void publishObservation(ros::Time timeStamp, const ocs2::SystemObservation& observation); + + void publishDesiredTrajectory(ros::Time timeStamp, const ocs2::TargetTrajectories& targetTrajectories) const; + + void publishOptimizedStateTrajectory(ros::Time timeStamp, const scalar_array_t& mpcTimeTrajectory, + const vector_array_t& mpcStateTrajectory, const ocs2::ModeSchedule& modeSchedule) const; + + private: + void publishCartesianMarkers(ros::Time timeStamp, const contact_flag_t& contactFlags, const feet_array_t& feetPosition, + const feet_array_t& feetForce) const; + void publishEndEffectorPoses(ros::Time timeStamp, const feet_array_t& feetPositions, + const feet_array_t>& feetOrientations) const; + void publishCollisionSpheres(ros::Time timeStamp, const base_coordinate_t& basePose, const joint_coordinate_t& jointAngles) const; + + std::unique_ptr kinematicModelPtr_; + + QuadrupedTfPublisher quadrupedTfPublisher_; + + // Cost desired publisher. + ros::Publisher costDesiredBasePositionPublisher_; + ros::Publisher costDesiredBasePosePublisher_; + ros::Publisher costDesiredBaseVelocityPublisher_; + ros::Publisher costDesiredBaseAngVelocityPublisher_; + feet_array_t costDesiredFeetPositionPublishers_; + feet_array_t costDesiredFeetVelocityPublishers_; + + // State optimized publisher. + ros::Publisher stateOptimizedPublisher_; + ros::Publisher stateOptimizedPosePublisher_; + + // Current state publisher.. + ros::Publisher currentStatePublisher_; + ros::Publisher currentFeetPosesPublisher_; + ros::Publisher currentCollisionSpheresPublisher_; + + scalar_t lastTime_; + scalar_t minPublishTimeDifference_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/SwingPlanningVisualizer.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/SwingPlanningVisualizer.h new file mode 100644 index 000000000..c53234bc4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/SwingPlanningVisualizer.h @@ -0,0 +1,38 @@ +// +// Created by rgrandia on 30.04.20. +// + +#pragma once + +#include +#include + +#include +#include + +#include "ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h" + +namespace switched_model { + +class SwingPlanningVisualizer : public ocs2::SolverSynchronizedModule { + public: + /** Visualization settings (publicly available) */ + std::string frameId_ = "world"; // Frame name all messages are published in + double arrowScale = 0.05; // Size of the arrow representing the velocity vector + switched_model::feet_array_t feetColorMap_ = {ocs2::Color::blue, ocs2::Color::orange, ocs2::Color::yellow, + ocs2::Color::purple}; // Colors for markers per feet + + SwingPlanningVisualizer(const SwingTrajectoryPlanner& swingTrajectoryPlanner, ros::NodeHandle& nodeHandle); + + void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) override; + + void postSolverRun(const ocs2::PrimalSolution& primalSolution) override{}; + + private: + const SwingTrajectoryPlanner* swingTrajectoryPlannerPtr_; + feet_array_t nominalFootholdPublishers_; + feet_array_t swingTrajectoryPublishers_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainPlaneVisualizer.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainPlaneVisualizer.h new file mode 100644 index 000000000..3fe30f930 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainPlaneVisualizer.h @@ -0,0 +1,51 @@ +// +// Created by rgrandia on 30.04.20. +// + +#pragma once + +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace switched_model { + +class TerrainPlaneVisualizer { + public: + /** Visualization settings (publicly available) */ + std::string frameId_ = "world"; // Frame name all messages are published in + double planeWidth_ = 1.5; + double planeLength_ = 1.5; + double planeThickness_ = 0.005; + double planeAlpha_ = 0.5; + + explicit TerrainPlaneVisualizer(ros::NodeHandle& nodeHandle); + + void update(scalar_t time, const TerrainPlane& terrainPlane); + + private: + ros::Publisher terrainPublisher_; +}; + +class TerrainPlaneVisualizerSynchronizedModule : public ocs2::SolverSynchronizedModule { + public: + TerrainPlaneVisualizerSynchronizedModule(const SwingTrajectoryPlanner& swingTrajectoryPlanner, ros::NodeHandle& nodeHandle); + + void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) override{}; + + void postSolverRun(const ocs2::PrimalSolution& primalSolution) override; + + private: + const SwingTrajectoryPlanner* swingTrajectoryPlanner_; + TerrainPlaneVisualizer planeVisualizer_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainReceiver.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainReceiver.h new file mode 100644 index 000000000..14cca9053 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/include/ocs2_quadruped_interface/TerrainReceiver.h @@ -0,0 +1,34 @@ +// +// Created by rgrandia on 28.09.20. +// + +#pragma once + +#include +#include + +#include +#include + +#include + +#include + +namespace switched_model { + +class TerrainReceiverSynchronizedModule : public ocs2::SolverSynchronizedModule { + public: + TerrainReceiverSynchronizedModule(ocs2::Synchronized& terrainModel, ros::NodeHandle& nodeHandle); + ~TerrainReceiverSynchronizedModule() override = default; + + void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) override; + + void postSolverRun(const ocs2::PrimalSolution& primalSolution) override{}; + + private: + ocs2::Synchronized* terrainModelPtr_; + std::unique_ptr segmentedPlanesRos_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/launch/visualization.launch b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/launch/visualization.launch new file mode 100644 index 000000000..c595de98d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/launch/visualization.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/package.xml new file mode 100644 index 000000000..0bc4d3e6d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/package.xml @@ -0,0 +1,30 @@ + + + ocs2_quadruped_interface + 0.0.0 + The ocs2_quadruped_interface package + + Farbod Farshidian + Jan Carius + Ruben Grandia + + TODO + + catkin + + ocs2_core + ocs2_ddp + ocs2_ocs2 + ocs2_mpc + ocs2_sqp + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_interface + ocs2_anymal_commands + roscpp + tf + kdl_parser + robot_state_publisher + segmented_planes_terrain_model + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedDummyNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedDummyNode.cpp new file mode 100644 index 000000000..5920123a8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedDummyNode.cpp @@ -0,0 +1,54 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_interface/QuadrupedDummyNode.h" + +#include +#include + +#include + +#include +#include + +namespace switched_model { + +void quadrupedDummyNode(ros::NodeHandle& nodeHandle, const QuadrupedInterface& quadrupedInterface, const ocs2::RolloutBase* rolloutPtr, + double mrtDesiredFrequency, double mpcDesiredFrequency) { + const std::string robotName = "anymal"; + + // MRT + ocs2::MRT_ROS_Interface mrt(robotName); + if (rolloutPtr != nullptr) { + mrt.initRollout(rolloutPtr); + } + mrt.launchNodes(nodeHandle); + + // Visualization + auto visualizer = std::make_shared( + quadrupedInterface.getKinematicModel(), quadrupedInterface.getJointNames(), quadrupedInterface.getBaseName(), nodeHandle); + + // Logging + std::string logFileName = "/tmp/ocs2/QuadrupedDummyNodeLog.txt"; + auto logger = std::make_shared(logFileName, quadrupedInterface.getKinematicModel(), + quadrupedInterface.getComModel()); + + // Dummy MRT + ocs2::MRT_ROS_Dummy_Loop dummySimulator(mrt, mrtDesiredFrequency, mpcDesiredFrequency); + dummySimulator.subscribeObservers({visualizer, logger}); + + // initial state + ocs2::SystemObservation initObservation; + initObservation.state = quadrupedInterface.getInitialState(); + initObservation.input = vector_t::Zero(INPUT_DIM); + initObservation.mode = switched_model::ModeNumber::STANCE; + + // initial command + const ocs2::TargetTrajectories initTargetTrajectories({0.0}, {initObservation.state}, {initObservation.input}); + + // run dummy + dummySimulator.run(initObservation, initTargetTrajectories); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedInterface.cpp new file mode 100644 index 000000000..e51c5ccb8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedInterface.cpp @@ -0,0 +1,171 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_interface/QuadrupedInterface.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace switched_model { + +QuadrupedInterface::QuadrupedInterface(const kinematic_model_t& kinematicModel, const ad_kinematic_model_t& adKinematicModel, + const com_model_t& comModel, const ad_com_model_t& adComModel, + const InverseKinematicsModelBase* inverseKinematics, Settings settings, + std::vector jointNames, std::string baseName) + : settings_(std::move(settings)), + jointNames_(std::move(jointNames)), + baseName_(std::move(baseName)), + inverseKinematicModelPtr_(nullptr), + kinematicModelPtr_(kinematicModel.clone()), + adKinematicModelPtr_(adKinematicModel.clone()), + comModelPtr_(comModel.clone()), + adComModelPtr_(adComModel.clone()), + problemPtr_(new ocs2::OptimalControlProblem) { + if (inverseKinematics != nullptr) { + inverseKinematicModelPtr_.reset(inverseKinematics->clone()); + } + + std::unique_ptr gaitSchedule(new GaitSchedule(0.0, settings_.defaultGait_)); + + std::unique_ptr swingTrajectoryPlanner( + new SwingTrajectoryPlanner(settings_.swingTrajectoryPlannerSettings_, getKinematicModel(), getInverseKinematicModelPtr())); + + std::unique_ptr terrainModel(new PlanarTerrainModel(std::move(settings_.terrainPlane_))); + + // Mode schedule manager + modeScheduleManagerPtr_ = std::make_shared(std::move(gaitSchedule), std::move(swingTrajectoryPlanner), + std::move(terrainModel)); + // Dynamics parameter module + dynamicsParametersSynchronizedModulePtr_ = std::make_shared(); + appendToSynchronizedModules(dynamicsParametersSynchronizedModulePtr_); +} + +std::unique_ptr QuadrupedInterface::createPrecomputation() const { + return std::unique_ptr( + new SwitchedModelPreComputation(getSwitchedModelModeScheduleManagerPtr()->getSwingTrajectoryPlanner(), getKinematicModel(), + getKinematicModelAd(), getComModel(), getComModelAd(), modelSettings())); +} + +std::unique_ptr QuadrupedInterface::createMotionTrackingCost() const { + return std::unique_ptr(new MotionTrackingCost(costSettings(), getKinematicModelAd(), modelSettings())); +} + +std::unique_ptr QuadrupedInterface::createMotionTrackingTerminalCost(matrix_t Q) const { + return std::unique_ptr(new MotionTrackingTerminalCost(std::move(Q))); +} + +std::unique_ptr QuadrupedInterface::createFootPlacementCost() const { + return std::unique_ptr( + new FootPlacementCost(ocs2::RelaxedBarrierPenalty::Config(modelSettings().muFootPlacement_, modelSettings().deltaFootPlacement_))); +} + +std::unique_ptr QuadrupedInterface::createCollisionAvoidanceCost() const { + return std::unique_ptr( + new CollisionAvoidanceCost(ocs2::RelaxedBarrierPenalty::Config(modelSettings().muSdf_, modelSettings().deltaSdf_))); +} + +std::unique_ptr QuadrupedInterface::createJointLimitsSoftConstraint() const { + // Joint position constraints + std::vector stateConstraints; + stateConstraints.reserve(JOINT_COORDINATE_SIZE); + for (int j = 0; j < JOINT_COORDINATE_SIZE; ++j) { + ocs2::StateInputSoftBoxConstraint::BoxConstraint jointPositionConstraint; + jointPositionConstraint.index = 2 * BASE_COORDINATE_SIZE + j; + jointPositionConstraint.penaltyPtr.reset( + new ocs2::RelaxedBarrierPenalty({modelSettings().muJointsPosition_, modelSettings().deltaJointsPosition_})); + jointPositionConstraint.lowerBound = modelSettings().lowerJointLimits_[j]; + jointPositionConstraint.upperBound = modelSettings().upperJointLimits_[j]; + stateConstraints.push_back(std::move(jointPositionConstraint)); + } + + // Joint velocity constraints + std::vector inputConstraints; + inputConstraints.reserve(JOINT_COORDINATE_SIZE); + for (int j = 0; j < JOINT_COORDINATE_SIZE; ++j) { + ocs2::StateInputSoftBoxConstraint::BoxConstraint jointVelocityConstraint; + jointVelocityConstraint.index = 3 * NUM_CONTACT_POINTS + j; + jointVelocityConstraint.penaltyPtr.reset( + new ocs2::RelaxedBarrierPenalty({modelSettings().muJointsVelocity_, modelSettings().deltaJointsVelocity_})); + jointVelocityConstraint.lowerBound = -modelSettings().jointVelocityLimits[j]; + jointVelocityConstraint.upperBound = modelSettings().jointVelocityLimits[j]; + inputConstraints.push_back(std::move(jointVelocityConstraint)); + } + + std::unique_ptr jointLimitSoftConstraintPtr( + new ocs2::StateInputSoftBoxConstraint(std::move(stateConstraints), std::move(inputConstraints))); + jointLimitSoftConstraintPtr->initializeOffset(0.0, getInitialState(), input_vector_t::Zero()); + return jointLimitSoftConstraintPtr; +} + +std::unique_ptr QuadrupedInterface::createTorqueLimitsSoftConstraint(const joint_coordinate_t& nominalTorques) const { + return std::unique_ptr(new TorqueLimitsSoftConstraint( + modelSettings().jointTorqueLimits, {modelSettings().muJointsTorque_, modelSettings().deltaJointsTorque_}, nominalTorques)); +} + +std::unique_ptr QuadrupedInterface::createDynamics() const { + return std::unique_ptr( + new ComKinoSystemDynamicsAd(getKinematicModelAd(), getComModelAd(), *getDynamicsParametersSynchronizedModulePtr(), modelSettings())); +} + +std::unique_ptr QuadrupedInterface::createZeroForceConstraint(size_t leg) const { + return std::unique_ptr(new ZeroForceConstraint(leg, *getSwitchedModelModeScheduleManagerPtr())); +} + +std::unique_ptr QuadrupedInterface::createFootNormalConstraint(size_t leg) const { + return std::unique_ptr(new FootNormalConstraint(leg, settings_.swingTrajectoryPlannerSettings_.errorGain)); +} + +std::unique_ptr QuadrupedInterface::createEndEffectorVelocityConstraint(size_t leg) const { + return std::unique_ptr(new EndEffectorVelocityConstraint(leg, *getSwitchedModelModeScheduleManagerPtr())); +} + +std::unique_ptr QuadrupedInterface::createFrictionConeCost() const { + friction_cone::Config frictionConfig(modelSettings().frictionCoefficient_, modelSettings().coneRegularization_, + modelSettings().gripperForce_); + std::unique_ptr penalty( + new ocs2::RelaxedBarrierPenalty({modelSettings().muFrictionCone_, modelSettings().deltaFrictionCone_})); + return std::unique_ptr( + new FrictionConeCost(std::move(frictionConfig), *getSwitchedModelModeScheduleManagerPtr(), std::move(penalty))); +} + +QuadrupedInterface::Settings loadQuadrupedSettings(const std::string& pathToConfigFile) { + QuadrupedInterface::Settings settings; + settings.rolloutSettings_ = ocs2::rollout::loadSettings(pathToConfigFile, "rollout"); + settings.modelSettings_ = loadModelSettings(pathToConfigFile); + settings.trackingWeights_ = loadWeightsFromFile(pathToConfigFile, "tracking_cost_weights"); + + // initial state of the switched system + ocs2::loadData::loadEigenMatrix(pathToConfigFile, "initialRobotState", settings.initialState_); + + // Gait Schedule + const auto defaultModeSequenceTemplate = loadModeSequenceTemplate(pathToConfigFile, "defaultModeSequenceTemplate", false); + settings.defaultGait_ = toGait(defaultModeSequenceTemplate); + + // Swing trajectory planner + settings.swingTrajectoryPlannerSettings_ = loadSwingTrajectorySettings(pathToConfigFile); + + // Terrain + settings.terrainPlane_ = loadTerrainPlane(pathToConfigFile, true); + + return settings; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedLogger.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedLogger.cpp new file mode 100644 index 000000000..ec181f133 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedLogger.cpp @@ -0,0 +1,155 @@ +// +// Created by rgrandia on 05.11.20. +// + +#include "ocs2_quadruped_interface/QuadrupedLogger.h" + +#include + +#include +#include +#include + +namespace switched_model { + +QuadrupedLogger::QuadrupedLogger(std::string logFileName, const kinematic_model_t& kinematicModel, const com_model_t& comModel, + std::vector additionalColumns) + : logFileName_(std::move(logFileName)), + kinematicModel_(kinematicModel.clone()), + comModel_(comModel.clone()), + additionalColumns_(std::move(additionalColumns)) {} + +QuadrupedLogger::~QuadrupedLogger() { + Eigen::IOFormat CommaFmt(Eigen::StreamPrecision, Eigen::DontAlignCols, ", ", ", ", "", "", "", ""); + + if (std::ofstream logfile{logFileName_}) { + logfile << getLogHeader() << std::endl; + for (int i = 1; i < buffer_.size(); ++i) { + logfile << buffer_[i].transpose().format(CommaFmt) << ", \n"; + } + std::cerr << "[QuadrupedLogger] Log written to '" << logFileName_ << "'\n"; + } else { + std::cerr << "[QuadrupedLogger] Unable to open '" << logFileName_ << "'\n"; + } +} + +std::string QuadrupedLogger::getLogHeader() const { + std::string delim = ", "; + std::stringstream header; + // clang-format off + header << + "time" << delim << + "contactflag_LF" << delim << + "contactflag_RF" << delim << + "contactflag_LH" << delim << + "contactflag_RH" << delim << + "base_positionInWorld_x" << delim << + "base_positionInWorld_y" << delim << + "base_positionInWorld_z" << delim << + "base_quaternion_w" << delim << + "base_quaternion_x" << delim << + "base_quaternion_y" << delim << + "base_quaternion_z" << delim << + "base_linearvelocityInBase_x" << delim << + "base_linearvelocityInBase_y" << delim << + "base_linearvelocityInBase_z" << delim << + "base_angularvelocityInBase_x" << delim << + "base_angularvelocityInBase_y" << delim << + "base_angularvelocityInBase_z" << delim; + // clang-format on + for (const auto& name : namesPerLeg("jointAngle", {"HAA", "HFE", "KFE"})) { + header << name << delim; + } + for (const auto& name : namesPerLeg("jointVelocity", {"HAA", "HFE", "KFE"})) { + header << name << delim; + } + for (const auto& name : namesPerLeg("contactForcesInWorld", {"x", "y", "z"})) { + header << name << delim; + } + for (const auto& name : additionalColumns_) { + header << name << delim; + } + return header.str(); +} + +int QuadrupedLogger::getNumColumns() const { + int numColumns = 0; + numColumns += 1; // time + numColumns += NUM_CONTACT_POINTS; // contactFlags + numColumns += BASE_COORDINATE_SIZE + 1; // base pose (with quaternion) + numColumns += BASE_COORDINATE_SIZE; // base twist + numColumns += JOINT_COORDINATE_SIZE; // joint angles + numColumns += JOINT_COORDINATE_SIZE; // joint velocities + numColumns += 3 * NUM_CONTACT_POINTS; // contact forces + numColumns += additionalColumns_.size(); // extra columns + return numColumns; +} + +void QuadrupedLogger::addLine(const ocs2::SystemObservation& observation, const vector_t& additionalColumns) { + if (!buffer_.empty() && observation.time == buffer_.back()[0]) { // time is same as last one + return; + } + comkino_state_t state(observation.state); + comkino_input_t input(observation.input); + + // Extract elements from state + const base_coordinate_t basePose = getBasePose(state); + const auto basePosition = getPositionInOrigin(basePose); + const base_coordinate_t baseLocalVelocities = getBaseLocalVelocities(state); + const auto baseAngularVelocities = getAngularVelocity(baseLocalVelocities); + const auto baseLinearVelocities = getLinearVelocity(baseLocalVelocities); + const joint_coordinate_t qJoints = getJointPositions(state); + const joint_coordinate_t dqJoints = getJointVelocities(input); + const Eigen::Matrix3d o_R_b = rotationMatrixBaseToOrigin(getOrientation(basePose)); + const auto quat = ocs2::matrixToQuaternion(o_R_b); + + // Contact state + const contact_flag_t contactFlags = modeNumber2StanceLeg(observation.mode); + + // Forces + joint_coordinate_t forceInputs = input.head<3 * NUM_CONTACT_POINTS>(); + const auto contactForcesInBase = toArray(forceInputs); + feet_array_t contactForcesInWorld; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + contactForcesInWorld[i] = o_R_b * contactForcesInBase[i]; + } + + // Fill log + vector_t logEntry(getNumColumns()); + // clang-format off + logEntry << + observation.time, + static_cast(contactFlags[0]), + static_cast(contactFlags[1]), + static_cast(contactFlags[2]), + static_cast(contactFlags[3]), + basePosition, + quat.w(), + quat.x(), + quat.y(), + quat.z(), + baseLinearVelocities, + baseAngularVelocities, + qJoints, + dqJoints, + contactForcesInWorld[0], + contactForcesInWorld[1], + contactForcesInWorld[2], + contactForcesInWorld[3], + additionalColumns; + // clang-format on + + buffer_.push_back(std::move(logEntry)); +} + +std::vector QuadrupedLogger::namesPerLeg(const std::string& prefix, const std::vector& postfixes) { + std::vector names; + for (const auto& legName : std::vector{"LF", "RF", "LH", "RH"}) { + for (const auto& postfix : postfixes) { + names.emplace_back(prefix + "_" + legName + "_" + postfix); + } + } + return names; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpc.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpc.cpp new file mode 100644 index 000000000..8b114bbea --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpc.cpp @@ -0,0 +1,31 @@ +// +// Created by rgrandia on 06.07.21. +// + +#include "ocs2_quadruped_interface/QuadrupedMpc.h" + +#include +#include + +namespace switched_model { + +std::unique_ptr getDdpMpc(const QuadrupedInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::ddp::Settings& ddpSettings) { + std::unique_ptr mpcPtr(new ocs2::GaussNewtonDDP_MPC(mpcSettings, ddpSettings, quadrupedInterface.getRollout(), + quadrupedInterface.getOptimalControlProblem(), + quadrupedInterface.getInitializer())); + mpcPtr->getSolverPtr()->setReferenceManager(quadrupedInterface.getReferenceManagerPtr()); + mpcPtr->getSolverPtr()->setSynchronizedModules(quadrupedInterface.getSynchronizedModules()); + return mpcPtr; +} + +std::unique_ptr getSqpMpc(const QuadrupedInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::sqp::Settings& sqpSettings) { + std::unique_ptr mpcPtr( + new ocs2::SqpMpc(mpcSettings, sqpSettings, quadrupedInterface.getOptimalControlProblem(), quadrupedInterface.getInitializer())); + mpcPtr->getSolverPtr()->setReferenceManager(quadrupedInterface.getReferenceManagerPtr()); + mpcPtr->getSolverPtr()->setSynchronizedModules(quadrupedInterface.getSynchronizedModules()); + return mpcPtr; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpcNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpcNode.cpp new file mode 100644 index 000000000..dd922aa85 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedMpcNode.cpp @@ -0,0 +1,56 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_interface/QuadrupedMpcNode.h" + +#include +#include + +#include +#include + +#include +#include +#include + +namespace switched_model { + +void quadrupedMpcNode(ros::NodeHandle& nodeHandle, const QuadrupedInterface& quadrupedInterface, std::unique_ptr mpcPtr) { + const std::string robotName = "anymal"; + + auto solverModules = quadrupedInterface.getSynchronizedModules(); + + // Gait + auto gaitReceiver = + std::make_shared(nodeHandle, quadrupedInterface.getSwitchedModelModeScheduleManagerPtr()->getGaitSchedule(), robotName); + solverModules.push_back(gaitReceiver); + + // Terrain Receiver + auto terrainReceiver = std::make_shared( + quadrupedInterface.getSwitchedModelModeScheduleManagerPtr()->getTerrainModel(), nodeHandle); + solverModules.push_back(terrainReceiver); + + // Terrain plane visualization + auto terrainVisualizer = std::make_shared( + quadrupedInterface.getSwitchedModelModeScheduleManagerPtr()->getSwingTrajectoryPlanner(), nodeHandle); + solverModules.push_back(terrainVisualizer); + + // Swing planner + auto swingPlanningVisualizer = std::make_shared( + quadrupedInterface.getSwitchedModelModeScheduleManagerPtr()->getSwingTrajectoryPlanner(), nodeHandle); + solverModules.push_back(swingPlanningVisualizer); + + // reference manager + auto rosReferenceManagerPtr = std::make_shared(robotName, quadrupedInterface.getReferenceManagerPtr()); + rosReferenceManagerPtr->subscribe(nodeHandle); + mpcPtr->getSolverPtr()->setReferenceManager(rosReferenceManagerPtr); + + // MPC + mpcPtr->getSolverPtr()->setSynchronizedModules(solverModules); + + // launch MPC nodes + ocs2::MPC_ROS_Interface mpcNode(*mpcPtr, robotName); + mpcNode.launchNodes(nodeHandle); +} +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedPointfootInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedPointfootInterface.cpp new file mode 100644 index 000000000..877fadd2f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedPointfootInterface.cpp @@ -0,0 +1,70 @@ +// +// Created by rgrandia on 19.03.20. +// + +#include "ocs2_quadruped_interface/QuadrupedPointfootInterface.h" + +#include +#include +#include + +namespace switched_model { + +QuadrupedPointfootInterface::QuadrupedPointfootInterface(const kinematic_model_t& kinematicModel, + const ad_kinematic_model_t& adKinematicModel, const com_model_t& comModel, + const ad_com_model_t& adComModel, + const InverseKinematicsModelBase* inverseKinematics, Settings settings, + std::vector jointNames, std::string baseName) + : QuadrupedInterface(kinematicModel, adKinematicModel, comModel, adComModel, inverseKinematics, std::move(settings), + std::move(jointNames), std::move(baseName)) { + // nominal values + const auto stanceFlags = switched_model::constantFeetArray(true); + const auto uSystemForWeightCompensation = weightCompensatingInputs(getComModel(), stanceFlags, switched_model::vector3_t::Zero()); + const auto jointTorquesForWeightCompensation = torqueApproximation( + getJointPositions(getInitialState()), toArray(uSystemForWeightCompensation.head<3 * NUM_CONTACT_POINTS>()), kinematicModel); + + problemPtr_->preComputationPtr = createPrecomputation(); + + // Cost terms + problemPtr_->costPtr->add("MotionTrackingCost", createMotionTrackingCost()); + problemPtr_->stateCostPtr->add("FootPlacementCost", createFootPlacementCost()); + problemPtr_->stateCostPtr->add("CollisionAvoidanceCost", createCollisionAvoidanceCost()); + problemPtr_->costPtr->add("JointLimitCost", createJointLimitsSoftConstraint()); + problemPtr_->costPtr->add("TorqueLimitCost", createTorqueLimitsSoftConstraint(jointTorquesForWeightCompensation)); + problemPtr_->costPtr->add("FrictionCones", createFrictionConeCost()); + + // Dynamics + problemPtr_->dynamicsPtr = createDynamics(); + + // Per leg terms + for (int i = 0; i < NUM_CONTACT_POINTS; i++) { + const auto& footName = feetNames[i]; + problemPtr_->equalityConstraintPtr->add(footName + "_ZeroForce", createZeroForceConstraint(i)); + problemPtr_->equalityConstraintPtr->add(footName + "_EENormal", createFootNormalConstraint(i)); + problemPtr_->equalityConstraintPtr->add(footName + "_EEVel", createEndEffectorVelocityConstraint(i)); + } + + // Initialize cost to be able to query it + ocs2::TargetTrajectories targetTrajectories({0.0}, {getInitialState()}, {uSystemForWeightCompensation}); + problemPtr_->targetTrajectoriesPtr = &targetTrajectories; + + getSwitchedModelModeScheduleManagerPtr()->setTargetTrajectories(targetTrajectories); + getSwitchedModelModeScheduleManagerPtr()->preSolverRun(0.0, 1.0, getInitialState()); + auto lqrSolution = ocs2::continuous_time_lqr::solve(*problemPtr_, 0.0, getInitialState(), uSystemForWeightCompensation); + lqrSolution.valueFunction *= 10.0; + problemPtr_->finalCostPtr->add("lqr_terminal_cost", createMotionTrackingTerminalCost(lqrSolution.valueFunction)); + + // Store cost approximation at nominal state input + auto& preComputation = *problemPtr_->preComputationPtr; + constexpr auto request = ocs2::Request::Cost + ocs2::Request::SoftConstraint + ocs2::Request::Approximation; + preComputation.request(request, 0.0, getInitialState(), uSystemForWeightCompensation); + nominalCostApproximation_ = ocs2::approximateCost(*problemPtr_, 0.0, getInitialState(), uSystemForWeightCompensation); + + // Reset, the target trajectories pointed to are local + problemPtr_->targetTrajectoriesPtr = nullptr; + + initializerPtr_.reset(new ComKinoInitializer(getComModel(), *getSwitchedModelModeScheduleManagerPtr())); + timeTriggeredRolloutPtr_.reset(new ocs2::TimeTriggeredRollout(*problemPtr_->dynamicsPtr, rolloutSettings())); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedTfPublisher.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedTfPublisher.cpp new file mode 100644 index 000000000..f3045d7d9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedTfPublisher.cpp @@ -0,0 +1,82 @@ +// +// Created by rgrandia on 10.03.22. +// + +#include "ocs2_quadruped_interface/QuadrupedTfPublisher.h" + +#include + +// Additional messages not in the helpers file +#include + +// URDF stuff +#include +#include + +#include + +namespace switched_model { + +void QuadrupedTfPublisher::launchNode(ros::NodeHandle& nodeHandle, const std::string& descriptionName, std::vector jointNames, + std::string baseName, const std::string& tfPrefix) { + tfPrefix_ = tfPrefix; + jointNames_ = std::move(jointNames); + baseName_ = std::move(baseName); + + // Load URDF model + urdf::Model urdfModel; + if (!urdfModel.initParam(descriptionName)) { + std::cerr << "[QuadrupedTfPublisher] Could not read URDF from: \"" << descriptionName << "\"" << std::endl; + } else { + KDL::Tree kdlTree; + kdl_parser::treeFromUrdfModel(urdfModel, kdlTree); + + robotStatePublisherPtr_.reset(new robot_state_publisher::RobotStatePublisher(kdlTree)); + robotStatePublisherPtr_->publishFixedTransforms(tfPrefix_, true); + } +} + +void QuadrupedTfPublisher::publish(ros::Time timeStamp, const vector_t& state, const std::string& worldFrame) { + publish(timeStamp, getBasePose(state), getJointPositions(state), worldFrame); +} + +void QuadrupedTfPublisher::publish(ros::Time timeStamp, const base_coordinate_t& basePose, const joint_coordinate_t& jointPositions, + const std::string& worldFrame) { + if (robotStatePublisherPtr_ != nullptr && lastTimeStamp_ != timeStamp) { + // Joint positions + updateJointPositions(jointPositions); + robotStatePublisherPtr_->publishTransforms(jointPositionsMap_, timeStamp, tfPrefix_); + + // Base positions + updateBasePose(timeStamp, basePose, worldFrame); + tfBroadcaster_.sendTransform(baseToWorldTransform_); + + lastTimeStamp_ = timeStamp; + } +} + +void QuadrupedTfPublisher::updateJointPositions(const joint_coordinate_t& jointPositions) { + jointPositionsMap_[jointNames_[0]] = jointPositions[0]; + jointPositionsMap_[jointNames_[1]] = jointPositions[1]; + jointPositionsMap_[jointNames_[2]] = jointPositions[2]; + jointPositionsMap_[jointNames_[3]] = jointPositions[3]; + jointPositionsMap_[jointNames_[4]] = jointPositions[4]; + jointPositionsMap_[jointNames_[5]] = jointPositions[5]; + jointPositionsMap_[jointNames_[6]] = jointPositions[6]; + jointPositionsMap_[jointNames_[7]] = jointPositions[7]; + jointPositionsMap_[jointNames_[8]] = jointPositions[8]; + jointPositionsMap_[jointNames_[9]] = jointPositions[9]; + jointPositionsMap_[jointNames_[10]] = jointPositions[10]; + jointPositionsMap_[jointNames_[11]] = jointPositions[11]; +} + +void QuadrupedTfPublisher::updateBasePose(ros::Time timeStamp, const base_coordinate_t& basePose, const std::string& worldFrame) { + baseToWorldTransform_.header = ocs2::getHeaderMsg(worldFrame, timeStamp); + baseToWorldTransform_.child_frame_id = tfPrefix_ + "/" + baseName_; + + const Eigen::Quaternion q_world_base = quaternionBaseToOrigin(getOrientation(basePose)); + baseToWorldTransform_.transform.rotation = ocs2::getOrientationMsg(q_world_base); + baseToWorldTransform_.transform.translation = ocs2::getVectorMsg(getPositionInOrigin(basePose)); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedVisualizer.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedVisualizer.cpp new file mode 100644 index 000000000..3b3ec1da1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/QuadrupedVisualizer.cpp @@ -0,0 +1,356 @@ +// +// Created by rgrandia on 13.02.19. +// + +#include "ocs2_quadruped_interface/QuadrupedVisualizer.h" + +#include + +#include + +// Additional messages not in the helpers file +#include +#include + +// URDF stuff +#include +#include + +// Switched model conversions +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/core/Rotations.h" + +namespace switched_model { + +void QuadrupedVisualizer::launchVisualizerNode(ros::NodeHandle& nodeHandle, std::vector jointNames, std::string baseName) { + costDesiredBasePositionPublisher_ = nodeHandle.advertise("/ocs2_anymal/desiredBaseTrajectory", 1); + costDesiredBasePosePublisher_ = nodeHandle.advertise("/ocs2_anymal/desiredPoseTrajectory", 1); + costDesiredBaseAngVelocityPublisher_ = nodeHandle.advertise("/ocs2_anymal/desiredAngVelTrajectory", 1); + costDesiredBaseVelocityPublisher_ = nodeHandle.advertise("/ocs2_anymal/desiredVelTrajectory", 1); + costDesiredFeetPositionPublishers_[0] = nodeHandle.advertise("/ocs2_anymal/desiredFeetTrajectory/LF", 1); + costDesiredFeetPositionPublishers_[1] = nodeHandle.advertise("/ocs2_anymal/desiredFeetTrajectory/RF", 1); + costDesiredFeetPositionPublishers_[2] = nodeHandle.advertise("/ocs2_anymal/desiredFeetTrajectory/LH", 1); + costDesiredFeetPositionPublishers_[3] = nodeHandle.advertise("/ocs2_anymal/desiredFeetTrajectory/RH", 1); + costDesiredFeetVelocityPublishers_[0] = + nodeHandle.advertise("/ocs2_anymal/desiredFeetVelTrajectory/LF", 1); + costDesiredFeetVelocityPublishers_[1] = + nodeHandle.advertise("/ocs2_anymal/desiredFeetVelTrajectory/RF", 1); + costDesiredFeetVelocityPublishers_[2] = + nodeHandle.advertise("/ocs2_anymal/desiredFeetVelTrajectory/LH", 1); + costDesiredFeetVelocityPublishers_[3] = + nodeHandle.advertise("/ocs2_anymal/desiredFeetVelTrajectory/RH", 1); + stateOptimizedPublisher_ = nodeHandle.advertise("/ocs2_anymal/optimizedStateTrajectory", 1); + stateOptimizedPosePublisher_ = nodeHandle.advertise("/ocs2_anymal/optimizedPoseTrajectory", 1); + currentStatePublisher_ = nodeHandle.advertise("/ocs2_anymal/currentState", 1); + currentFeetPosesPublisher_ = nodeHandle.advertise("/ocs2_anymal/currentFeetPoses", 1); + currentCollisionSpheresPublisher_ = nodeHandle.advertise("/ocs2_anymal/currentCollisionSpheres", 1); + + quadrupedTfPublisher_.launchNode(nodeHandle, "ocs2_anymal_description", std::move(jointNames), std::move(baseName)); +} + +void QuadrupedVisualizer::update(const ocs2::SystemObservation& observation, const ocs2::PrimalSolution& primalSolution, + const ocs2::CommandData& command) { + if (observation.time - lastTime_ > minPublishTimeDifference_) { + const auto timeStamp = ros::Time::now(); + publishObservation(timeStamp, observation); + publishDesiredTrajectory(timeStamp, command.mpcTargetTrajectories_); + publishOptimizedStateTrajectory(timeStamp, primalSolution.timeTrajectory_, primalSolution.stateTrajectory_, + primalSolution.modeSchedule_); + lastTime_ = observation.time; + } +} + +void QuadrupedVisualizer::publishObservation(ros::Time timeStamp, const ocs2::SystemObservation& observation) { + // Extract components from state + const state_vector_t switchedState = observation.state.head(STATE_DIM); + const base_coordinate_t basePose = getBasePose(switchedState); + const auto o_basePosition = getPositionInOrigin(basePose); + const Eigen::Matrix3d o_R_b = rotationMatrixBaseToOrigin(getOrientation(basePose)); + const joint_coordinate_t qJoints = getJointPositions(state_vector_t(observation.state)); + + // Compute cartesian state and inputs + feet_array_t feetPosition; + feet_array_t feetForce; + feet_array_t> feetOrientations; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + feetPosition[i] = o_basePosition; + feetPosition[i].noalias() += o_R_b * kinematicModelPtr_->positionBaseToFootInBaseFrame(i, qJoints); + + feetForce[i] = o_R_b * observation.input.segment<3>(3 * i); + + const matrix3_t footOrientationInOriginFrame = o_R_b * kinematicModelPtr_->footOrientationInBaseFrame(i, qJoints); + feetOrientations[i] = Eigen::Quaternion(footOrientationInOriginFrame); + } + + // Publish + quadrupedTfPublisher_.publish(timeStamp, basePose, qJoints, frameId_); + publishCartesianMarkers(timeStamp, modeNumber2StanceLeg(observation.mode), feetPosition, feetForce); + publishEndEffectorPoses(timeStamp, feetPosition, feetOrientations); + publishCollisionSpheres(timeStamp, basePose, qJoints); +} + +void QuadrupedVisualizer::publishTrajectory(const std::vector& system_observation_array, double speed) { + for (size_t k = 0; k < system_observation_array.size() - 1; k++) { + double frameDuration = speed * (system_observation_array[k + 1].time - system_observation_array[k].time); + double publishDuration = ocs2::timedExecutionInSeconds([&]() { publishObservation(ros::Time::now(), system_observation_array[k]); }); + if (frameDuration > publishDuration) { + ros::WallDuration(frameDuration - publishDuration).sleep(); + } + } +} + +void QuadrupedVisualizer::publishCartesianMarkers(ros::Time timeStamp, const contact_flag_t& contactFlags, + const feet_array_t& feetPosition, + const feet_array_t& feetForce) const { + // Reserve message + const int numberOfCartesianMarkers = 10; + visualization_msgs::MarkerArray markerArray; + markerArray.markers.reserve(numberOfCartesianMarkers); + + // Feet positions and Forces + for (int i = 0; i < NUM_CONTACT_POINTS; ++i) { + markerArray.markers.emplace_back( + getFootMarker(feetPosition[i], contactFlags[i], feetColorMap_[i], footMarkerDiameter_, footAlphaWhenLifted_)); + markerArray.markers.emplace_back(getForceMarker(feetForce[i], feetPosition[i], contactFlags[i], ocs2::Color::green, forceScale_)); + } + + // Center of pressure + markerArray.markers.emplace_back(getCenterOfPressureMarker(feetForce.begin(), feetForce.end(), feetPosition.begin(), contactFlags.begin(), + ocs2::Color::green, copMarkerDiameter_)); + + // Support polygon + markerArray.markers.emplace_back(getSupportPolygonMarker(feetPosition.begin(), feetPosition.end(), contactFlags.begin(), + ocs2::Color::black, supportPolygonLineWidth_)); + + // Give markers an id and a frame + ocs2::assignHeader(markerArray.markers.begin(), markerArray.markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(markerArray.markers.begin(), markerArray.markers.end()); + + // Publish cartesian markers (minus the CoM Pose) + currentStatePublisher_.publish(markerArray); +} + +void QuadrupedVisualizer::publishDesiredTrajectory(ros::Time timeStamp, const ocs2::TargetTrajectories& targetTrajectories) const { + const auto& stateTrajectory = targetTrajectories.stateTrajectory; + const auto& inputTrajectory = targetTrajectories.inputTrajectory; + const size_t stateTrajSize = stateTrajectory.size(); + const size_t inputTrajSize = inputTrajectory.size(); + + // Reserve Base messages + std::vector desiredBasePositionMsg; + desiredBasePositionMsg.reserve(stateTrajSize); + geometry_msgs::PoseArray poseArray; + poseArray.poses.reserve(stateTrajSize); + visualization_msgs::MarkerArray velArray; + velArray.markers.reserve(stateTrajSize); + visualization_msgs::MarkerArray angVelArray; + angVelArray.markers.reserve(stateTrajSize); + + // Reserve feet messages + feet_array_t> desiredFeetPositionMsgs; + feet_array_t feetVelArray; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + desiredFeetPositionMsgs[i].reserve(stateTrajSize); + feetVelArray[i].markers.reserve(stateTrajSize); + } + + for (size_t k = 0; k < stateTrajSize; ++k) { + const state_vector_t state = stateTrajectory[k]; + input_vector_t input; + if (k < inputTrajSize) { + input = inputTrajectory[k]; + } else { + input.setZero(); + } + + // Extract elements from state + const base_coordinate_t basePose = state.head<6>(); + const base_coordinate_t baseTwist = state.segment<6>(6); + const auto o_basePosition = getPositionInOrigin(basePose); + const auto eulerXYZ = getOrientation(basePose); + const Eigen::Matrix3d o_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + const auto qJoints = getJointPositions(state); + const auto qVelJoints = getJointVelocities(input); + + // Construct pose msg + geometry_msgs::Pose pose; + pose.position = ocs2::getPointMsg(o_basePosition); + pose.orientation = ocs2::getOrientationMsg(quaternionBaseToOrigin(eulerXYZ)); + + // Construct vel msg + const vector3_t o_baseVel = o_R_b * getLinearVelocity(baseTwist); + const vector3_t o_baseAngVel = o_R_b * getAngularVelocity(baseTwist); + + // Fill message containers + desiredBasePositionMsg.push_back(pose.position); + poseArray.poses.push_back(std::move(pose)); + velArray.markers.emplace_back(getArrowAtPointMsg(o_baseVel / velScale_, o_basePosition, ocs2::Color::blue)); + angVelArray.markers.emplace_back(getArrowAtPointMsg(o_baseAngVel / velScale_, o_basePosition, ocs2::Color::green)); + + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + const vector3_t b_baseToFoot = kinematicModelPtr_->positionBaseToFootInBaseFrame(i, qJoints); + auto o_footPosition = o_basePosition; + o_footPosition.noalias() += o_R_b * b_baseToFoot; + const vector3_t b_footVelocity = kinematicModelPtr_->footVelocityRelativeToBaseInBaseFrame(i, qJoints, qVelJoints) + + getLinearVelocity(baseTwist) + getAngularVelocity(baseTwist).cross(b_baseToFoot); + const vector3_t o_footVelocity = o_R_b * b_footVelocity; + desiredFeetPositionMsgs[i].push_back(ocs2::getPointMsg(o_footPosition)); + feetVelArray[i].markers.emplace_back(getArrowAtPointMsg(o_footVelocity / velScale_, o_footPosition, feetColorMap_[i])); + } + } + + // Headers + auto baseLineMsg = getLineMsg(std::move(desiredBasePositionMsg), ocs2::Color::green, trajectoryLineWidth_); + baseLineMsg.header = ocs2::getHeaderMsg(frameId_, timeStamp); + baseLineMsg.id = 0; + poseArray.header = ocs2::getHeaderMsg(frameId_, timeStamp); + + ocs2::assignHeader(velArray.markers.begin(), velArray.markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(velArray.markers.begin(), velArray.markers.end()); + ocs2::assignHeader(angVelArray.markers.begin(), angVelArray.markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(angVelArray.markers.begin(), angVelArray.markers.end()); + + // Publish + costDesiredBasePositionPublisher_.publish(baseLineMsg); + costDesiredBasePosePublisher_.publish(poseArray); + costDesiredBaseVelocityPublisher_.publish(velArray); + costDesiredBaseAngVelocityPublisher_.publish(angVelArray); + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + auto footLineMsg = getLineMsg(std::move(desiredFeetPositionMsgs[i]), feetColorMap_[i], trajectoryLineWidth_); + footLineMsg.header = ocs2::getHeaderMsg(frameId_, timeStamp); + footLineMsg.id = 0; + costDesiredFeetPositionPublishers_[i].publish(footLineMsg); + ocs2::assignHeader(feetVelArray[i].markers.begin(), feetVelArray[i].markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(feetVelArray[i].markers.begin(), feetVelArray[i].markers.end()); + costDesiredFeetVelocityPublishers_[i].publish(feetVelArray[i]); + } +} + +void QuadrupedVisualizer::publishOptimizedStateTrajectory(ros::Time timeStamp, const scalar_array_t& mpcTimeTrajectory, + const vector_array_t& mpcStateTrajectory, + const ocs2::ModeSchedule& modeSchedule) const { + if (mpcTimeTrajectory.empty() || mpcStateTrajectory.empty()) { + return; // Nothing to publish + } + + // Reserve Feet msg + feet_array_t> feetMsgs; + std::for_each(feetMsgs.begin(), feetMsgs.end(), [&](std::vector& v) { v.reserve(mpcStateTrajectory.size()); }); + + // Reserve Base Msg + std::vector mpcBasePositionMsgs; + mpcBasePositionMsgs.reserve(mpcStateTrajectory.size()); + + // Reserve Pose array + geometry_msgs::PoseArray poseArray; + poseArray.poses.reserve(mpcStateTrajectory.size()); + + // Extract Base and Feet from state + std::for_each(mpcStateTrajectory.begin(), mpcStateTrajectory.end(), [&](const vector_t& state) { + const state_vector_t switchedState = state.head(STATE_DIM); + const base_coordinate_t basePose = getBasePose(switchedState); + const vector3_t o_basePosition = getPositionInOrigin(basePose); + const vector3_t eulerXYZ = getOrientation(basePose); + const matrix3_t o_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + const joint_coordinate_t qJoints = getJointPositions(switchedState); + + // Fill Base position and pose msgs + geometry_msgs::Pose pose; + pose.position = ocs2::getPointMsg(o_basePosition); + pose.orientation = ocs2::getOrientationMsg(quaternionBaseToOrigin(eulerXYZ)); + mpcBasePositionMsgs.push_back(pose.position); + poseArray.poses.push_back(std::move(pose)); + + // Fill feet msgs + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + auto o_footPosition = o_basePosition; + o_footPosition.noalias() += o_R_b * kinematicModelPtr_->positionBaseToFootInBaseFrame(i, qJoints); + feetMsgs[i].push_back(ocs2::getPointMsg(o_footPosition)); + } + }); + + // Convert feet msgs to Array message + visualization_msgs::MarkerArray markerArray; + markerArray.markers.reserve(NUM_CONTACT_POINTS + 2); // 1 trajectory per foot + 1 for the future footholds + 1 for the Base trajectory + for (int i = 0; i < NUM_CONTACT_POINTS; i++) { + markerArray.markers.emplace_back(getLineMsg(std::move(feetMsgs[i]), feetColorMap_[i], trajectoryLineWidth_)); + markerArray.markers.back().ns = "EE Trajectories"; + } + markerArray.markers.emplace_back(getLineMsg(std::move(mpcBasePositionMsgs), ocs2::Color::red, trajectoryLineWidth_)); + markerArray.markers.back().ns = "Base Trajectory"; + + // Future footholds + visualization_msgs::Marker sphereList; + sphereList.type = visualization_msgs::Marker::SPHERE_LIST; + sphereList.scale.x = footMarkerDiameter_; + sphereList.scale.y = footMarkerDiameter_; + sphereList.scale.z = footMarkerDiameter_; + sphereList.ns = "Future footholds"; + sphereList.pose.orientation = ocs2::getOrientationMsg({1., 0., 0., 0.}); + const auto& eventTimes = modeSchedule.eventTimes; + const auto& subsystemSequence = modeSchedule.modeSequence; + const double tStart = mpcTimeTrajectory.front(); + const double tEnd = mpcTimeTrajectory.back(); + for (int event = 0; event < eventTimes.size(); ++event) { + if (tStart < eventTimes[event] && eventTimes[event] < tEnd) { // Only publish future footholds within the optimized horizon + const auto preEventContactFlags = modeNumber2StanceLeg(subsystemSequence[event]); + const auto postEventContactFlags = modeNumber2StanceLeg(subsystemSequence[event + 1]); + const vector_t postEventState = ocs2::LinearInterpolation::interpolate(eventTimes[event], mpcTimeTrajectory, mpcStateTrajectory); + const state_vector_t postEventSwitchedState = postEventState.head(STATE_DIM); + const base_coordinate_t basePose = getBasePose(postEventSwitchedState); + const joint_coordinate_t qJoints = getJointPositions(postEventSwitchedState); + + for (int i = 0; i < NUM_CONTACT_POINTS; i++) { + if (!preEventContactFlags[i] && postEventContactFlags[i]) { // If a foot lands, a marker is added at that location. + const auto o_feetPosition = kinematicModelPtr_->footPositionInOriginFrame(i, basePose, qJoints); + sphereList.points.emplace_back(ocs2::getPointMsg(o_feetPosition)); + sphereList.colors.push_back(getColor(feetColorMap_[i])); + } + } + } + } + markerArray.markers.push_back(std::move(sphereList)); + + // Add headers and Id + ocs2::assignHeader(markerArray.markers.begin(), markerArray.markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(markerArray.markers.begin(), markerArray.markers.end()); + poseArray.header = ocs2::getHeaderMsg(frameId_, timeStamp); + + stateOptimizedPublisher_.publish(markerArray); + stateOptimizedPosePublisher_.publish(poseArray); +} + +void QuadrupedVisualizer::publishEndEffectorPoses(ros::Time timeStamp, const feet_array_t& feetPositions, + const feet_array_t>& feetOrientations) const { + // Feet positions and Forces + geometry_msgs::PoseArray poseArray; + poseArray.header = ocs2::getHeaderMsg(frameId_, timeStamp); + for (int i = 0; i < NUM_CONTACT_POINTS; ++i) { + geometry_msgs::Pose pose; + pose.position = ocs2::getPointMsg(feetPositions[i]); + pose.orientation = ocs2::getOrientationMsg(feetOrientations[i]); + poseArray.poses.push_back(std::move(pose)); + } + + currentFeetPosesPublisher_.publish(poseArray); +} + +void QuadrupedVisualizer::publishCollisionSpheres(ros::Time timeStamp, const base_coordinate_t& basePose, + const joint_coordinate_t& jointAngles) const { + const auto collisionSpheres = kinematicModelPtr_->collisionSpheresInOriginFrame(basePose, jointAngles); + + visualization_msgs::MarkerArray markerArray; + markerArray.markers.reserve(collisionSpheres.size()); + + for (const auto& sphere : collisionSpheres) { + markerArray.markers.emplace_back(ocs2::getSphereMsg(sphere.position, ocs2::Color::red, 2.0 * sphere.radius)); + } + + // Give markers an id and a frame + ocs2::assignHeader(markerArray.markers.begin(), markerArray.markers.end(), ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(markerArray.markers.begin(), markerArray.markers.end()); + + currentCollisionSpheresPublisher_.publish(markerArray); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/SwingPlanningVisualizer.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/SwingPlanningVisualizer.cpp new file mode 100644 index 000000000..423998c2b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/SwingPlanningVisualizer.cpp @@ -0,0 +1,84 @@ +// +// Created by rgrandia on 30.04.20. +// + +#include "ocs2_quadruped_interface/SwingPlanningVisualizer.h" + +#include +#include + +#include + +namespace switched_model { + +SwingPlanningVisualizer::SwingPlanningVisualizer(const SwingTrajectoryPlanner& swingTrajectoryPlanner, ros::NodeHandle& nodeHandle) + : swingTrajectoryPlannerPtr_(&swingTrajectoryPlanner) { + nominalFootholdPublishers_[0] = nodeHandle.advertise("/ocs2_anymal/swing_planner/nominalFootholds_LF", 1); + nominalFootholdPublishers_[1] = nodeHandle.advertise("/ocs2_anymal/swing_planner/nominalFootholds_RF", 1); + nominalFootholdPublishers_[2] = nodeHandle.advertise("/ocs2_anymal/swing_planner/nominalFootholds_LH", 1); + nominalFootholdPublishers_[3] = nodeHandle.advertise("/ocs2_anymal/swing_planner/nominalFootholds_RH", 1); + swingTrajectoryPublishers_[0] = nodeHandle.advertise("/ocs2_anymal/swing_planner/trajectory_LF", 1); + swingTrajectoryPublishers_[1] = nodeHandle.advertise("/ocs2_anymal/swing_planner/trajectory_RF", 1); + swingTrajectoryPublishers_[2] = nodeHandle.advertise("/ocs2_anymal/swing_planner/trajectory_LH", 1); + swingTrajectoryPublishers_[3] = nodeHandle.advertise("/ocs2_anymal/swing_planner/trajectory_RH", 1); +} + +void SwingPlanningVisualizer::preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) { + const auto timeStamp = ros::Time::now(); + + // Nominal footholds + for (int leg = 0; leg < NUM_CONTACT_POINTS; leg++) { + const auto nominalFootholds = swingTrajectoryPlannerPtr_->getNominalFootholds(leg); + + // Reserve pose array + geometry_msgs::PoseArray poseArray; + poseArray.poses.reserve(nominalFootholds.size()); + + // Convert terrain planes to pose msgs + std::for_each(nominalFootholds.begin(), nominalFootholds.end(), [&](const ConvexTerrain& foothold) { + // Construct pose msg + geometry_msgs::Pose pose; + pose.position = ocs2::getPointMsg(foothold.plane.positionInWorld); + Eigen::Quaterniond terrainOrientation(foothold.plane.orientationWorldToTerrain.transpose()); + pose.orientation = ocs2::getOrientationMsg(terrainOrientation); + + // Fill message container + poseArray.poses.push_back(std::move(pose)); + }); + + poseArray.header = ocs2::getHeaderMsg(frameId_, timeStamp); + nominalFootholdPublishers_[leg].publish(poseArray); + } + + // Feet trajectories + visualization_msgs::Marker deleteMarker; + deleteMarker.action = visualization_msgs::Marker::DELETEALL; + for (int leg = 0; leg < NUM_CONTACT_POINTS; leg++) { + // Initialize and add marker that deletes old visualizations + visualization_msgs::MarkerArray swingTrajectoriesMessage; + swingTrajectoriesMessage.markers.reserve(swingTrajectoryPlannerPtr_->getTargetTrajectories().timeTrajectory.size() + 1); // lower bound + swingTrajectoriesMessage.markers.push_back(deleteMarker); + + for (const auto& t : swingTrajectoryPlannerPtr_->getTargetTrajectories().timeTrajectory) { + if (t < initTime || t > finalTime) { + continue; + } + + const auto& footPhase = swingTrajectoryPlannerPtr_->getFootPhase(leg, t); + SwingNode3d node{t, footPhase.getPositionInWorld(t), footPhase.getVelocityInWorld(t)}; + + swingTrajectoriesMessage.markers.push_back(ocs2::getArrowAtPointMsg(arrowScale * node.velocity, node.position, feetColorMap_[leg])); + swingTrajectoriesMessage.markers.back().scale.x = 0.005; // shaft diameter + swingTrajectoriesMessage.markers.back().scale.y = 0.01; // arrow-head diameter + swingTrajectoriesMessage.markers.back().scale.z = 0.02; // arrow-head length + } + + ocs2::assignHeader(swingTrajectoriesMessage.markers.begin(), swingTrajectoriesMessage.markers.end(), + ocs2::getHeaderMsg(frameId_, timeStamp)); + ocs2::assignIncreasingId(swingTrajectoriesMessage.markers.begin(), swingTrajectoriesMessage.markers.end()); + swingTrajectoryPublishers_[leg].publish(swingTrajectoriesMessage); + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainPlaneVisualizer.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainPlaneVisualizer.cpp new file mode 100644 index 000000000..9d414f10e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainPlaneVisualizer.cpp @@ -0,0 +1,49 @@ +// +// Created by rgrandia on 30.04.20. +// + +#include "ocs2_quadruped_interface/TerrainPlaneVisualizer.h" + +#include + +#include "ocs2_switched_model_interface/terrain/PlaneFitting.h" + +namespace switched_model { + +TerrainPlaneVisualizer::TerrainPlaneVisualizer(ros::NodeHandle& nodeHandle) { + terrainPublisher_ = nodeHandle.advertise("/ocs2_anymal/localTerrain", 1, true); +} + +void TerrainPlaneVisualizer::update(scalar_t time, const TerrainPlane& terrainPlane) { + // Headers + Eigen::Quaterniond terrainOrientation(terrainPlane.orientationWorldToTerrain.transpose()); + auto planeMsg = + getPlaneMsg(terrainPlane.positionInWorld, terrainOrientation, ocs2::Color::black, planeWidth_, planeLength_, planeThickness_); + planeMsg.header = ocs2::getHeaderMsg(frameId_, ros::Time::now()); + planeMsg.id = 0; + planeMsg.color.a = planeAlpha_; + + terrainPublisher_.publish(planeMsg); +} + +TerrainPlaneVisualizerSynchronizedModule::TerrainPlaneVisualizerSynchronizedModule(const SwingTrajectoryPlanner& swingTrajectoryPlanner, + ros::NodeHandle& nodeHandle) + : swingTrajectoryPlanner_(&swingTrajectoryPlanner), planeVisualizer_(nodeHandle) {} + +void TerrainPlaneVisualizerSynchronizedModule::postSolverRun(const ocs2::PrimalSolution& primalSolution) { + std::vector regressionPoints; + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const auto& footholds = swingTrajectoryPlanner_->getNominalFootholds(leg); + if (!footholds.empty()) { + regressionPoints.push_back(footholds.front().plane.positionInWorld); + } + } + + if (regressionPoints.size() >= 3) { + const auto normalAndPosition = estimatePlane(regressionPoints); + TerrainPlane plane(normalAndPosition.position, orientationWorldToTerrainFromSurfaceNormalInWorld(normalAndPosition.normal)); + planeVisualizer_.update(primalSolution.timeTrajectory_.front(), plane); + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainReceiver.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainReceiver.cpp new file mode 100644 index 000000000..99b0c55df --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_interface/src/TerrainReceiver.cpp @@ -0,0 +1,21 @@ +// +// Created by rgrandia on 28.09.20. +// + +#include "ocs2_quadruped_interface/TerrainReceiver.h" + +namespace switched_model { + +TerrainReceiverSynchronizedModule::TerrainReceiverSynchronizedModule(ocs2::Synchronized& terrainModel, + ros::NodeHandle& nodeHandle) + : terrainModelPtr_(&terrainModel), segmentedPlanesRos_(new switched_model::SegmentedPlanesTerrainModelRos(nodeHandle)) {} + +void TerrainReceiverSynchronizedModule::preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) { + if (auto newTerrain = segmentedPlanesRos_->getTerrainModel()) { + terrainModelPtr_->reset(std::move(newTerrain)); + segmentedPlanesRos_->publish(); + } +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/CMakeLists.txt new file mode 100644 index 000000000..92331cf9c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/CMakeLists.txt @@ -0,0 +1,84 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_quadruped_loopshaping_interface) + +## Catkin Dependencies +set(CATKIN_PACKAGE_DEPENDENCIES + ocs2_quadruped_interface + ) +find_package(catkin REQUIRED COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} + ) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ${CATKIN_PACKAGE_DEPENDENCIES} + DEPENDS +) + +########### +## Build ## +########### + +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +# Declare a C++ library +add_library(${PROJECT_NAME} + src/QuadrupedLoopshapingDummyNode.cpp + src/QuadrupedLoopshapingInterface.cpp + src/QuadrupedLoopshapingMpc.cpp + src/QuadrupedLoopshapingMpcNode.cpp +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if (cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} + SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include + CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include + CF_WERROR + ) +endif (cmake_clang_tools_FOUND) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/LoopshapingDimensions.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/LoopshapingDimensions.h new file mode 100644 index 000000000..fa8e33bdb --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/LoopshapingDimensions.h @@ -0,0 +1,36 @@ +// +// Created by rgrandia on 18.02.20. +// + +#pragma once + +#include + +#include + +namespace switched_model_loopshaping { + +static constexpr size_t STATE_DIM = 48; +static constexpr size_t INPUT_DIM = 24; +static constexpr size_t SYSTEM_STATE_DIM = 24; +static constexpr size_t SYSTEM_INPUT_DIM = 24; +static constexpr size_t FILTER_STATE_DIM = 24; +static constexpr size_t FILTER_INPUT_DIM = 24; + +using scalar_t = ocs2::scalar_t; +using ad_scalar_t = ocs2::ad_scalar_t; +using scalar_array_t = ocs2::scalar_array_t; +using vector_t = ocs2::vector_t; +using vector_array_t = ocs2::vector_array_t; + +template +using filter_state_s_t = Eigen::Matrix; +using filter_state_t = filter_state_s_t; +using filter_state_ad_t = filter_state_s_t; + +template +using filter_input_s_t = Eigen::Matrix; +using filter_input_t = filter_input_s_t; +using filter_input_ad_t = filter_input_s_t; + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingDummyNode.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingDummyNode.h new file mode 100644 index 000000000..7ffd10078 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingDummyNode.h @@ -0,0 +1,16 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +#include + +#include "QuadrupedLoopshapingInterface.h" + +namespace switched_model_loopshaping { + +void quadrupedLoopshapingDummyNode(ros::NodeHandle& nodeHandle, const QuadrupedLoopshapingInterface& quadrupedInterface, + double mrtDesiredFrequency, double mpcDesiredFrequency); + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingInterface.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingInterface.h new file mode 100644 index 000000000..e9507082d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingInterface.h @@ -0,0 +1,63 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +// Loopshaping +#include +#include + +#include + +#include +#include + +#include "ocs2_quadruped_loopshaping_interface/LoopshapingDimensions.h" + +namespace switched_model_loopshaping { + +class QuadrupedLoopshapingInterface : public ocs2::LoopshapingRobotInterface { + public: + using com_model_t = switched_model::ComModelBase; + using kinematic_model_t = switched_model::KinematicsModelBase; + + using ad_com_model_t = switched_model::ComModelBase; + using ad_kinematic_model_t = switched_model::KinematicsModelBase; + + QuadrupedLoopshapingInterface(std::unique_ptr quadrupedPtr, + std::shared_ptr loopshapingDefinition); + + ~QuadrupedLoopshapingInterface() override = default; + + const switched_model::QuadrupedInterface& getQuadrupedInterface() const { return this->get(); } + + std::shared_ptr getLoopshapingSynchronizedModule() const { return loopshapingSynchronizedModule_; }; + + /** Gets kinematic model */ + const kinematic_model_t& getKinematicModel() const { return getQuadrupedInterface().getKinematicModel(); } + + /** Gets center of mass model */ + const com_model_t& getComModel() const { return getQuadrupedInterface().getComModel(); } + + /** Gets the loaded initial state */ + const vector_t& getInitialState() const { return initialState_; } + + /** Access to model settings */ + const switched_model::ModelSettings& modelSettings() const { return getQuadrupedInterface().modelSettings(); }; + + /** Access to model names */ + const std::vector& getJointNames() const { return getQuadrupedInterface().getJointNames(); }; + const std::string& getBaseName() const { return getQuadrupedInterface().getBaseName(); }; + + /** Gets the rollout class */ + const ocs2::RolloutBase& getRollout() const { return *timeTriggeredRolloutPtr_; } + + private: + std::unique_ptr timeTriggeredRolloutPtr_; + std::shared_ptr loopshapingSynchronizedModule_; + + vector_t initialState_; +}; + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpc.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpc.h new file mode 100644 index 000000000..5f9600da9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpc.h @@ -0,0 +1,24 @@ +// +// Created by rgrandia on 06.07.21. +// + +#pragma once + +#include +#include +#include +#include + +#include "ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingInterface.h" + +namespace switched_model_loopshaping { + +/** Constructs an DDP MPC object */ +std::unique_ptr getDdpMpc(const QuadrupedLoopshapingInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::ddp::Settings& ddpSettings); + +/** Constructs an SQP MPC object */ +std::unique_ptr getSqpMpc(const QuadrupedLoopshapingInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::sqp::Settings& sqpSettings); + +} // namespace switched_model_loopshaping \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpcNode.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpcNode.h new file mode 100644 index 000000000..5f8c9ed36 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/include/ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpcNode.h @@ -0,0 +1,18 @@ +// +// Created by rgrandia on 17.02.20. +// + +#pragma once + +#include + +#include + +#include "QuadrupedLoopshapingInterface.h" + +namespace switched_model_loopshaping { + +void quadrupedLoopshapingMpcNode(ros::NodeHandle& nodeHandle, const QuadrupedLoopshapingInterface& quadrupedInterface, + std::unique_ptr mpcPtr); + +} // namespace switched_model_loopshaping \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/package.xml new file mode 100644 index 000000000..027573941 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/package.xml @@ -0,0 +1,19 @@ + + + ocs2_quadruped_loopshaping_interface + 0.0.0 + The ocs2_quadruped_loopshaping_interface package + + + + + farbod + + + TODO + + catkin + + ocs2_quadruped_interface + + \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingDummyNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingDummyNode.cpp new file mode 100644 index 000000000..84937a7ff --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingDummyNode.cpp @@ -0,0 +1,59 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingDummyNode.h" + +#include + +#include +#include + +#include + +#include +#include + +namespace switched_model_loopshaping { + +void quadrupedLoopshapingDummyNode(ros::NodeHandle& nodeHandle, const QuadrupedLoopshapingInterface& quadrupedInterface, + double mrtDesiredFrequency, double mpcDesiredFrequency) { + const std::string robotName = "anymal"; + + // MRT + ocs2::MRT_ROS_Interface mrt(robotName); + mrt.initRollout(&quadrupedInterface.getRollout()); + mrt.launchNodes(nodeHandle); + + // Visualization + auto visualizer = std::make_shared( + quadrupedInterface.getKinematicModel(), quadrupedInterface.getJointNames(), quadrupedInterface.getBaseName(), nodeHandle); + + // Logging + std::string logFileName = "/tmp/ocs2/QuadrupedLoopshapingDummyNodeLog.txt"; + auto logger = std::make_shared(logFileName, quadrupedInterface.getKinematicModel(), + quadrupedInterface.getComModel()); + + // Loopshaping observer wrappers + std::vector> observers{visualizer, logger}; + auto loopshapingObservers = std::make_shared(quadrupedInterface.getLoopshapingDefinition(), observers); + + // Dummy MRT + ocs2::MRT_ROS_Dummy_Loop dummySimulator(mrt, mrtDesiredFrequency, mpcDesiredFrequency); + dummySimulator.subscribeObservers({loopshapingObservers}); + + // initial state + ocs2::SystemObservation initObservation; + initObservation.state = quadrupedInterface.getInitialState(); + initObservation.input.setZero(INPUT_DIM); + initObservation.mode = switched_model::ModeNumber::STANCE; + + // initial command + ocs2::TargetTrajectories initTargetTrajectories({0.0}, {quadrupedInterface.getQuadrupedInterface().getInitialState()}, + {initObservation.input}); + + // run dummy + dummySimulator.run(initObservation, initTargetTrajectories); +} + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingInterface.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingInterface.cpp new file mode 100644 index 000000000..c073ac035 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingInterface.cpp @@ -0,0 +1,31 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingInterface.h" +#include "ocs2_quadruped_loopshaping_interface/LoopshapingDimensions.h" + +namespace switched_model_loopshaping { + +QuadrupedLoopshapingInterface::QuadrupedLoopshapingInterface(std::unique_ptr quadrupedPtr, + std::shared_ptr loopshapingDefinition) + : ocs2::LoopshapingRobotInterface(std::move(quadrupedPtr), std::move(loopshapingDefinition)) { + // initialize state including filter state + const auto stanceFlags = switched_model::constantFeetArray(true); + const auto uSystemForWeightCompensation = + weightCompensatingInputs(getQuadrupedInterface().getComModel(), stanceFlags, switched_model::vector3_t::Zero()); + + ocs2::vector_t initialFilterState; + ocs2::vector_t initialFilterInput; + this->getLoopshapingDefinition()->getFilterEquilibrium(uSystemForWeightCompensation, initialFilterState, initialFilterInput); + initialState_ = + this->getLoopshapingDefinition()->concatenateSystemAndFilterState(getQuadrupedInterface().getInitialState(), initialFilterState); + + // wrap with loopshaping + timeTriggeredRolloutPtr_.reset( + new ocs2::TimeTriggeredRollout(*getOptimalControlProblem().dynamicsPtr, getQuadrupedInterface().rolloutSettings())); + loopshapingSynchronizedModule_ = std::make_shared(this->getLoopshapingDefinition(), + getQuadrupedInterface().getSynchronizedModules()); +} + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpc.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpc.cpp new file mode 100644 index 000000000..8acc64ed5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpc.cpp @@ -0,0 +1,31 @@ +// +// Created by rgrandia on 06.07.21. +// + +#include "ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpc.h" + +#include +#include + +namespace switched_model_loopshaping { + +std::unique_ptr getDdpMpc(const QuadrupedLoopshapingInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::ddp::Settings& ddpSettings) { + std::unique_ptr mpcPtr(new ocs2::GaussNewtonDDP_MPC(mpcSettings, ddpSettings, quadrupedInterface.getRollout(), + quadrupedInterface.getOptimalControlProblem(), + quadrupedInterface.getInitializer())); + mpcPtr->getSolverPtr()->setReferenceManager(quadrupedInterface.getReferenceManagerPtr()); + mpcPtr->getSolverPtr()->setSynchronizedModules({quadrupedInterface.getLoopshapingSynchronizedModule()}); + return mpcPtr; +} + +std::unique_ptr getSqpMpc(const QuadrupedLoopshapingInterface& quadrupedInterface, const ocs2::mpc::Settings& mpcSettings, + const ocs2::sqp::Settings& sqpSettings) { + std::unique_ptr mpcPtr( + new ocs2::SqpMpc(mpcSettings, sqpSettings, quadrupedInterface.getOptimalControlProblem(), quadrupedInterface.getInitializer())); + mpcPtr->getSolverPtr()->setReferenceManager(quadrupedInterface.getReferenceManagerPtr()); + mpcPtr->getSolverPtr()->setSynchronizedModules({quadrupedInterface.getLoopshapingSynchronizedModule()}); + return mpcPtr; +} + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpcNode.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpcNode.cpp new file mode 100644 index 000000000..b9143e3a1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_quadruped_loopshaping_interface/src/QuadrupedLoopshapingMpcNode.cpp @@ -0,0 +1,57 @@ +// +// Created by rgrandia on 17.02.20. +// + +#include "ocs2_quadruped_loopshaping_interface/QuadrupedLoopshapingMpcNode.h" + +#include +#include + +#include + +#include +#include +#include + +namespace switched_model_loopshaping { + +void quadrupedLoopshapingMpcNode(ros::NodeHandle& nodeHandle, const QuadrupedLoopshapingInterface& quadrupedInterface, + std::unique_ptr mpcPtr) { + const std::string robotName = "anymal"; + + auto loopshapingSolverModule = quadrupedInterface.getLoopshapingSynchronizedModule(); + + // Gait + auto gaitReceiver = std::make_shared( + nodeHandle, quadrupedInterface.getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getGaitSchedule(), robotName); + loopshapingSolverModule->add(gaitReceiver); + + // Terrain Receiver + auto terrainReceiver = std::make_shared( + quadrupedInterface.getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getTerrainModel(), nodeHandle); + loopshapingSolverModule->add(terrainReceiver); + + // Terrain plane visualization + auto terrainVisualizer = std::make_shared( + quadrupedInterface.getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getSwingTrajectoryPlanner(), nodeHandle); + loopshapingSolverModule->add(terrainVisualizer); + + // Swing planner + auto swingPlanningVisualizer = std::make_shared( + quadrupedInterface.getQuadrupedInterface().getSwitchedModelModeScheduleManagerPtr()->getSwingTrajectoryPlanner(), nodeHandle); + loopshapingSolverModule->add(swingPlanningVisualizer); + + // reference manager + auto rosReferenceManagerPtr = std::make_shared(robotName, quadrupedInterface.getReferenceManagerPtr()); + rosReferenceManagerPtr->subscribe(nodeHandle); + mpcPtr->getSolverPtr()->setReferenceManager(rosReferenceManagerPtr); + + // MPC + mpcPtr->getSolverPtr()->setSynchronizedModules({loopshapingSolverModule}); + + // launch MPC nodes + ocs2::MPC_ROS_Interface mpcNode(*mpcPtr, robotName); + mpcNode.launchNodes(nodeHandle); +} + +} // namespace switched_model_loopshaping diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/CMakeLists.txt new file mode 100644 index 000000000..534994e69 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/CMakeLists.txt @@ -0,0 +1,194 @@ +cmake_minimum_required(VERSION 3.0) +project(ocs2_switched_model_interface) + +## Catkin Dependencies +set(CATKIN_PACKAGE_DEPENDENCIES + roscpp + ocs2_core + ocs2_msgs + ocs2_oc + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_msgs +) +find_package(catkin REQUIRED COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} +) + +## Eigen3 +find_package(Eigen3 3.3 REQUIRED NO_MODULE) + +# Generate compile_commands.json for clang tools +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + CATKIN_DEPENDS + ${CATKIN_PACKAGE_DEPENDENCIES} +# DEPENDS +) + +########### +## Build ## +########### +include_directories( + include + ${EIGEN3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/analytical_inverse_kinematics/AnalyticalInverseKinematics.cpp + src/analytical_inverse_kinematics/LegInverseKinematicParameters.cpp + src/constraint/EndEffectorVelocityConstraint.cpp + src/constraint/FootNormalConstraint.cpp + src/constraint/FrictionConeConstraint.cpp + src/constraint/ZeroForceConstraint.cpp + src/dynamics/ComKinoSystemDynamicsAd.cpp + src/dynamics/ComKinoDynamicsParameters.cpp + src/cost/CollisionAvoidanceCost.cpp + src/cost/FootPlacementCost.cpp + src/cost/FrictionConeCost.cpp + src/cost/LinearStateInequalitySoftConstraint.cpp + src/cost/MotionTrackingCost.cpp + src/cost/MotionTrackingTerminalCost.cpp + src/cost/TorqueLimitsSoftConstraint.cpp + src/foot_planner/KinematicFootPlacementPenalty.cpp + src/foot_planner/CubicSpline.cpp + src/foot_planner/FootPhase.cpp + src/foot_planner/QuinticSplineSwing.cpp + src/foot_planner/SplineCpg.cpp + src/foot_planner/SwingSpline3d.cpp + src/foot_planner/SwingTrajectoryPlanner.cpp + src/initialization/ComKinoInitializer.cpp + src/logic/Gait.cpp + src/logic/GaitAdaptation.cpp + src/logic/GaitReceiver.cpp + src/logic/GaitSchedule.cpp + src/logic/ModeSequenceTemplate.cpp + src/logic/SingleLegLogic.cpp + src/logic/DynamicsParametersSynchronizedModule.cpp + src/logic/SwitchedModelModeScheduleManager.cpp + src/ros_msg_conversions/RosMsgConversions.cpp + src/terrain/PlanarSignedDistanceField.cpp + src/terrain/PlanarTerrainModel.cpp + src/terrain/PlaneFitting.cpp + src/terrain/TerrainPlane.cpp + src/core/ComModelBase.cpp + src/core/KinematicsModelBase.cpp + src/core/ModelSettings.cpp + src/core/SwitchedModelPrecomputation.cpp + src/core/TorqueApproximation.cpp +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + dl +) +target_compile_options(${PROJECT_NAME} PUBLIC ${OCS2_CXX_FLAGS}) + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if(cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} + SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include + CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include + CF_WERROR + ) +endif(cmake_clang_tools_FOUND) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +############# +## Testing ## +############# + +catkin_add_gtest(test_constraints + test/constraint/testZeroForceConstraint.cpp + test/constraint/testFrictionConeConstraint.cpp +) +target_link_libraries(test_constraints + ${PROJECT_NAME} + ${catkin_LIBRARIES} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_core + test/core/testRotation.cpp +) +target_link_libraries(test_${PROJECT_NAME}_core + ${PROJECT_NAME} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_cost + test/cost/testFootplacementCost.cpp + test/cost/testFrictionConeCost.cpp + test/cost/testTorqueLimitsSoftConstraint.cpp +) +target_link_libraries(test_${PROJECT_NAME}_cost + ${PROJECT_NAME} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_footplanner + test/foot_planner/testSwingPhase.cpp +) +target_link_libraries(test_${PROJECT_NAME}_footplanner + ${PROJECT_NAME} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_logic + test/logic/testEarlyTouchDown.cpp + test/logic/testExtractContractTimings.cpp + test/logic/testGait.cpp + test/logic/testGaitSwitching.cpp + test/logic/testGaitSchedule.cpp + test/logic/testSingleLegLogic.cpp +) +target_link_libraries(test_${PROJECT_NAME}_logic + ${PROJECT_NAME} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_terrain + test/terrain/testTerrainPlane.cpp +) +target_link_libraries(test_${PROJECT_NAME}_terrain + ${PROJECT_NAME} + gtest_main +) + +catkin_add_gtest(test_${PROJECT_NAME}_convexTerrain + test/terrain/testConvexTerrain.cpp +) +target_link_libraries(test_${PROJECT_NAME}_convexTerrain + ${PROJECT_NAME} + gtest_main +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/AnalyticalInverseKinematics.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/AnalyticalInverseKinematics.h new file mode 100644 index 000000000..9608ae5d0 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/AnalyticalInverseKinematics.h @@ -0,0 +1,20 @@ +#pragma once + +#include "ocs2_switched_model_interface/analytical_inverse_kinematics/LegInverseKinematicParameters.h" + +namespace switched_model { +namespace analytical_inverse_kinematics { + +/** + * Computes the inverse kinematics for a single leg given the position in base frame + * @param legJoints : will be filled with the resulting [HAA, HFE, KFE] joint angles + * @param positionBaseToFootInBaseFrame : position of the foot in base frame to compute the IK for. + * @param parameters : precomputed inverse kinematics parameters + * @param limb : limb number in {LF = 0, RF, LH, RH} + */ +void getLimbJointPositionsFromPositionBaseToFootInBaseFrame(Eigen::Vector3d& legJoints, + const Eigen::Vector3d& positionBaseToFootInBaseFrame, + const LegInverseKinematicParameters& parameters, size_t limb); + +} // namespace analytical_inverse_kinematics +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/LegInverseKinematicParameters.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/LegInverseKinematicParameters.h new file mode 100644 index 000000000..a8838ff39 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/analytical_inverse_kinematics/LegInverseKinematicParameters.h @@ -0,0 +1,50 @@ +#pragma once + +#include + +namespace switched_model { +namespace analytical_inverse_kinematics { + +/** + * Contains the relative positions of base, hip, thigh, shank, and foot in the zero configuration. + * From there it derives constant parameters for the analytical inverse kinematics computation. + */ +class LegInverseKinematicParameters { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + LegInverseKinematicParameters() = default; + + // Construct these parameters with the robot configuration at all 0.0 joint angles + LegInverseKinematicParameters(const Eigen::Vector3d& positionBaseToHipInBaseFrame, const Eigen::Vector3d& positionHipToThighInBaseFrame, + const Eigen::Vector3d& positionThighToShankInBaseFrame, + const Eigen::Vector3d& positionShankToFootInBaseFrame); + + // Zero configuration + Eigen::Vector3d positionBaseToHipInBaseFrame_{Eigen::Vector3d::Zero()}; + Eigen::Vector3d positionHipToThighInBaseFrame_{Eigen::Vector3d::Zero()}; + Eigen::Vector3d positionThighToShankInBaseFrame_{Eigen::Vector3d::Zero()}; + Eigen::Vector3d positionShankToFootInBaseFrame_{Eigen::Vector3d::Zero()}; + + // Inverse kinematics parameters (derived from zero configuration) + Eigen::Vector3d positionBaseToHaaCenterInBaseFrame_{Eigen::Vector3d::Zero()}; + double positionHipToFootYoffset_{0.0}; + double positionHipToFootYoffsetSquared_{0.0}; + double minReach_{0.0}; + double minReach_SP_{0.0}; + double minReachSquared_{0.0}; + double maxReach_SP_{0.0}; + double maxReach_{0.0}; + double maxReachSquared_{0.0}; + double KFEOffset_{0.0}; + double a1_{0.0}; + double a1_squared_{0.0}; + double a2_{0.0}; + double a2_squared_{0.0}; + + private: + /** @brief Initializes all derived parameters. Requires the base parameters to be set. */ + void initialize(); +}; + +} // namespace analytical_inverse_kinematics +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/EndEffectorVelocityConstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/EndEffectorVelocityConstraint.h new file mode 100644 index 000000000..b508f6c2b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/EndEffectorVelocityConstraint.h @@ -0,0 +1,42 @@ +#pragma once + +#include + +#include + +namespace switched_model { + +/** + * Implements the constraint that the velocity of the foot w.r.t. the world, that is tangent to the surface normal, + * must be zero for a foot in contact: + * + * Tangent(n) * footVelocity = 0 + * + * Uses the precomputed foot velocity. + */ +class EndEffectorVelocityConstraint final : public ocs2::StateInputConstraint { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EndEffectorVelocityConstraint(int legNumber, const SwitchedModelModeScheduleManager& modeScheduleManager); + + ~EndEffectorVelocityConstraint() override = default; + + EndEffectorVelocityConstraint* clone() const override; + + bool isActive(scalar_t time) const override; + + size_t getNumConstraints(scalar_t time) const override; + + vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const ocs2::PreComputation& preComp) const override; + + VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const override; + + private: + EndEffectorVelocityConstraint(const EndEffectorVelocityConstraint& rhs) = default; + + int legNumber_; + const SwitchedModelModeScheduleManager* modeScheduleManager_; +}; +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FootNormalConstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FootNormalConstraint.h new file mode 100644 index 000000000..f42546934 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FootNormalConstraint.h @@ -0,0 +1,42 @@ +// +// Created by rgrandia on 29.04.20. +// + +#pragma once + +#include + +#include + +namespace switched_model { + +/** + * Implements the swing motion equality constraint in the normal direction of the terrain. + * Active both in contact (to stabilize the position w.r.t. terrain) and in swing (to follow the trajectory in normal direction) + * + * The constraint is a hybrid position-velocity constraint formulated in task space: + * A_p * position + A_v * velocity + b = 0 + */ +class FootNormalConstraint : public ocs2::StateInputConstraint { + public: + FootNormalConstraint(int legNumber, scalar_t positionGain); + + FootNormalConstraint* clone() const override; + + bool isActive(scalar_t time) const override { return true; } + + size_t getNumConstraints(scalar_t time) const override { return 1; } + + vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const ocs2::PreComputation& preComp) const override; + + VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const override; + + private: + FootNormalConstraint(const FootNormalConstraint& rhs); + + const int legNumber_; + const scalar_t positionGain_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FrictionConeConstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FrictionConeConstraint.h new file mode 100644 index 000000000..797e79873 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/FrictionConeConstraint.h @@ -0,0 +1,123 @@ +#pragma once + +#include + +#include +#include + +namespace switched_model { + +/** + * Implements the constraint h(t,x,u) >= 0 + * + * frictionCoefficient * (Fz + gripperForce) - sqrt(Fx * Fx + Fy * Fy + regularization) >= 0 + * + * The gripper force shifts the origin of the friction cone down in z-direction by the amount of gripping force available. This makes it + * possible to produce tangential forces without applying a regular normal force on that foot, or to "pull" on the foot with magnitude up to + * the gripping force. + * + * The regularization prevents the constraint gradient / hessian to go to infinity when Fx = Fz = 0. It also creates a parabolic safety + * margin to the friction cone. For example: when Fx = Fy = 0 the constraint zero-crossing will be at Fz = 1/frictionCoefficient * + * sqrt(regularization) instead of Fz = 0 + * + */ +namespace friction_cone { + +/** + * frictionCoefficient: The coefficient of friction. + * regularization: A positive number to regulize the friction constraint. refer to the FrictionConeConstraint documentation. + * gripperForce: Gripper force in normal direction. + * hessianDiagonalShift: The Hessian shift to assure a strictly-convex quadratic constraint approximation. + */ +struct Config { + explicit Config(scalar_t frictionCoefficientParam = 0.7, scalar_t regularizationParam = 25.0, scalar_t gripperForceParam = 0.0, + scalar_t hessianDiagonalShiftParam = 1e-6) + : frictionCoefficient(frictionCoefficientParam), + regularization(regularizationParam), + gripperForce(gripperForceParam), + hessianDiagonalShift(hessianDiagonalShiftParam) { + assert(frictionCoefficient > 0.0); + assert(regularization > 0.0); + assert(hessianDiagonalShift >= 0.0); + } + + scalar_t frictionCoefficient; + scalar_t regularization; + scalar_t gripperForce; + scalar_t hessianDiagonalShift; +}; + +/** + * Computes the friction cone constraint + * + * @param config : friction cone configuration + * @param forcesInTerrainFrame : forces defined in the terrain frame. The z component is aligned with the normal direction. + * @return scalar constraint value h(t,x,u) >= 0 + */ +scalar_t frictionConeConstraint(const Config& config, const vector3_t& forcesInTerrainFrame); + +/** + * Zero, first, and second order derivative of the friction cone constraint w.r.t forces in the terrain + */ +struct ConeLocalDerivatives { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// constraint value + scalar_t coneConstraint; + + /// first derivative w.r.t force in the terrain frame + vector3_t dCone_dF; + + /// second derivative w.r.t force in the terrain frame + matrix3_t d2Cone_dF2; +}; + +/** + * Compute the derivatives of the friction cone constraint w.r.t. the local forces + * + * @param config : friction cone configuration + * @param forcesInTerrainFrame : forces defined in the terrain frame. The z component is aligned with the normal direction. + * @return zero, first, and second derivative of the friction cone. + */ +ConeLocalDerivatives frictionConeLocalDerivatives(const Config& config, const vector3_t& forcesInTerrainFrame); + +/** + * Zero, first, and second order derivative of the friction cone constraint w.r.t forces in the body frame + */ +struct ConeDerivatives { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + /// constraint value + scalar_t coneConstraint; + + /// first derivative w.r.t body orientation (EulerXYZ) + vector3_t dCone_deuler; + + /// first derivative w.r.t forces in body frame + vector3_t dCone_du; + + /// second derivative w.r.t body orientation (EulerXYZ) + matrix3_t d2Cone_deuler2; + + /// second derivative w.r.t forces in body frame + matrix3_t d2Cone_du2; + + /// second derivative coupling terms {forces in body frame} x {body orientation (EulerXYZ)} + matrix3_t d2Cone_dudeuler; +}; + +/** + * Computes the derivatives of the friction cone constraint w.r.t. forces in body frame and the body orientation (eulerXYZ). + * + * @param config : friction cone configuration + * @param forcesInTerrainFrame : forces defined in the terrain frame. The z component is aligned with the normal direction. + * @param t_R_w : rotation matrix world to terrain + * @param w_R_b : rotation matrix body to world + * @param eulerXYZ : current body orientation + * @param forcesInBodyFrame : forces in body frame + * @return zero, first, and second derivative of the friction cone. + */ +ConeDerivatives frictionConeDerivatives(const Config& config, const vector3_t& forcesInTerrainFrame, const matrix3_t& t_R_w, + const matrix3_t& w_R_b, const vector3_t& eulerXYZ, const vector3_t& forcesInBodyFrame); + +} // namespace friction_cone + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/ZeroForceConstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/ZeroForceConstraint.h new file mode 100644 index 000000000..826a46159 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/constraint/ZeroForceConstraint.h @@ -0,0 +1,36 @@ +#pragma once + +#include + +#include +#include + +namespace switched_model { + +/** + * Implements the constraint that the contact forces of the foot must be zero for a foot in swing. + */ +class ZeroForceConstraint final : public ocs2::StateInputConstraint { + public: + explicit ZeroForceConstraint(int legNumber, const SwitchedModelModeScheduleManager& modeScheduleManager); + + ZeroForceConstraint* clone() const override; + + bool isActive(scalar_t time) const override; + + size_t getNumConstraints(scalar_t time) const override; + + vector_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const ocs2::PreComputation& preComp) const override; + + VectorFunctionLinearApproximation getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const override; + + private: + ZeroForceConstraint(const ZeroForceConstraint& rhs) = default; + + const int legStartIdx_; + const int legNumber_; + const SwitchedModelModeScheduleManager* modeScheduleManager_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ComModelBase.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ComModelBase.h new file mode 100644 index 000000000..63cfd4f2f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ComModelBase.h @@ -0,0 +1,62 @@ +#pragma once + +#include + +namespace switched_model { + +/** + * CoM Model Base Class + */ +template +class ComModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + ComModelBase() = default; + + virtual ~ComModelBase() = default; + + /** + * Clone ComModelBase class. + */ + virtual ComModelBase* clone() const = 0; + + /** + * Total mass of robot + * @return mass in kg + */ + virtual SCALAR_T totalMass() const = 0; + + /** + * Computes the base acceleration based on the top 6 rows of the full rigid body dynamics of the system. + * + * @param basePose : {EulerXYZ (3x1), base position in Origin frame (3x1)} + * @param baseLocalVelocities : {base angular velocity in Base Frame (3x1), base linear velocity in Base Frame (3x1)} + * @param jointPositions : Joint positions (12x1) + * @param jointVelocities : Joint velocities (12x1) + * @param jointAccelerations : Joint accelerations (12x1) + * @param forcesOnBaseInBaseFrame : { torque on base in Base Frame (3x1), linear forces on the base in Base Frame (3x1) }. + * Forces on the base due to contact forces, i.e. J^T * F should also be included here. + * @return baseLocalAccelerations : {base angular acceleration in Base Frame (3x1), base linear acceleration in Base Frame (3x1)} + */ + virtual base_coordinate_s_t calculateBaseLocalAccelerations( + const base_coordinate_s_t& basePose, const base_coordinate_s_t& baseLocalVelocities, + const joint_coordinate_s_t& jointPositions, const joint_coordinate_s_t& jointVelocities, + const joint_coordinate_s_t& jointAccelerations, + const switched_model::base_coordinate_s_t& forcesOnBaseInBaseFrame) const = 0; +}; + +extern template class ComModelBase; +extern template class ComModelBase; + +/** + * Distribute the weight equally among all stance feet. + * + * @return model inputs with {Forces in base, joint velocies} + */ +comkino_input_t weightCompensatingInputs(const ComModelBase& comModel, const contact_flag_t& contactFlags, + const vector3_t& baseOrientation); + +comkino_input_t weightCompensatingInputs(scalar_t mass, const contact_flag_t& contactFlags, const vector3_t& baseOrientation); + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/InverseKinematicsModelBase.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/InverseKinematicsModelBase.h new file mode 100644 index 000000000..7215630ac --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/InverseKinematicsModelBase.h @@ -0,0 +1,30 @@ +// +// Created by rgrandia on 02.08.22. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +class InverseKinematicsModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + using joint_jacobian_block_t = Eigen::Matrix; + + virtual ~InverseKinematicsModelBase() = default; + + virtual vector3_t getLimbJointPositionsFromPositionBaseToFootInBaseFrame(size_t footIndex, + const vector3_t& positionBaseToFootInBaseFrame) const = 0; + + virtual vector3_t getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame(size_t footIndex, + const vector3_t& footVelocityRelativeToBaseInBaseFrame, + const joint_jacobian_block_t& jointJacobian, + scalar_t damping) const = 0; + + virtual InverseKinematicsModelBase* clone() const = 0; +}; + +}; // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/KinematicsModelBase.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/KinematicsModelBase.h new file mode 100644 index 000000000..a5a5a24f9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/KinematicsModelBase.h @@ -0,0 +1,102 @@ +/* + * KinematicsModelBase.h + * + * Created on: Aug 2, 2017 + * Author: Farbod + */ + +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * ModelKinematics Base Class + * @tparam SCALAR_T + */ +template +class KinematicsModelBase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + using joint_jacobian_t = Eigen::Matrix; + using joint_jacobian_block_t = Eigen::Matrix; + + KinematicsModelBase() = default; + + virtual ~KinematicsModelBase() = default; + + virtual KinematicsModelBase* clone() const = 0; + + virtual vector3_s_t baseToLegRootInBaseFrame(size_t footIndex) const = 0; + + vector3_s_t legRootInOriginFrame(size_t footIndex, const base_coordinate_s_t& basePose) const; + + matrix3_s_t orientationLegRootToOriginFrame(size_t footIndex, const base_coordinate_s_t& basePose) const; + + vector3_s_t legRootVelocityInBaseFrame(size_t footIndex, const base_coordinate_s_t& baseTwistInBaseFrame) const; + + vector3_s_t legRootVelocityInOriginFrame(size_t footIndex, const base_coordinate_s_t& basePoseInOriginFrame, + const base_coordinate_s_t& baseTwistInBaseFrame) const; + + virtual vector3_s_t positionBaseToFootInBaseFrame(size_t footIndex, + const joint_coordinate_s_t& jointPositions) const = 0; + + feet_array_t> positionBaseToFeetInBaseFrame(const joint_coordinate_s_t& jointPositions) const; + + vector3_s_t footPositionInOriginFrame(size_t footIndex, const base_coordinate_s_t& basePoseInOriginFrame, + const joint_coordinate_s_t& jointPositions) const; + + feet_array_t> feetPositionsInOriginFrame(const base_coordinate_s_t& basePose, + const joint_coordinate_s_t& jointPositions) const; + + joint_jacobian_t baseToFootJacobianInBaseFrame(size_t footIndex, const joint_coordinate_s_t& jointPositions) const; + + virtual joint_jacobian_block_t baseToFootJacobianBlockInBaseFrame(size_t footIndex, + const joint_coordinate_s_t& jointPositions) const = 0; + + virtual matrix3_s_t footOrientationInBaseFrame(size_t footIndex, + const joint_coordinate_s_t& jointPositions) const = 0; + + matrix3_s_t footOrientationInOriginFrame(size_t footIndex, const base_coordinate_s_t& basePose, + const joint_coordinate_s_t& jointPositions) const; + + virtual vector3_s_t footVelocityRelativeToBaseInBaseFrame(size_t footIndex, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const; + + vector3_s_t footVelocityInBaseFrame(size_t footIndex, const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const; + + vector3_s_t footVelocityInOriginFrame(size_t footIndex, const base_coordinate_s_t& basePoseInOriginFrame, + const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const; + + vector3_s_t footVelocityInFootFrame(size_t footIndex, const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const; + + feet_array_t> feetVelocitiesInOriginFrame(const base_coordinate_s_t& basePoseInOriginFrame, + const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const; + + struct CollisionSphere { + vector3_s_t position; + SCALAR_T radius; + }; + std::vector collisionSpheresInOriginFrame(const base_coordinate_s_t& basePoseInOriginFrame, + const joint_coordinate_s_t& jointPositions) const; + + virtual std::vector collisionSpheresInBaseFrame(const joint_coordinate_s_t& jointPositions) const; +}; + +extern template class KinematicsModelBase; +extern template class KinematicsModelBase; + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ModelSettings.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ModelSettings.h new file mode 100644 index 000000000..9df961589 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/ModelSettings.h @@ -0,0 +1,54 @@ +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +enum class Algorithm { DDP, SQP }; +std::string toAlgorithmName(Algorithm type); +Algorithm fromAlgorithmName(std::string name); + +struct ModelSettings { + Algorithm algorithm_ = Algorithm::SQP; + bool recompileLibraries_ = true; + std::string robotName_ = "quadruped"; + std::string autodiffLibraryFolder_ = "/tmp/ocs2"; + + scalar_t phaseTransitionStanceTime_ = 0.4; + + // Analytical IK + bool analyticalInverseKinematics_ = false; + + // Friction Cone + scalar_t frictionCoefficient_ = 1.0; + scalar_t coneRegularization_ = 25.0; + scalar_t gripperForce_ = 0.0; + scalar_t muFrictionCone_ = 0.1; + scalar_t deltaFrictionCone_ = 5.0; + + // FootPlacement relaxed barrier parameters + scalar_t muFootPlacement_ = 0.1; // magnitude scaling + scalar_t deltaFootPlacement_ = 0.01; // [m] distance from constraint boundary where the barrier becomes quadratic. + + // Collision avoidance relaxed barrier parameters + scalar_t muSdf_ = 2.5; + scalar_t deltaSdf_ = 0.005; + + // Joint Limits + joint_coordinate_t lowerJointLimits_ = joint_coordinate_t::Constant(-1e30); + joint_coordinate_t upperJointLimits_ = joint_coordinate_t::Constant(1e30); + joint_coordinate_t jointVelocityLimits = joint_coordinate_t::Constant(1e30); + joint_coordinate_t jointTorqueLimits = joint_coordinate_t::Constant(1e30); + scalar_t muJointsPosition_ = 0.1; + scalar_t deltaJointsPosition_ = 0.1; + scalar_t muJointsVelocity_ = 0.1; + scalar_t deltaJointsVelocity_ = 0.1; + scalar_t muJointsTorque_ = 0.1; + scalar_t deltaJointsTorque_ = 0.1; +}; + +ModelSettings loadModelSettings(const std::string& filename, bool verbose = true); + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/MotionPhaseDefinition.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/MotionPhaseDefinition.h new file mode 100644 index 000000000..573ce90fe --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/MotionPhaseDefinition.h @@ -0,0 +1,151 @@ +/* + * MotionPhaseDefinition.h + * + * Created on: Nov 16, 2017 + * Author: farbod + */ + +#pragma once + +#include +#include +#include +#include + +#include +#include + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +enum ModeNumber { // {LF, RF, LH, RH} + FLY = 0, + RH = 1, + LH = 2, + LH_RH = 3, + RF = 4, + RF_RH = 5, + RF_LH = 6, + RF_LH_RH = 7, + LF = 8, + LF_RH = 9, + LF_LH = 10, + LF_LH_RH = 11, + LF_RF = 12, + LF_RF_RH = 13, + LF_RF_LH = 14, + STANCE = 15, +}; + +inline contact_flag_t modeNumber2StanceLeg(const size_t& modeNumber) { + contact_flag_t stanceLegs; // {LF, RF, LH, RH} + + switch (modeNumber) { + case 0: + stanceLegs = contact_flag_t{false, false, false, false}; + break; // 0: 0-leg-stance + case 1: + stanceLegs = contact_flag_t{false, false, false, true}; + break; // 1: RH + case 2: + stanceLegs = contact_flag_t{false, false, true, false}; + break; // 2: LH + case 3: + stanceLegs = contact_flag_t{false, false, true, true}; + break; // 3: RH, LH + case 4: + stanceLegs = contact_flag_t{false, true, false, false}; + break; // 4: RF + case 5: + stanceLegs = contact_flag_t{false, true, false, true}; + break; // 5: RF, RH + case 6: + stanceLegs = contact_flag_t{false, true, true, false}; + break; // 6: RF, LH + case 7: + stanceLegs = contact_flag_t{false, true, true, true}; + break; // 7: RF, LH, RH + case 8: + stanceLegs = contact_flag_t{true, false, false, false}; + break; // 8: LF, + case 9: + stanceLegs = contact_flag_t{true, false, false, true}; + break; // 9: LF, RH + case 10: + stanceLegs = contact_flag_t{true, false, true, false}; + break; // 10: LF, LH + case 11: + stanceLegs = contact_flag_t{true, false, true, true}; + break; // 11: LF, LH, RH + case 12: + stanceLegs = contact_flag_t{true, true, false, false}; + break; // 12: LF, RF + case 13: + stanceLegs = contact_flag_t{true, true, false, true}; + break; // 13: LF, RF, RH + case 14: + stanceLegs = contact_flag_t{true, true, true, false}; + break; // 14: LF, RF, LH + case 15: + stanceLegs = contact_flag_t{true, true, true, true}; + break; // 15: 4-leg-stance + } + + return stanceLegs; +} + +inline size_t stanceLeg2ModeNumber(const contact_flag_t& stanceLegs) { + return static_cast(stanceLegs[3]) + 2 * static_cast(stanceLegs[2]) + 4 * static_cast(stanceLegs[1]) + + 8 * static_cast(stanceLegs[0]); +} + +inline std::string modeNumber2String(const size_t& modeNumber) { + // build the map from mode number to name + std::map modeToName; + modeToName[FLY] = "FLY"; + modeToName[RH] = "RH"; + modeToName[LH] = "LH"; + modeToName[LH_RH] = "LH_RH"; + modeToName[RF] = "RF"; + modeToName[RF_RH] = "RF_RH"; + modeToName[RF_LH] = "RF_LH"; + modeToName[RF_LH_RH] = "RF_LH_RH"; + modeToName[LF] = "LF"; + modeToName[LF_RH] = "LF_RH"; + modeToName[LF_LH] = "LF_LH"; + modeToName[LF_LH_RH] = "LF_LH_RH"; + modeToName[LF_RF] = "LF_RF"; + modeToName[LF_RF_RH] = "LF_RF_RH"; + modeToName[LF_RF_LH] = "LF_RF_LH"; + modeToName[STANCE] = "STANCE"; + + return modeToName[modeNumber]; +} + +inline size_t string2ModeNumber(const std::string& modeString) { + // build the map from name to mode number + std::map nameToMode; + nameToMode["FLY"] = FLY; + nameToMode["RH"] = RH; + nameToMode["LH"] = LH; + nameToMode["LH_RH"] = LH_RH; + nameToMode["RF"] = RF; + nameToMode["RF_RH"] = RF_RH; + nameToMode["RF_LH"] = RF_LH; + nameToMode["RF_LH_RH"] = RF_LH_RH; + nameToMode["LF"] = LF; + nameToMode["LF_RH"] = LF_RH; + nameToMode["LF_LH"] = LF_LH; + nameToMode["LF_LH_RH"] = LF_LH_RH; + nameToMode["LF_RF"] = LF_RF; + nameToMode["LF_RF_RH"] = LF_RF_RH; + nameToMode["LF_RF_LH"] = LF_RF_LH; + nameToMode["STANCE"] = STANCE; + + return nameToMode[modeString]; +} + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/Rotations.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/Rotations.h new file mode 100644 index 000000000..5b371211a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/Rotations.h @@ -0,0 +1,306 @@ +// +// Created by rgrandia on 22.10.19. +// + +#pragma once + +#include +#include +#include + +#include + +namespace switched_model { + +/** + * Base to origin rotation matrix + * @tparam Derived + * @param [in] eulerAngles + * @return + */ +template +Eigen::Matrix rotationMatrixBaseToOrigin(const Eigen::Matrix& eulerAnglesXYZ) { + // Generated code for: + // // inputs are the intrinsic rotation angles in RADIANTS + // SCALAR_T sinAlpha = sin(eulerAngles(0)); + // SCALAR_T cosAlpha = cos(eulerAngles(0)); + // SCALAR_T sinBeta = sin(eulerAngles(1)); + // SCALAR_T cosBeta = cos(eulerAngles(1)); + // SCALAR_T sinGamma = sin(eulerAngles(2)); + // SCALAR_T cosGamma = cos(eulerAngles(2)); + // + // Eigen::Matrix Rx, Ry, Rz; + // Rx << SCALAR_T(1), SCALAR_T(0), SCALAR_T(0), SCALAR_T(0), cosAlpha, -sinAlpha, SCALAR_T(0), sinAlpha, cosAlpha; + // Ry << cosBeta, SCALAR_T(0), sinBeta, SCALAR_T(0), SCALAR_T(1), SCALAR_T(0), -sinBeta, SCALAR_T(0), cosBeta; + // Rz << cosGamma, -sinGamma, SCALAR_T(0), sinGamma, cosGamma, SCALAR_T(0), SCALAR_T(0), SCALAR_T(0), SCALAR_T(1); + // + // return Rx * Ry * Rz; + Eigen::Matrix o_R_b; + + // auxiliary variables + std::array v{}; + + v[0] = cos(eulerAnglesXYZ[1]); + v[1] = cos(eulerAnglesXYZ[2]); + o_R_b(0) = v[0] * v[1]; + v[2] = sin(eulerAnglesXYZ[0]); + v[3] = -v[2]; + o_R_b(6) = sin(eulerAnglesXYZ[1]); + v[4] = -o_R_b(6); + v[5] = v[3] * v[4]; + v[6] = cos(eulerAnglesXYZ[0]); + v[7] = sin(eulerAnglesXYZ[2]); + o_R_b(1) = v[5] * v[1] + v[6] * v[7]; + v[4] = v[6] * v[4]; + o_R_b(2) = v[4] * v[1] + v[2] * v[7]; + v[7] = -v[7]; + o_R_b(3) = v[0] * v[7]; + o_R_b(4) = v[5] * v[7] + v[6] * v[1]; + o_R_b(5) = v[4] * v[7] + v[2] * v[1]; + o_R_b(7) = v[3] * v[0]; + o_R_b(8) = v[6] * v[0]; + return o_R_b; +} + +template +Eigen::Matrix rotationMatrixOriginToBase(const Eigen::Matrix& eulerAngles) { + return rotationMatrixBaseToOrigin(eulerAngles).transpose(); +} + +template +void rotateInPlace2d(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vy = v.y(); + v.x() = c * vx - s * vy; + v.y() = s * vx + c * vy; +} + +template +void invRotateInPlace2d(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vy = v.y(); + v.x() = c * vx + s * vy; + v.y() = -s * vx + c * vy; +} + +template +void rotateInPlaceZ(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vy = v.y(); + v.x() = c * vx - s * vy; + v.y() = s * vx + c * vy; +} + +template +void invRotateInPlaceZ(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vy = v.y(); + v.x() = c * vx + s * vy; + v.y() = -s * vx + c * vy; +} + +template +void rotateInPlaceY(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vz = v.z(); + v.x() = c * vx + s * vz; + v.z() = -s * vx + c * vz; +} + +template +void invRotateInPlaceY(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vx = v.x(); + const SCALAR_T vz = v.z(); + v.x() = c * vx - s * vz; + v.z() = s * vx + c * vz; +} + +template +void rotateInPlaceX(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vy = v.y(); + const SCALAR_T vz = v.z(); + v.y() = c * vy - s * vz; + v.z() = s * vy + c * vz; +} + +template +void invRotateInPlaceX(Eigen::Matrix& v, SCALAR_T angle) { + const SCALAR_T c = cos(angle); + const SCALAR_T s = sin(angle); + const SCALAR_T vy = v.y(); + const SCALAR_T vz = v.z(); + v.y() = c * vy + s * vz; + v.z() = -s * vy + c * vz; +} + +/** + * Directly rotates a vector from base to origin. + * + * Uses 12 (3*4) multiplications, and 6 (3*2) additions. + * + * Constructing just the rotation matrix already takes 14 multiplication, and 4 additions. Without having rotated the vector. + * Multiplication with the rotation matrix takes 9 multiplications and 6 additions. + * Constructing the rotation matrix could be cheaper when doing >5 rotations with the same matrix + */ +template +Eigen::Matrix rotateVectorBaseToOrigin(const Eigen::Matrix& v, + const Eigen::Matrix& eulerAnglesXYZ) { + Eigen::Matrix rotatedVector = v; + rotateInPlaceZ(rotatedVector, eulerAnglesXYZ[2]); + rotateInPlaceY(rotatedVector, eulerAnglesXYZ[1]); + rotateInPlaceX(rotatedVector, eulerAnglesXYZ[0]); + return rotatedVector; +} + +/** + * inverse of rotateVectorBaseToOrigin, use here the invRotate helpers instead of rotate(-angle), + * otherwise the sin/cos(angle) and sin/cos(-angle) cannot be merged by CppAd + */ +template +Eigen::Matrix rotateVectorOriginToBase(const Eigen::Matrix& v, + const Eigen::Matrix& eulerAnglesXYZ) { + Eigen::Matrix rotatedVector = v; + invRotateInPlaceX(rotatedVector, eulerAnglesXYZ[0]); + invRotateInPlaceY(rotatedVector, eulerAnglesXYZ[1]); + invRotateInPlaceZ(rotatedVector, eulerAnglesXYZ[2]); + return rotatedVector; +} + +template +Eigen::Quaternion quaternionBaseToOrigin(const Eigen::Matrix& eulerAngles) { + return Eigen::Quaternion(Eigen::AngleAxis(eulerAngles(0), Eigen::Matrix::UnitX()) * + Eigen::AngleAxis(eulerAngles(1), Eigen::Matrix::UnitY()) * + Eigen::AngleAxis(eulerAngles(2), Eigen::Matrix::UnitZ())); +} + +template +Eigen::Matrix eulerAnglesFromQuaternionBaseToOrigin(const Eigen::Quaternion& q_origin_base) { + return q_origin_base.toRotationMatrix().eulerAngles(0, 1, 2); +} + +/** + * Calculates the skew matrix for vector cross product + * @tparam Derived + * @param [in] in + * @return + */ +template +Eigen::Matrix crossProductMatrix(const Eigen::DenseBase& in) { + if (in.innerSize() != 3 || in.outerSize() != 1) { + throw std::runtime_error("Input argument should be a 3-by-1 vector."); + } + + Eigen::Matrix out; + out << SCALAR_T(0.0), -in(2), +in(1), +in(2), SCALAR_T(0.0), -in(0), -in(1), +in(0), SCALAR_T(0.0); + return out; +} + +/** + * Computes the matrix which transforms derivatives of angular velocities in the body frame to euler angles derivatives + * WARNING: matrix is singular when rotation around y axis is +/- 90 degrees + * @param[in] eulerAngles: euler angles in xyz convention + * @return M: matrix that does the transformation + */ +template +Eigen::Matrix angularVelocitiesToEulerAngleDerivativesMatrix(const Eigen::Matrix& eulerAngles) { + Eigen::Matrix M; + SCALAR_T sinPsi = sin(eulerAngles(2)); + SCALAR_T cosPsi = cos(eulerAngles(2)); + SCALAR_T sinTheta = sin(eulerAngles(1)); + SCALAR_T cosTheta = cos(eulerAngles(1)); + + M << cosPsi / cosTheta, -sinPsi / cosTheta, SCALAR_T(0), sinPsi, cosPsi, SCALAR_T(0), -cosPsi * sinTheta / cosTheta, + sinTheta * sinPsi / cosTheta, SCALAR_T(1); + + return M; +} + +template +Eigen::Matrix angularVelocitiesToEulerAngleDerivatives(const Eigen::Matrix& angularVelocitiesInBase, + const Eigen::Matrix& eulerAngles) { + const SCALAR_T sinPsi = sin(eulerAngles(2)); + const SCALAR_T cosPsi = cos(eulerAngles(2)); + const SCALAR_T sinTheta = sin(eulerAngles(1)); + const SCALAR_T cosTheta = cos(eulerAngles(1)); + + const SCALAR_T dRoll = (cosPsi * angularVelocitiesInBase(0) - sinPsi * angularVelocitiesInBase(1)) / cosTheta; + const SCALAR_T dPitch = sinPsi * angularVelocitiesInBase(0) + cosPsi * angularVelocitiesInBase(1); + const SCALAR_T dYaw = angularVelocitiesInBase(2) - sinTheta * dRoll; + + return {dRoll, dPitch, dYaw}; +} + +/** + * Computes the derivative w.r.t eulerXYZ of rotating a vector from base to origin : d/d(euler) (o_R_b(euler) * v_base) + * + * @param[in] eulerAnglesXYZ: euler angles in xyz convention. + * @param[in] vectorInBase: the vector in base that is rotated. + * @return d/d(euler) (o_R_b(euler) * v_base) + */ +template +Eigen::Matrix rotationBaseToOriginJacobian(const Eigen::Matrix& eulerAnglesXYZ, + const Eigen::Matrix& vectorInBase) { + // dependent variables + Eigen::Matrix jac; + + // auxiliary variables + std::array v{}; + + jac(0) = SCALAR_T(0.0); + v[0] = -sin(eulerAnglesXYZ[1]); + v[1] = cos(eulerAnglesXYZ[2]); + v[2] = sin(eulerAnglesXYZ[2]); + v[3] = v[1] * vectorInBase[0] - v[2] * vectorInBase[1]; + v[4] = cos(eulerAnglesXYZ[1]); + jac(3) = v[0] * v[3] + v[4] * vectorInBase[2]; + v[5] = v[4]; + v[6] = -v[2]; + v[7] = v[1]; + v[8] = v[6] * vectorInBase[0] - v[7] * vectorInBase[1]; + jac(6) = v[5] * v[8]; + v[9] = -sin(eulerAnglesXYZ[0]); + v[2] = v[2] * vectorInBase[0] + v[1] * vectorInBase[1]; + v[1] = cos(eulerAnglesXYZ[0]); + v[10] = v[0]; + v[5] = v[10] * v[3] + v[5] * vectorInBase[2]; + jac(1) = v[9] * v[2] - v[1] * v[5]; + v[11] = -v[9]; + v[4] = (-v[4]) * v[3] + v[0] * vectorInBase[2]; + jac(4) = -v[11] * v[4]; + v[3] = v[1]; + v[7] = v[7] * vectorInBase[0] + v[6] * vectorInBase[1]; + v[10] = v[10] * v[8]; + jac(7) = v[3] * v[7] - v[11] * v[10]; + jac(2) = v[1] * v[2] + v[9] * v[5]; + jac(5) = v[3] * v[4]; + jac(8) = v[11] * v[7] + v[3] * v[10]; + return jac; +} + +template +Eigen::Matrix rotationErrorInWorldEulerXYZ(const Eigen::Matrix& eulerXYZcurrent, + const Eigen::Matrix& eulerXYZreference) { + return ocs2::rotationErrorInWorld(rotationMatrixBaseToOrigin(eulerXYZcurrent), rotationMatrixBaseToOrigin(eulerXYZreference)); +} + +template +Eigen::Matrix rotationErrorInLocalEulerXYZ(const Eigen::Matrix& eulerXYZcurrent, + const Eigen::Matrix& eulerXYZreference) { + return ocs2::rotationErrorInLocal(rotationMatrixBaseToOrigin(eulerXYZcurrent), rotationMatrixBaseToOrigin(eulerXYZreference)); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModel.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModel.h new file mode 100644 index 000000000..17abf9c5a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModel.h @@ -0,0 +1,228 @@ +#pragma once + +#include +#include + +#include +#include +#include + +namespace switched_model { +/** + * Switched model definition: + * + * state = [theta, p, w, v, q (4x)] + * theta: EulerXYZ (3x1) + * p: Base position in Origin frame (3x1) + * w: Base angular velocity in Base Frame (3x1) + * v: Base linear velocity in Base Frame (3x1) + * q: Joint angles per leg [HAA, HFE, KFE] (3x1) [4x] + * + * input = [lambda (4x), qj (4x)] + * lambda: Force at the EE [LF, RF, LH, RH] in Base Frame (3x1) + * qj: Joint velocities per leg [HAA, HFE, KFE] (3x1) + */ + +constexpr size_t NUM_CONTACT_POINTS = 4; +constexpr size_t BASE_COORDINATE_SIZE = 6; +constexpr size_t JOINT_COORDINATE_SIZE = 12; +constexpr size_t STATE_DIM = 2 * BASE_COORDINATE_SIZE + JOINT_COORDINATE_SIZE; // 24 +constexpr size_t INPUT_DIM = 3 * NUM_CONTACT_POINTS + JOINT_COORDINATE_SIZE; // 24 + +/* Import ocs2 types into the switched_model namespace */ +using ocs2::ad_matrix_t; +using ocs2::ad_scalar_t; +using ocs2::ad_vector_t; +using ocs2::matrix_array_t; +using ocs2::matrix_t; +using ocs2::scalar_array_t; +using ocs2::scalar_t; +using ocs2::size_array_t; +using ocs2::vector_array_t; +using ocs2::vector_t; + +using ocs2::ScalarFunctionQuadraticApproximation; +using ocs2::VectorFunctionLinearApproximation; +using ocs2::VectorFunctionQuadraticApproximation; + +/* Define fixed-size types */ +using state_vector_t = Eigen::Matrix; +using input_vector_t = Eigen::Matrix; + +/* Feet related declarations */ +enum class FeetEnum { LF, RF, LH, RH }; +template +using feet_array_t = std::array; // Fixed size container per foot +const feet_array_t feetNames{"LF", "RF", "LH", "RH"}; +using contact_flag_t = feet_array_t; // Contact state per foot, true = in contact, false = not in contact + +template +using vector2_s_t = Eigen::Matrix; +using vector2_t = vector2_s_t; +using vector2_ad_t = vector2_s_t; + +template +using vector3_s_t = Eigen::Matrix; +using vector3_t = vector3_s_t; +using vector3_ad_t = vector3_s_t; + +template +using matrix3_s_t = Eigen::Matrix; +using matrix3_t = matrix3_s_t; +using matrix3_ad_t = matrix3_s_t; + +template +using vector6_s_t = Eigen::Matrix; +using vector6_t = vector6_s_t; +using vector6_ad_t = vector6_s_t; + +template +using matrix6_s_t = Eigen::Matrix; +using matrix6_t = matrix6_s_t; +using matrix6_ad_t = matrix6_s_t; + +template +using base_coordinate_s_t = Eigen::Matrix; +using base_coordinate_t = base_coordinate_s_t; +using base_coordinate_ad_t = base_coordinate_s_t; + +template +using joint_coordinate_s_t = Eigen::Matrix; +using joint_coordinate_t = joint_coordinate_s_t; +using joint_coordinate_ad_t = joint_coordinate_s_t; + +template +using com_state_s_t = Eigen::Matrix; +using com_state_t = com_state_s_t; +using com_state_ad_t = com_state_s_t; + +template +using comkino_state_s_t = Eigen::Matrix; +using comkino_state_t = comkino_state_s_t; +using comkino_state_ad_t = comkino_state_s_t; + +template +using comkino_input_s_t = Eigen::Matrix; +using comkino_input_t = comkino_input_s_t; +using comkino_input_ad_t = comkino_input_s_t; + +template +base_coordinate_s_t getBasePose(const Eigen::Matrix& comkinoState) { + return comkinoState.template head(); +} + +template +base_coordinate_s_t getBasePose(const comkino_state_s_t& comkinoState) { + return comkinoState.template head(); +} + +template +vector3_s_t getOrientation(const base_coordinate_s_t& baseCoordinate) { + return baseCoordinate.template head<3>(); +} + +template +vector3_s_t getPositionInOrigin(const base_coordinate_s_t& baseCoordinate) { + return baseCoordinate.template tail<3>(); +} + +template +base_coordinate_s_t getBaseLocalVelocities(const Eigen::Matrix& comkinoState) { + return comkinoState.template segment(BASE_COORDINATE_SIZE); +} + +template +base_coordinate_s_t getBaseLocalVelocities(const comkino_state_s_t& comkinoState) { + return comkinoState.template segment(BASE_COORDINATE_SIZE); +} + +template +vector3_s_t getAngularVelocity(const base_coordinate_s_t& baseTwist) { + return baseTwist.template head<3>(); +} + +template +vector3_s_t getAngularAcceleration(const base_coordinate_s_t& baseAcceleration) { + return baseAcceleration.template head<3>(); +} + +template +vector3_s_t getLinearVelocity(const base_coordinate_s_t& baseTwist) { + return baseTwist.template tail<3>(); +} + +template +vector3_s_t getLinearAcceleration(const base_coordinate_s_t& baseAcceleration) { + return baseAcceleration.template tail<3>(); +} + +template +joint_coordinate_s_t getJointPositions(const Eigen::Matrix& comkinoState) { + return comkinoState.template segment(2 * BASE_COORDINATE_SIZE); +} + +template +joint_coordinate_s_t getJointPositions(const comkino_state_s_t& comkinoState) { + return comkinoState.template segment(2 * BASE_COORDINATE_SIZE); +} + +template +joint_coordinate_s_t getJointVelocities(const Eigen::Matrix& comkinoInput) { + return comkinoInput.template segment(NUM_CONTACT_POINTS * 3); +} + +template +joint_coordinate_s_t getJointVelocities(const comkino_input_s_t& comkinoInput) { + return comkinoInput.template segment(NUM_CONTACT_POINTS * 3); +} + +template +feet_array_t> toArray(const joint_coordinate_s_t& valuesAsVector) { + return {valuesAsVector.template segment<3>(0), valuesAsVector.template segment<3>(3), valuesAsVector.template segment<3>(6), + valuesAsVector.template segment<3>(9)}; +} + +template +joint_coordinate_s_t fromArray(const feet_array_t>& valuesAsArray) { + joint_coordinate_s_t valuesAsVector; + valuesAsVector << valuesAsArray[0], valuesAsArray[1], valuesAsArray[2], valuesAsArray[3]; + return valuesAsVector; +} + +/** + * Applies the function f to each leg individually. The inputs of f are to be passed per leg using feet_array. + * + * Example usage: + * feet_array_t numbers = {0.0, 1.0, 2.0, 3.0}; + * feet_array_t flags = {true, false, true, false}; + * + * auto negativeIfTrue = [](scalar_t val, bool flag) { return flag ? val : -val; }; + * const auto result = applyPerLeg(negativeIfTrue, numbers, flags); // = {-0.0, 1.0, -2.0, 3.0} + */ +template +auto applyPerLeg(Func f, const feet_array_t&... inputs) -> feet_array_t { + return {f(inputs[0]...), f(inputs[1]...), f(inputs[2]...), f(inputs[3]...)}; +} + +/** Creates a feet array filled with constant values */ +template +feet_array_t constantFeetArray(const T& val) { + return {val, val, val, val}; +} + +/** Count contact feet */ +inline int numberOfClosedContacts(const contact_flag_t& contactFlags) { + size_t numStanceLegs = 0; + for (auto legInContact : contactFlags) { + if (legInContact) { + ++numStanceLegs; + } + } + return numStanceLegs; +} + +inline int numberOfOpenContacts(const contact_flag_t& contactFlags) { + return NUM_CONTACT_POINTS - numberOfClosedContacts(contactFlags); +} + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h new file mode 100644 index 000000000..b6aebe1a5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h @@ -0,0 +1,146 @@ +// +// Created by rgrandia on 21.09.21. +// + +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/ComModelBase.h" +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/ModelSettings.h" +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/cost/CostElements.h" +#include "ocs2_switched_model_interface/foot_planner/FootPhase.h" +#include "ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h" +#include "ocs2_switched_model_interface/terrain/SignedDistanceField.h" + +namespace switched_model { + +class SwitchedModelPreComputationMockup; + +class SwitchedModelPreComputation : public ocs2::PreComputation { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + using com_model_t = ComModelBase; + using ad_com_model_t = ComModelBase; + using kinematic_model_t = KinematicsModelBase; + using ad_kinematic_model_t = KinematicsModelBase; + + SwitchedModelPreComputation(const SwingTrajectoryPlanner& swingTrajectoryPlanner, const kinematic_model_t& kinematicModel, + const ad_kinematic_model_t& adKinematicModel, const com_model_t& comModel, const ad_com_model_t& adComModel, + ModelSettings settings); + + ~SwitchedModelPreComputation() override = default; + + SwitchedModelPreComputation* clone() const override { return new SwitchedModelPreComputation(*this); } + + void request(ocs2::RequestSet request, scalar_t t, const vector_t& x, const vector_t& u) override; + + void requestPreJump(ocs2::RequestSet request, scalar_t t, const vector_t& x) override; + + void requestFinal(ocs2::RequestSet request, scalar_t t, const vector_t& x) override; + + // Precomputation access : always available + const SignedDistanceField* getSignedDistanceField() const { return swingTrajectoryPlannerPtr_->getSignedDistanceField(); } + const contact_flag_t& getContactFlags() const { return contactFlags_; } + const vector3_t& getSurfaceNormalInOriginFrame(size_t leg) const { return surfaceNormalsInOriginFrame_[leg]; } + const FootTangentialConstraintMatrix* getFootTangentialConstraintInWorldFrame(size_t leg) const { + return footTangentialConstraintInWorldFrame_[leg]; + } + + // Precomputation access : any(cost, constraint, softConstraint) + const vector3_t& footPositionInOriginFrame(size_t leg) const { return feetPositionInOriginFrame_[leg]; } + const vector3_t& footVelocityInOriginFrame(size_t leg) const { return feetVelocitiesInOriginFrame_[leg]; } + const joint_coordinate_t& jointTorques() const { return jointTorques_; } + const std::vector& collisionSpheresActive() const { return collisionSpheresActive_; } + const std::vector& collisionSpheresInOriginFrame() const { return collisionSpheresInOriginFrame_; } + const CostElements& getMotionReference() const { return motionReference_; } + const vector_t& getStateReference() const { return stateReference_; } + + // Precomputation access : any(cost, constraint, softConstraint) + (derivatives) + const matrix_t& footPositionInOriginFrameStateDerivative(size_t leg) const { return feetPositionInOriginFrameStateDerivative_[leg]; } + const VectorFunctionLinearApproximation& footVelocityInOriginFrameDerivative(size_t leg) const { + return feetVelocitiesInOriginFrameDerivative_[leg]; + } + const VectorFunctionLinearApproximation& jointTorquesDerivative() const { return jointTorquesDerivative_; } + const std::vector& collisionSpheresInOriginFrameStateDerivative() const { return collisionSpheresDerivative_; } + + protected: + SwitchedModelPreComputation() = default; + SwitchedModelPreComputation(const SwitchedModelPreComputation& other); + + private: + const FootPhase& getFootPhase(size_t leg) const { return *feetPhases_[leg]; } + void updateFeetPhases(scalar_t t); + + void updateMotionReference(scalar_t t); + + static void intermediateLinearOutputs(const ad_com_model_t& adComModel, const ad_kinematic_model_t& adKinematicsModel, + const ad_vector_t& state, const ad_vector_t& input, ad_vector_t& outputs); + void updateIntermediateLinearOutputs(scalar_t t, const vector_t& tapedStateInput); + void updateIntermediateLinearOutputDerivatives(scalar_t t, const vector_t& tapedStateInput); + + static void prejumpLinearOutputs(const ad_com_model_t& adComModel, const ad_kinematic_model_t& adKinematicsModel, + const ad_vector_t& state, ad_vector_t& outputs); + void updatePrejumpLinearOutputs(scalar_t t, const vector_t& state); + void updatePrejumpLinearOutputDerivatives(scalar_t t, const vector_t& state); + + const SwingTrajectoryPlanner* swingTrajectoryPlannerPtr_; + std::unique_ptr intermediateLinearOutputAdInterface_; + std::unique_ptr prejumpLinearOutputAdInterface_; + std::vector collisionRadii_; // Does not include those for the feet + + // ===== Storage for the precomputation === + scalar_t robotMass_; + vector_t tapedStateInput_; + + // Precomputation access : always available + feet_array_t feetPhases_; + contact_flag_t contactFlags_; + feet_array_t surfaceNormalsInOriginFrame_; + feet_array_t footTangentialConstraintInWorldFrame_; + + // Precomputation access : any(cost, constraint, softConstraint) + feet_array_t feetPositionInOriginFrame_; + feet_array_t feetVelocitiesInOriginFrame_; + joint_coordinate_t jointTorques_; + std::vector collisionSpheresActive_; + std::vector collisionSpheresInOriginFrame_; + CostElements motionReference_; + vector_t stateReference_; + + // Precomputation access : any(cost, constraint, softConstraint) + (derivatives) + feet_array_t feetPositionInOriginFrameStateDerivative_; + feet_array_t feetVelocitiesInOriginFrameDerivative_; + VectorFunctionLinearApproximation jointTorquesDerivative_; + std::vector collisionSpheresDerivative_; + + /// Friend access for unit testing purposes + friend SwitchedModelPreComputationMockup; +}; + +/** + * Helper class to set the internal state of the precomputation class in unit tests. + */ +class SwitchedModelPreComputationMockup : public SwitchedModelPreComputation { + public: + const FootPhase*& feetPhases(size_t leg) { return feetPhases_[leg]; }; + contact_flag_t& contactFlags() { return contactFlags_; } + vector3_t& feetPositionInOriginFrame(size_t leg) { return feetPositionInOriginFrame_[leg]; } + vector3_t& surfaceNormalInOriginFrame(size_t leg) { return surfaceNormalsInOriginFrame_[leg]; } + matrix_t& feetPositionInOriginFrameStateDerivative(size_t leg) { return feetPositionInOriginFrameStateDerivative_[leg]; } + vector3_t& feetVelocitiesInOriginFrame(size_t leg) { return feetVelocitiesInOriginFrame_[leg]; } + VectorFunctionLinearApproximation& feetVelocitiesInOriginFrameDerivative(size_t leg) { + return feetVelocitiesInOriginFrameDerivative_[leg]; + } + joint_coordinate_t jointTorques() { return jointTorques_; } + VectorFunctionLinearApproximation& jointTorquesDerivative() { return jointTorquesDerivative_; } + std::vector& collisionSpheresActive() { return collisionSpheresActive_; } + std::vector& collisionSpheresInOriginFrame() { return collisionSpheresInOriginFrame_; } + std::vector& collisionSpheresDerivative() { return collisionSpheresDerivative_; } +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/TorqueApproximation.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/TorqueApproximation.h new file mode 100644 index 000000000..50d62eb4e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/core/TorqueApproximation.h @@ -0,0 +1,28 @@ +// +// Created by rgrandia on 08.12.21. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Approximate joint torques with J(q)^T F, i.e. neglecting leg dynamics. + */ +template +joint_coordinate_s_t torqueApproximation(const joint_coordinate_s_t& jointPositions, + const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics); + +// Explicit instantiations +extern template joint_coordinate_s_t torqueApproximation(const joint_coordinate_s_t& jointPositions, + const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics); +extern template joint_coordinate_s_t torqueApproximation( + const joint_coordinate_s_t& jointPositions, const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics); + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CollisionAvoidanceCost.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CollisionAvoidanceCost.h new file mode 100644 index 000000000..bef8b2e85 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CollisionAvoidanceCost.h @@ -0,0 +1,37 @@ +// +// Created by rgrandia on 26.06.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Implements the collision avoidance penalty function for all collision spheres given by the precomputation. + * Uses a Gauss-Newton approximation to generate a positive semi-definite cost Hessian w.r.t. state. + */ +class CollisionAvoidanceCost final : public ocs2::StateCost { + public: + CollisionAvoidanceCost(ocs2::RelaxedBarrierPenalty::Config settings); + + CollisionAvoidanceCost* clone() const override; + + scalar_t getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + ScalarFunctionQuadraticApproximation getQuadraticApproximation(scalar_t time, const vector_t& state, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + private: + CollisionAvoidanceCost(const CollisionAvoidanceCost& rhs); + + std::unique_ptr penalty_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CostElements.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CostElements.h new file mode 100644 index 000000000..398ea2e4e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/CostElements.h @@ -0,0 +1,47 @@ +// +// Created by rgrandia on 19.07.22. +// + +#pragma once + +namespace switched_model { + +template +struct CostElements { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + vector3_s_t eulerXYZ{vector3_s_t::Zero()}; + vector3_s_t comPosition{vector3_s_t::Zero()}; + vector3_s_t comAngularVelocity{vector3_s_t::Zero()}; + vector3_s_t comLinearVelocity{vector3_s_t::Zero()}; + feet_array_t> jointPosition{constantFeetArray>(vector3_s_t::Zero())}; + feet_array_t> footPosition{constantFeetArray>(vector3_s_t::Zero())}; + feet_array_t> jointVelocity{constantFeetArray>(vector3_s_t::Zero())}; + feet_array_t> footVelocity{constantFeetArray>(vector3_s_t::Zero())}; + feet_array_t> contactForce{constantFeetArray>(vector3_s_t::Zero())}; + + static size_t Size() { + constexpr size_t baseTargets = 12; + constexpr size_t legTargets = 15; + return baseTargets + NUM_CONTACT_POINTS * legTargets; + } + + Eigen::Matrix asVector() const { + constexpr size_t baseTargets = 12; + constexpr size_t legTargets = 15; + constexpr size_t costVectorLength = baseTargets + NUM_CONTACT_POINTS * legTargets; + + Eigen::Matrix v(costVectorLength); + + // Base + v.head(baseTargets) << eulerXYZ, comPosition, comAngularVelocity, comLinearVelocity; + + // Legs + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + v.segment(baseTargets + leg * legTargets, legTargets) << jointPosition[leg], footPosition[leg], jointVelocity[leg], footVelocity[leg], + contactForce[leg]; + } + return v; + } +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FootPlacementCost.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FootPlacementCost.h new file mode 100644 index 000000000..1fe160f02 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FootPlacementCost.h @@ -0,0 +1,37 @@ +// +// Created by rgrandia on 26.06.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Implements footplacement penalty function for a provided polygon. + * Uses a Gauss-Newton approximation to generate a positive semi-definite cost Hessian w.r.t. state. + */ +class FootPlacementCost final : public ocs2::StateCost { + public: + FootPlacementCost(ocs2::RelaxedBarrierPenalty::Config settings); + + FootPlacementCost* clone() const override; + + scalar_t getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + ScalarFunctionQuadraticApproximation getQuadraticApproximation(scalar_t time, const vector_t& state, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + private: + FootPlacementCost(const FootPlacementCost& rhs); + + std::unique_ptr polygonPenalty_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FrictionConeCost.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FrictionConeCost.h new file mode 100644 index 000000000..25a6aacc1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/FrictionConeCost.h @@ -0,0 +1,43 @@ +// +// Created by rgrandia on 22.09.21. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/constraint/FrictionConeConstraint.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Implements the conversion of the friction cone constraint of all legs into a penalty cost. + * This is a specialization of the soft-constraint wrapping in ocs2. Here we can exploit the sparsity of the particular constraint. + */ +class FrictionConeCost final : public ocs2::StateInputCost { + public: + FrictionConeCost(friction_cone::Config config, const SwitchedModelModeScheduleManager& modeScheduleManager, + std::unique_ptr penaltyFunction); + + FrictionConeCost* clone() const override; + + bool isActive(scalar_t time) const override; + + scalar_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + ScalarFunctionQuadraticApproximation getQuadraticApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + private: + FrictionConeCost(const FrictionConeCost& rhs); + + friction_cone::Config config_; + const SwitchedModelModeScheduleManager* modeScheduleManager_; + std::unique_ptr penalty_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h new file mode 100644 index 000000000..3ff21d25e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h @@ -0,0 +1,40 @@ +// +// Created by rgrandia on 26.07.21. +// + +#pragma once + +#include + +#include + +namespace switched_model { +/** + * Linear inequality constraint in task space: A * f(x) + b >= 0 + * h(x) = A * f(x) + b + * together with the penalty function to apply to this constraint + */ +struct LinearStateInequalitySoftConstraint { + Eigen::Matrix A; + vector_t h; + const ocs2::PenaltyBase* penalty; +}; + +/// Specialization where there is only 1 constraint +struct SingleLinearStateInequalitySoftConstraint { + Eigen::Matrix A; + scalar_t h; + const ocs2::PenaltyBase* penalty; +}; + +scalar_t getValue(const LinearStateInequalitySoftConstraint& constraints, const vector_t& f); + +scalar_t getValue(const SingleLinearStateInequalitySoftConstraint& constraints, const vector_t& f); + +ScalarFunctionQuadraticApproximation getQuadraticApproximation(const LinearStateInequalitySoftConstraint& constraints, const vector_t& f, + const matrix_t& dfdx); + +ScalarFunctionQuadraticApproximation getQuadraticApproximation(const SingleLinearStateInequalitySoftConstraint& constraint, + const vector_t& f, const matrix_t& dfdx); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingCost.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingCost.h new file mode 100644 index 000000000..4c5d40050 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingCost.h @@ -0,0 +1,66 @@ +// +// Created by rgrandia on 30.04.21. +// + +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/ComModelBase.h" +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/ModelSettings.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h" + +namespace switched_model { + +/** + * Defines a cost over tracking base and feet references + */ +class MotionTrackingCost final : public ocs2::StateInputCostGaussNewtonAd { + public: + /** + * Cost settings per motion target, weights are applied as: cost = sum_i {w_i * (target_i - ref_i)^2} + * Magic values set as default + */ + struct Weights { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + vector3_t eulerXYZ{100.0, 200.0, 200.0}; + vector3_t comPosition{1000.0, 1000.0, 1500.0}; + vector3_t comAngularVelocity{5.0, 10.0, 10.0}; + vector3_t comLinearVelocity{15.0, 15.0, 30.0}; + feet_array_t jointPosition = constantFeetArray(vector3_t(2.0, 2.0, 1.0)); + feet_array_t footPosition = constantFeetArray(vector3_t(60.0, 60.0, 60.0)); + feet_array_t jointVelocity = constantFeetArray(vector3_t(0.02, 0.02, 0.01)); + feet_array_t footVelocity = constantFeetArray(vector3_t(1.0, 1.0, 1.0)); + feet_array_t contactForce = constantFeetArray(vector3_t(0.001, 0.001, 0.001)); + }; + + using kinematic_model_t = KinematicsModelBase; + using ad_kinematic_model_t = KinematicsModelBase; + using com_model_t = ComModelBase; + using ad_com_model_t = ComModelBase; + + MotionTrackingCost(const Weights& settings, const ad_kinematic_model_t& adKinematicModel, const ModelSettings& modelSettings); + + ~MotionTrackingCost() override = default; + MotionTrackingCost* clone() const { return new MotionTrackingCost(*this); } + + ocs2::vector_t getParameters(ocs2::scalar_t time, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const override; + + protected: + MotionTrackingCost(const MotionTrackingCost& other); + + ocs2::ad_vector_t costVectorFunction(ocs2::ad_scalar_t time, const ocs2::ad_vector_t& state, const ocs2::ad_vector_t& input, + const ocs2::ad_vector_t& parameters) const override; + + private: + std::unique_ptr adKinematicModelPtr_; + ocs2::vector_t sqrtWeights_; + const ModelSettings& modelSettings_; +}; + +MotionTrackingCost::Weights loadWeightsFromFile(const std::string& filename, const std::string& fieldname, bool verbose = true); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingTerminalCost.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingTerminalCost.h new file mode 100644 index 000000000..5e3914843 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/MotionTrackingTerminalCost.h @@ -0,0 +1,37 @@ +// +// Created by rgrandia on 10.03.22. +// + +#pragma once + +#include + +#include "ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h" + +namespace switched_model { + +class MotionTrackingTerminalCost final : public ocs2::StateCost { + public: + explicit MotionTrackingTerminalCost(matrix_t Q); + + ~MotionTrackingTerminalCost() override = default; + MotionTrackingTerminalCost* clone() const override; + + /** Get cost term value */ + scalar_t getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const; + + /** Get cost term quadratic approximation */ + ScalarFunctionQuadraticApproximation getQuadraticApproximation(scalar_t time, const vector_t& state, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const; + + private: + MotionTrackingTerminalCost(const MotionTrackingTerminalCost& other); + + vector_t getStateDeviation(const vector_t& state, const ocs2::PreComputation& preComputation) const; + + matrix_t Q_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/TorqueLimitsSoftConstraint.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/TorqueLimitsSoftConstraint.h new file mode 100644 index 000000000..805722854 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/cost/TorqueLimitsSoftConstraint.h @@ -0,0 +1,57 @@ +// +// Created by rgrandia on 26.07.21. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Implements the a penalty cost to keep the joints within upper and lower bounds. Unbounded joints are specified through a high numeric + * value e.g. +-1e30: + * + * -torqueLimits(j) < torque(j) < torqueLimits(j), for all joints j + * + * Implementing this penalty directly as a cost allows us to take advantage of the sparsity of these constraints that target + * individual entries of the state with a double sided penalty. + */ +class TorqueLimitsSoftConstraint final : public ocs2::StateInputCost { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** + * + * @param torqueLimits : joint torque limits + * @param settings : Settings for the penalty function. + * @param nominalState : nominal state where cost will be zero + * @param nominalInput : nominal input where cost will be zero + */ + TorqueLimitsSoftConstraint(const joint_coordinate_t& torqueLimits, ocs2::RelaxedBarrierPenalty::Config settings, + const joint_coordinate_t& nominalTorques); + + TorqueLimitsSoftConstraint* clone() const override { return new TorqueLimitsSoftConstraint(*this); } + + scalar_t getValue(scalar_t time, const vector_t& state, const vector_t& input, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + ScalarFunctionQuadraticApproximation getQuadraticApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const override; + + scalar_t getValue(const joint_coordinate_t& jointTorques) const; + ScalarFunctionQuadraticApproximation getQuadraticApproximation(const VectorFunctionLinearApproximation& jointTorquesDerivative) const; + + private: + TorqueLimitsSoftConstraint(const TorqueLimitsSoftConstraint& rhs); + + std::unique_ptr jointTorquePenalty_; + joint_coordinate_t torqueLimits_; + scalar_t offset_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h new file mode 100644 index 000000000..35be3c306 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h @@ -0,0 +1,41 @@ +// +// Created by rgrandia on 04.06.21. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Parameters of the system dynamics (constant over the MPC horizon) + */ +template +struct ComKinoSystemDynamicsParameters { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + //! External forces on the base, expressed in the origin frame + vector3_s_t externalForceInOrigin = vector3_s_t::Zero(); + //! External torques on the base, expressed in the base frame + vector3_s_t externalTorqueInBase = vector3_s_t::Zero(); + + /** + * Provides the number of parameters in this struct. Needs to be fixed before model generation and stay constant afterwards. + */ + static size_t getNumParameters() { return 6; }; + + /** Construct with default values */ + ComKinoSystemDynamicsParameters() = default; + + /** Construct from vector */ + explicit ComKinoSystemDynamicsParameters(const Eigen::Matrix& parameterVector); + + /** Flatten to a vector */ + Eigen::Matrix asVector() const; +}; + +//! Explicit instantiations +extern template class ComKinoSystemDynamicsParameters; +extern template class ComKinoSystemDynamicsParameters; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoSystemDynamicsAd.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoSystemDynamicsAd.h new file mode 100644 index 000000000..399423579 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/dynamics/ComKinoSystemDynamicsAd.h @@ -0,0 +1,67 @@ +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/ComModelBase.h" +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/ModelSettings.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h" +#include "ocs2_switched_model_interface/logic/DynamicsParametersSynchronizedModule.h" +#include "ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h" + +namespace switched_model { + +class ComKinoSystemDynamicsAd : public ocs2::SystemDynamicsBaseAD { + public: + using Base = ocs2::SystemDynamicsBaseAD; + + using ad_com_model_t = ComModelBase; + using ad_kinematic_model_t = KinematicsModelBase; + using parameters_t = ComKinoSystemDynamicsParameters; + using ad_parameters_t = ComKinoSystemDynamicsParameters; + + explicit ComKinoSystemDynamicsAd(const ad_kinematic_model_t& adKinematicModel, const ad_com_model_t& adComModel, + const DynamicsParametersSynchronizedModule& dynamicsParametersModule, ModelSettings settings); + + ComKinoSystemDynamicsAd(const ComKinoSystemDynamicsAd& rhs); + + ~ComKinoSystemDynamicsAd() override = default; + + ComKinoSystemDynamicsAd* clone() const override; + + ocs2::ad_vector_t systemFlowMap(ocs2::ad_scalar_t time, const ocs2::ad_vector_t& state, const ocs2::ad_vector_t& input, + const ocs2::ad_vector_t& parameters) const override; + + ocs2::vector_t getFlowMapParameters(scalar_t time, const ocs2::PreComputation& /* preComputation */) const override { + return dynamicsParametersModulePtr_->getActiveDynamicsParameters().asVector(); + } + + size_t getNumFlowMapParameters() const override { return parameters_t::getNumParameters(); } + + template + static com_state_s_t computeComStateDerivative( + const ComModelBase& comModel, const KinematicsModelBase& kinematicsModel, + const comkino_state_s_t& comKinoState, const comkino_input_s_t& comKinoInput, + const ComKinoSystemDynamicsParameters& parameters = ComKinoSystemDynamicsParameters()); + + private: + std::unique_ptr adKinematicModelPtr_; + std::unique_ptr adComModelPtr_; + const DynamicsParametersSynchronizedModule* dynamicsParametersModulePtr_; + ModelSettings settings_; +}; + +//! Explicit instantiations of computeComStateDerivative +extern template com_state_t ComKinoSystemDynamicsAd::computeComStateDerivative(const ComModelBase& comModel, + const KinematicsModelBase& kinematicsModel, + const comkino_state_t& comKinoState, + const comkino_input_t& comKinoInput, + const parameters_t& parameters); +extern template com_state_ad_t ComKinoSystemDynamicsAd::computeComStateDerivative(const ComModelBase& comModel, + const KinematicsModelBase& kinematicsModel, + const comkino_state_ad_t& comKinoState, + const comkino_input_ad_t& comKinoInput, + const ad_parameters_t& parameters); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/CubicSpline.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/CubicSpline.h new file mode 100644 index 000000000..741f76585 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/CubicSpline.h @@ -0,0 +1,52 @@ +/* + * CubicSpline.h + * + * Created on: Apr 30, 2017 + * Author: farbod + */ + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +class CubicSpline { + public: + struct Node { + scalar_t time; + scalar_t position; + scalar_t velocity; + }; + + CubicSpline(Node start, Node end); + + scalar_t position(scalar_t time) const; + + scalar_t velocity(scalar_t time) const; + + scalar_t acceleration(scalar_t time) const; + + scalar_t startTimeDerivative(scalar_t t) const; + + scalar_t finalTimeDerivative(scalar_t t) const; + + private: + scalar_t normalizedTime(scalar_t t) const; + + scalar_t t0_; + scalar_t t1_; + scalar_t dt_; + + scalar_t c0_; + scalar_t c1_; + scalar_t c2_; + scalar_t c3_; + + scalar_t dc0_; // derivative w.r.t. dt_ + scalar_t dc1_; // derivative w.r.t. dt_ + scalar_t dc2_; // derivative w.r.t. dt_ + scalar_t dc3_; // derivative w.r.t. dt_ +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/FootPhase.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/FootPhase.h new file mode 100644 index 000000000..c52d8acbf --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/FootPhase.h @@ -0,0 +1,181 @@ +// +// Created by rgrandia on 24.04.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/foot_planner/SwingSpline3d.h" +#include "ocs2_switched_model_interface/terrain/ConvexTerrain.h" +#include "ocs2_switched_model_interface/terrain/TerrainModel.h" +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +/** + * Linear inequality constraint A_p * p_world + b >= 0 + */ +struct FootTangentialConstraintMatrix { + Eigen::Matrix A; + vector_t b; +}; + +FootTangentialConstraintMatrix tangentialConstraintsFromConvexTerrain(const ConvexTerrain& stanceTerrain, scalar_t margin); + +/** + * Base class for a planned foot phase : Stance or Swing. + */ +class FootPhase { + public: + FootPhase() = default; + virtual ~FootPhase() = default; + FootPhase(const FootPhase&) = delete; + FootPhase& operator=(const FootPhase&) = delete; + + /** Returns the contact flag for this phase. Stance phase: True, Swing phase: false */ + virtual bool contactFlag() const = 0; + + /** Returns the unit vector pointing in the normal direction */ + virtual vector3_t normalDirectionInWorldFrame(scalar_t time) const = 0; + + /** Nominal foothold location (upcoming for swinglegs) */ + virtual vector3_t nominalFootholdLocation() const = 0; + + /** Convex terrain that constrains the foot placement. (null for swinglegs) */ + virtual const ConvexTerrain* nominalFootholdConstraint() const { return nullptr; }; + + /** Foot reference position in world frame */ + virtual vector3_t getPositionInWorld(scalar_t time) const = 0; + + /** Foot reference velocity in world frame */ + virtual vector3_t getVelocityInWorld(scalar_t time) const = 0; + + /** Foot reference acceleration in world frame */ + virtual vector3_t getAccelerationInWorld(scalar_t time) const = 0; + + /** Returns the position inequality constraints formulated in the tangential direction */ + virtual const FootTangentialConstraintMatrix* getFootTangentialConstraintInWorldFrame() const { return nullptr; }; + + virtual scalar_t getMinimumFootClearance(scalar_t time) const { return 0.0; }; +}; + +/** + * Encodes a planned stance phase on a terrain plane. + * The normal constraint makes the foot converge to the terrain plane when positionGain > 0.0 + */ +class StancePhase final : public FootPhase { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + explicit StancePhase(ConvexTerrain stanceTerrain, scalar_t terrainMargin = 0.0); + ~StancePhase() override = default; + + bool contactFlag() const override { return true; }; + vector3_t normalDirectionInWorldFrame(scalar_t time) const override; + vector3_t nominalFootholdLocation() const override; + const ConvexTerrain* nominalFootholdConstraint() const override; + vector3_t getPositionInWorld(scalar_t time) const override; + vector3_t getVelocityInWorld(scalar_t time) const override; + vector3_t getAccelerationInWorld(scalar_t time) const override; + const FootTangentialConstraintMatrix* getFootTangentialConstraintInWorldFrame() const override; + + private: + ConvexTerrain stanceTerrain_; + const vector3_t nominalFootholdLocation_; + const vector3_t surfaceNormalInWorldFrame_; + const FootTangentialConstraintMatrix footTangentialConstraint_; +}; + +/** + * Encodes a swing trajectory between two terrain planes. + * A spline based swing motion is designed in both liftoff and target plane. + */ +class SwingPhase final : public FootPhase { + public: + struct SwingEvent { + scalar_t time; + scalar_t velocity; + const TerrainPlane* terrainPlane; + }; + + struct SwingProfile { + struct Node { + /// Time progress in the swing phase in [0, 1] + scalar_t phase = 0.5; + /// Swing height in normal direction + scalar_t swingHeight = 0.1; + /// Velocity in normal direction + scalar_t normalVelocity = 0.0; + /// Swing progress in tangential direction in [0, 1] + scalar_t tangentialProgress = 0.5; + /// Tangantial velocity as a factor of the average velocity. The tangential velocity will be: velocityFactor * swingdistance / dt + scalar_t tangentialVelocityFactor = 1.0; + }; + + /// Height / velocity profile + std::vector nodes; + /// Desired SDF clearance at the middle of the swing phase. + scalar_t sdfMidswingMargin = 0.0; + /// Desired SDF clearance at liftoff and touchdown. Slight negative margin allows a bit of ground penetration + scalar_t sdfStartEndMargin = -0.02; + /// Limits the amount of additional swing height from terrain adaptation + scalar_t maxSwingHeightAdaptation = 0.3; + }; + + /** + * Construct a swing phase: + * Creates a 3D swing reference motion + * Creates a 1D clearance profile for SDF based obstacle avoidance. + * @param liftOff : Information about the liftoff event. + * @param touchDown : Information about the touchdown event. + * @param SwingProfile : Settings to shape the swing profile + * @param terrainModel : (optional) Pointer to the terrain model. Terrain model should be kept alive externall as long as the swingphase + * object exists. Will extract SDF and obstacle information from the terrain. + */ + SwingPhase(SwingEvent liftOff, SwingEvent touchDown, const SwingProfile& swingProfile, const TerrainModel* terrainModel = nullptr); + ~SwingPhase() override = default; + + bool contactFlag() const override { return false; }; + vector3_t normalDirectionInWorldFrame(scalar_t time) const override; + vector3_t nominalFootholdLocation() const override; + vector3_t getPositionInWorld(scalar_t time) const override; + vector3_t getVelocityInWorld(scalar_t time) const override; + vector3_t getAccelerationInWorld(scalar_t time) const override; + scalar_t getMinimumFootClearance(scalar_t time) const override; + + private: + void setFullSwing(const SwingProfile& swingProfile, const TerrainModel* terrainModel); + void setHalveSwing(const SwingProfile& swingProfile, const TerrainModel* terrainModel); + + scalar_t getScaling(scalar_t time) const; + + SwingEvent liftOff_; + SwingEvent touchDown_; + + std::unique_ptr motion_; + std::unique_ptr terrainClearanceMotion_; +}; + +/** + * Encodes a swing trajectory derived directly from the reference motion + */ +class ExternalSwingPhase final : public FootPhase { + public: + ExternalSwingPhase(std::vector timeTrajectory, std::vector positionTrajectory, + std::vector velocityTrajectory); + ~ExternalSwingPhase() override = default; + + bool contactFlag() const override { return false; }; + vector3_t normalDirectionInWorldFrame(scalar_t time) const override { return {0.0, 0.0, 1.0}; } + vector3_t nominalFootholdLocation() const override { return positionTrajectory_.back(); } + vector3_t getPositionInWorld(scalar_t time) const override; + vector3_t getVelocityInWorld(scalar_t time) const override; + vector3_t getAccelerationInWorld(scalar_t time) const override { return vector3_t::Zero(); } + scalar_t getMinimumFootClearance(scalar_t time) const override { return 0.0; } + + private: + std::vector timeTrajectory_; + std::vector positionTrajectory_; + std::vector velocityTrajectory_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/KinematicFootPlacementPenalty.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/KinematicFootPlacementPenalty.h new file mode 100644 index 000000000..6d9a1dc9f --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/KinematicFootPlacementPenalty.h @@ -0,0 +1,45 @@ +// +// Created by rgrandia on 17.02.22. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Configuration for the kinematic penalty taking into account: + * - maximum leg extension + * - the hip not rotation inwards w.r.t gravity. Prevents placing the foot too far below the body. + */ +struct ApproximateKinematicsConfig { + scalar_t maxLegExtension; + scalar_t kinematicPenaltyWeight; +}; + +/** + * Compute the kinematic foot placement penalty. + * + * @param footPositionInHip : relative foot position in the hip frame + * @param gravityNormalInHip : gravity vector expressed in the hip frame + * @param config : settings + * @return positive kinematic penalty value. + */ +scalar_t computeKinematicPenalty(const vector3_t& footPositionInHip, const vector3_t& gravityNormalInHip, + const ApproximateKinematicsConfig& config); + +/** + * Compute the kinematic foot placement penalty. + * + * @param footPositionInWorld : foot position in the world frame + * @param hipPositionInWorld : hip position in the world frame + * @param rotationHipToWorld : rotation hip to world. Rotation around the positive x-axis of the hip frame should make the leg rotate + * outwards. + * @param config : settings + * @return positive kinematic penalty value. + */ +scalar_t computeKinematicPenalty(const vector3_t& footPositionInWorld, const vector3_t& hipPositionInWorld, + const matrix3_t& rotationHipToWorld, const ApproximateKinematicsConfig& config); + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/QuinticSplineSwing.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/QuinticSplineSwing.h new file mode 100644 index 000000000..53a83d2aa --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/QuinticSplineSwing.h @@ -0,0 +1,129 @@ +// +// Created by rgrandia on 21.01.21. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +struct SwingNode { + scalar_t time; + scalar_t position; + scalar_t velocity; +}; + +/** + * Implements a quintic polynomial: + * y = c_5 * tau^5 + ... + c_1 * tau + c_0, + * where tau = (t - t0) / dt + */ +class QuinticSpline { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** Default constructor creates a flat spline, y(t) = 0.0 for t in [-1e30, 1e30]*/ + QuinticSpline() : c_(vector6_t::Zero()), t0_(-1e30), dt_(2e30) {} + + /** + * Constructs a quintic spline. See class description for the definition. + * + * @param coefficients : spline coefficients [c_5, ..., c_0] + * @param t0 : start time of the spline. + * @param dt : time normalization factor. The normalized time is 1.0 at t = t0 + dt + */ + QuinticSpline(const vector6_t& coefficients, scalar_t t0, scalar_t dt) : c_(coefficients), t0_(t0), dt_(dt) {} + + /** returns y(t) */ + scalar_t position(scalar_t time) const; + + /** returns dy/dt(t) */ + scalar_t velocity(scalar_t time) const; + + /** returns d2y/dt2(t) */ + scalar_t acceleration(scalar_t time) const; + + /** returns d3y/dt3(t) */ + scalar_t jerk(scalar_t time) const; + + private: + scalar_t normalizedTime(scalar_t t) const; + + /// Coefficients [c_5, ..., c_0] for normalized time + vector6_t c_; + + /// Start time of the spline + scalar_t t0_; + + /// Spline time normalization + scalar_t dt_; +}; + +/** + * Implements a swing trajectory based on (at least 2) quintic splines + * The trajectory is made with the following conditions + * start: + * position = given + * velocity = given + * acceleration = 0.0 + * Mid (can be multiple): + * position = given & continuous + * velocity = given & continuous + * acceleration = continuous + * jerk = continuous + * End: + * position = given + * velocity = given + * acceleration = 0.0 + */ +class QuinticSwing { + public: + /** + * trajectory of constant zero + */ + QuinticSwing(); + + /** + * Construct a swing trajectory with given boundary conditions + * + * @param start : starting time and boundary conditions + * @param midHeight : desired height at the middle of the trajectory. Assumes zero velocity. + * @param end : ending time and boundary conditions + */ + QuinticSwing(const SwingNode& start, scalar_t midHeight, const SwingNode& end); + + /** + * Construct a swing trajectory with given boundary conditions + * + * @param start : starting time and boundary conditions + * @param mid : waypoint time, position, and velocity. Time must be between start and end. + * @param end : ending time and boundary conditions + */ + QuinticSwing(const SwingNode& start, const SwingNode& mid, const SwingNode& end); + + /** + * Construct a swing trajectory with through the given nodes. At least 3 need to be passed (such that there are at least 2 splines) + * + * @param nodes : each node is a waypoint in time, position, and velocity. Vector needs to be sorted in time. + */ + explicit QuinticSwing(const std::vector& nodes); + + /** returns z(t) */ + scalar_t position(scalar_t time) const; + + /** returns dz/dt(t) */ + scalar_t velocity(scalar_t time) const; + + /** returns d2z/dt2(t) */ + scalar_t acceleration(scalar_t time) const; + + /** returns d3z/dt3(t) */ + scalar_t jerk(scalar_t time) const; + + private: + std::vector nodeTimes; + std::vector splines; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SplineCpg.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SplineCpg.h new file mode 100644 index 000000000..a486d4cae --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SplineCpg.h @@ -0,0 +1,36 @@ +/* + * SplineCPG.h + * + * Created on: Apr 30, 2017 + * Author: farbod + */ + +#pragma once + +#include "ocs2_switched_model_interface/foot_planner/CubicSpline.h" + +namespace switched_model { + +class SplineCpg { + public: + SplineCpg(CubicSpline::Node liftOff, scalar_t midHeight, CubicSpline::Node touchDown); + + SplineCpg(CubicSpline::Node liftOff, CubicSpline::Node midNode, CubicSpline::Node touchDown); + + scalar_t position(scalar_t time) const; + + scalar_t velocity(scalar_t time) const; + + scalar_t acceleration(scalar_t time) const; + + scalar_t startTimeDerivative(scalar_t time) const; + + scalar_t finalTimeDerivative(scalar_t time) const; + + private: + scalar_t midTime_; + CubicSpline leftSpline_; + CubicSpline rightSpline_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingSpline3d.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingSpline3d.h new file mode 100644 index 000000000..2c0371d65 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingSpline3d.h @@ -0,0 +1,56 @@ +// +// Created by rgrandia on 03.08.21. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +#include "ocs2_switched_model_interface/foot_planner/QuinticSplineSwing.h" + +namespace switched_model { + +struct SwingNode3d { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + scalar_t time; + vector3_t position; + vector3_t velocity; +}; + +class SwingSpline3d { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** + * Construct a swing trajectory with given boundary conditions + * + * @param start : starting time and boundary conditions + * @param mid : waypoint time, position, and velocity. Time must be between start and end. + * @param end : ending time and boundary conditions + */ + SwingSpline3d(const SwingNode3d& start, const SwingNode3d& mid, const SwingNode3d& end); + + /** + * Construct a swing trajectory through the provided nodes (at least 3) + */ + explicit SwingSpline3d(const std::vector& nodes); + + /** returns p(t) */ + vector3_t position(scalar_t time) const; + + /** returns dp/dt(t) */ + vector3_t velocity(scalar_t time) const; + + /** returns d2p/dt2(t) */ + vector3_t acceleration(scalar_t time) const; + + /** returns d3p/dt3(t) */ + vector3_t jerk(scalar_t time) const; + + private: + QuinticSwing x_; + QuinticSwing y_; + QuinticSwing z_; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h new file mode 100644 index 000000000..672b9dbc9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h @@ -0,0 +1,132 @@ +// +// Created by rgrandia on 13.03.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/InverseKinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/foot_planner/FootPhase.h" +#include "ocs2_switched_model_interface/logic/SingleLegLogic.h" +#include "ocs2_switched_model_interface/terrain/ConvexTerrain.h" +#include "ocs2_switched_model_interface/terrain/TerrainModel.h" +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +struct SwingTrajectoryPlannerSettings { + scalar_t liftOffVelocity = 0.0; + scalar_t touchDownVelocity = 0.0; + scalar_t swingHeight = 0.1; + + scalar_t errorGain = 0.0; // proportional gain for returning to the planned swing trajectory. 10-90%-rise_time ~= 2.2 / errorGain + // alternatively can be measured as (velocity feedback) / (tracking error) ([m/s] / [m]) + scalar_t swingTimeScale = 0.15; // swing phases shorter than this time will be scaled down in height and velocity + scalar_t sdfMidswingMargin = 0.0; // desired sdf based clearance in the middle of the swing phase [m] + scalar_t terrainMargin = 0.0; // shrinkage of the convex terrain constrains in [m] + + scalar_t previousFootholdFactor = 0.0; // factor in [0, 1] with which to take previous foothold into account. + scalar_t previousFootholdDeadzone = 0.0; // previous foothold is taken if the new reference is within this threshold. [m] + scalar_t previousFootholdTimeDeadzone = 0.0; // previous foothold is taken if the contact phase is starting withing this time. [s] + scalar_t invertedPendulumHeight = 0.5; // height used for the inverted pendulum foothold adjustment + + scalar_t nominalLegExtension = 0.55; // Leg extension beyond this length [m] will be penalized in terrain selection + scalar_t legOverExtensionPenalty = 5.0; // Weight of the leg overextension penalty + + scalar_t referenceExtensionAfterHorizon = 1.0; // base and foot references generated for this amount of seconds after the horizon ends. + scalar_t maximumReferenceSampleTime = 0.05; // if the reference trajectory has samples with longer intervals, it will be subsampled. + + bool swingTrajectoryFromReference = false; // Flag to take the swing trajectory from the reference trajectory +}; + +SwingTrajectoryPlannerSettings loadSwingTrajectorySettings(const std::string& filename, bool verbose = true); + +using inverse_kinematics_function_t = std::function; + +class SwingTrajectoryPlanner { + public: + SwingTrajectoryPlanner(SwingTrajectoryPlannerSettings settings, const KinematicsModelBase& kinematicsModel, + const InverseKinematicsModelBase* inverseKinematicsModelPtr); + + // Update terrain model + void updateTerrain(std::unique_ptr terrainModel); + + // Access the SDF of the current terrain model + const SignedDistanceField* getSignedDistanceField() const; + + // Main interface preparing all swing trajectories in cartesian space (called by reference manager) + void updateSwingMotions(scalar_t initTime, scalar_t finalTime, const comkino_state_t& currentState, + const ocs2::TargetTrajectories& targetTrajectories, const ocs2::ModeSchedule& modeSchedule); + + // Main access method for the generated cartesian references. + const FootPhase& getFootPhase(size_t leg, scalar_t time) const; + + // Accessed by precomputation to generate the motion reference, used in the controller to visualize the generated references + const ocs2::TargetTrajectories& getTargetTrajectories() const { return targetTrajectories_; } + + // Accessed by the controller for visualization + std::vector getNominalFootholds(size_t leg) const { return nominalFootholdsPerLeg_[leg]; } + + // Accessed by the controller for visualization + std::vector getHeuristicFootholds(size_t leg) const { return heuristicFootholdsPerLeg_[leg]; } + + // Read settings + const SwingTrajectoryPlannerSettings& settings() const { return settings_; } + + private: + void updateLastContact(int leg, scalar_t expectedLiftOff, const vector3_t& currentFootPosition, const TerrainModel& terrainModel); + + std::pair, std::vector>> generateSwingTrajectories( + int leg, const std::vector& contactTimings, scalar_t finalTime) const; + + std::pair, std::vector>> extractSwingTrajectoriesFromReference( + int leg, const std::vector& contactTimings, scalar_t finalTime) const; + + std::vector selectHeuristicFootholds(int leg, const std::vector& contactTimings, + const ocs2::TargetTrajectories& targetTrajectories, scalar_t initTime, + const comkino_state_t& currentState, scalar_t finalTime) const; + + std::vector selectNominalFootholdTerrain(int leg, const std::vector& contactTimings, + const std::vector& heuristicFootholds, + const ocs2::TargetTrajectories& targetTrajectories, scalar_t initTime, + const comkino_state_t& currentState, scalar_t finalTime, + const TerrainModel& terrainModel) const; + + void applySwingMotionScaling(SwingPhase::SwingEvent& liftOff, SwingPhase::SwingEvent& touchDown, + SwingPhase::SwingProfile& swingProfile) const; + + void subsampleReferenceTrajectory(const ocs2::TargetTrajectories& targetTrajectories, scalar_t initTime, scalar_t finalTime); + + // Apply IK to cartesian swing motion to update joint references + void adaptJointReferencesWithInverseKinematics(scalar_t finalTime); + + std::unique_ptr extractExternalSwingPhase(int leg, scalar_t liftOffTime, scalar_t touchDownTime) const; + + SwingPhase::SwingProfile getDefaultSwingProfile() const; + + scalar_t getContactEndTime(const ContactTiming& contactPhase, scalar_t finalTime) const; + + const FootPhase* getFootPhaseIfInContact(size_t leg, scalar_t time) const; + + vector3_t filterFoothold(const vector3_t& newFoothold, const vector3_t& previousFoothold) const; + + SwingTrajectoryPlannerSettings settings_; + std::unique_ptr> kinematicsModel_; + std::unique_ptr inverseKinematicsModelPtr_; + + feet_array_t> lastContacts_; + feet_array_t>> feetNormalTrajectories_; + feet_array_t> feetNormalTrajectoriesEvents_; + + feet_array_t> nominalFootholdsPerLeg_; + feet_array_t> heuristicFootholdsPerLeg_; + std::unique_ptr terrainModel_; + + ocs2::TargetTrajectories targetTrajectories_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/initialization/ComKinoInitializer.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/initialization/ComKinoInitializer.h new file mode 100644 index 000000000..c317c07cf --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/initialization/ComKinoInitializer.h @@ -0,0 +1,31 @@ +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/ComModelBase.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h" + +namespace switched_model { + +class ComKinoInitializer : public ocs2::Initializer { + public: + using com_model_t = ComModelBase; + + ComKinoInitializer(const com_model_t& comModel, const SwitchedModelModeScheduleManager& modeScheduleManager); + + ~ComKinoInitializer() override = default; + + ComKinoInitializer* clone() const override; + + void compute(scalar_t time, const vector_t& state, scalar_t nextTime, vector_t& input, vector_t& nextState) override; + + protected: + ComKinoInitializer(const ComKinoInitializer& rhs); + + private: + std::unique_ptr comModelPtr_; + const SwitchedModelModeScheduleManager* modeScheduleManagerPtr_; +}; + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/DynamicsParametersSynchronizedModule.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/DynamicsParametersSynchronizedModule.h new file mode 100644 index 000000000..92be8f9ff --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/DynamicsParametersSynchronizedModule.h @@ -0,0 +1,33 @@ +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h" + +namespace switched_model { + +class DynamicsParametersSynchronizedModule : public ocs2::SolverSynchronizedModule { + public: + DynamicsParametersSynchronizedModule(); + + void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& initState, + const ocs2::ReferenceManagerInterface& referenceManager) override; + + void postSolverRun(const ocs2::PrimalSolution& primalSolution) override{}; + + // Write-able access to dynamics parameters + ocs2::Synchronized>& getDynamicsParameters() { return newDynamicsParameters_; } + const ocs2::Synchronized>& getDynamicsParameters() const { return newDynamicsParameters_; } + + // Read-only access to active dynamics parameters (Not thread safe while MPC is running!) + const ComKinoSystemDynamicsParameters& getActiveDynamicsParameters() const { return activeDynamicsParameters_; } + + private: + //! Parameters active in the current MPC optimization + ComKinoSystemDynamicsParameters activeDynamicsParameters_; + //! Updated externally, becomes active in next MPC iteration + ocs2::Synchronized> newDynamicsParameters_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/Gait.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/Gait.h new file mode 100644 index 000000000..643a4b37d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/Gait.h @@ -0,0 +1,61 @@ +// +// Created by rgrandia on 15.03.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * A gait is a periodic mode schedule parameterized by a "phase" variable. + * + * The eventPhases only indicate switches of modes, i.e. phase = 0 and phase = 1 are not part of the eventPhases. + * The number of modes is therefore number of phases + 1 + * + * The conversion to time is regulated by a duration + */ +struct Gait { + /** time for one gait cycle*/ + scalar_t duration; + /** points in (0.0, 1.0) along the gait cycle where the contact mode changes, size N-1 */ + std::vector eventPhases; + /** sequence of contact modes, size: N */ + std::vector modeSequence; +}; + +/** + * isValidGait checks the following properties + * - positive duration + * - eventPhases are all in (0.0, 1.0) + * - eventPhases are sorted + * - the size of the modeSequences is 1 more than the eventPhases. + */ +bool isValidGait(const Gait& gait); + +/** Check is if the phase is in [0.0, 1.0) */ +bool isValidPhase(scalar_t phase); + +/** Wraps a phase to [0.0, 1.0) */ +scalar_t wrapPhase(scalar_t phase); + +/** The modes are selected with a closed-open interval: [ ) */ +int getModeIndexFromPhase(scalar_t phase, const Gait& gait); + +/** Gets the active mode from the phase variable */ +size_t getModeFromPhase(scalar_t phase, const Gait& gait); + +/** Returns the time left in the gait based on the phase variable */ +scalar_t timeLeftInGait(scalar_t phase, const Gait& gait); + +/** Returns the time left in the current based on the phase variable */ +scalar_t timeLeftInMode(scalar_t phase, const Gait& gait); + +/** Print gait */ +std::ostream& operator<<(std::ostream& stream, const Gait& gait); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitAdaptation.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitAdaptation.h new file mode 100644 index 000000000..d206375ee --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitAdaptation.h @@ -0,0 +1,72 @@ +/* + * GaitAdaptation.h + * + * Created on: Jun 4, 2020 + * Author: Marko Bjelonic + */ + +#pragma once + +#include +#include + +namespace switched_model { + +struct GaitAdaptationSettings { + scalar_t earlyTouchDownTimeWindow = 0.1; +}; + +class GaitAdaptation { + public: + GaitAdaptation(const GaitAdaptationSettings& settings, const contact_flag_t& measuredContactFlags); + + void advance(GaitSchedule& gaitSchedule, const contact_flag_t& measuredContactFlags, scalar_t dt); + + private: + /// Update measured liftoff information + void advanceLiftoffTracking(const contact_flag_t& desiredContactFlags, const contact_flag_t& measuredContactFlags); + + /// Update next touchdown and liftoff information + void advanceSwingEvents(const GaitSchedule& gaitSchedule); + + enum class ScheduledAdaptation { None, EarlyContact }; + static bool isEarlyContact(ScheduledAdaptation adaptation) { return adaptation == ScheduledAdaptation::EarlyContact; } + + /** + * Determines the gait adaptation strategy per leg. + * @param desiredContactFlags : true = this leg was planned to be in contact, false = this was planned to be in swing. + * @param measuredContactFlags : true = this leg is measured to be in contact, false = this leg is measured to be in swing. + * @return Scheduled adaptation enum per leg. + */ + feet_array_t advanceLegStrategies(const contact_flag_t& desiredContactFlags, + const contact_flag_t& measuredContactFlags); + ScheduledAdaptation desiredContactMeasuredContact(size_t leg); + ScheduledAdaptation desiredContactMeasuredMotion(size_t leg); + ScheduledAdaptation desiredMotionMeasuredContact(size_t leg); + ScheduledAdaptation desiredMotionMeasuredMotion(size_t leg); + + void applyAdaptation(GaitSchedule& gaitSchedule, const feet_array_t& scheduledAdaptations); + + /// Planned event timing relative to the current time (before applying the gait adaptation). + feet_array_t timeUntilNextTouchDownPerLeg_; + feet_array_t timeUntilNextLiftOffPerLeg_; + + feet_array_t hasLiftedSinceLastContact_; + + GaitAdaptationSettings settings_; +}; + +/** + * Removes the first swing phase for all legs flagged with earlyTouchdown + */ +std::function +earlyTouchDownAdaptation(const switched_model::feet_array_t& earlyTouchDownPerLeg); + +/** Gets the mode index of the next phase with the specified contact state, returns the size of the modesequence of no such contact state + * was found */ +int getModeIndexOfNextContactStateOfLeg(bool contact, int startModeIdx, size_t leg, const Gait& gait); + +/** Adapts the mode sequence between the two mode ids of a specific leg to be with the specified flag. */ +void setContactStateOfLegBetweenModes(bool contact, int startModeIdx, int lastModeIdx, size_t leg, Gait& gait); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitReceiver.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitReceiver.h new file mode 100644 index 000000000..060908fa8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitReceiver.h @@ -0,0 +1,50 @@ +// +// Created by rgrandia on 18.03.20. +// + +#pragma once + +#include + +#include + +#include +#include +#include + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/GaitSchedule.h" + +namespace switched_model { + +class GaitReceiver : public ocs2::SolverSynchronizedModule { + public: + GaitReceiver(ros::NodeHandle nodeHandle, ocs2::Synchronized& gaitSchedule, const std::string& robotName); + + void preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) override; + + void postSolverRun(const ocs2::PrimalSolution& primalSolution) override{}; + + private: + void mpcModeSequenceCallback(const ocs2_msgs::mode_schedule::ConstPtr& msg); + void mpcModeScheduledGaitCallback(const ocs2_msgs::mode_schedule::ConstPtr& msg); + void mpcGaitSequenceCallback(const ocs2_switched_model_msgs::scheduled_gait_sequenceConstPtr& msg); + + ros::Subscriber mpcModeSequenceSubscriber_; + ros::Subscriber mpcScheduledModeSequenceSubscriber_; + ros::Subscriber mpcGaitSequenceSubscriber_; + + ocs2::Synchronized* gaitSchedulePtr_; + + std::atomic_bool gaitUpdated_; + + std::mutex receivedGaitMutex_; // protects the setGaitAction_ variable + std::function + setGaitAction_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSchedule.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSchedule.h new file mode 100644 index 000000000..961ed76bc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSchedule.h @@ -0,0 +1,81 @@ +// +// Created by rgrandia on 15.03.20. +// + +#pragma once + +#include +#include + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/Gait.h" + +namespace switched_model { + +class GaitSchedule { + public: + using GaitSequence = std::vector; + GaitSchedule(scalar_t time, Gait gait); + + /** Advances the gait schedule to a specified time, the specified time must be increasing w.r.t. previous calls. */ + void advanceToTime(scalar_t time); + + /** Adds gaits after completing the current gait */ + void setNextGait(const Gait& gait); + + /** Adds sequence of gaits after completing the current gait */ + void setGaitSequenceAfterCurrentGait(const GaitSequence& gaitSequence); + + /** Adds a gait at a specified time. The gait originally active at that time is shrunk in duration to make the new gait fit. Gaits after + * that time are removed */ + void setGaitAtTime(const Gait& gait, scalar_t time); + + /** Adds schedule of gaits at a specified time. The gait originally active at that time is shrunk in duration to make the new gait fit. + * Gaits after that time are removed */ + void setGaitSequenceAtTime(const GaitSequence& gaitSequence, scalar_t time); + + /** Adds a gait at the first opportunity after the specified time. Does not adapt gait cycle durations */ + void setGaitAfterTime(const Gait& gait, scalar_t time); + + /** Adds a gait sequence at the first opportunity after the specified time. Does not adapt gait cycle durations */ + void setGaitSequenceAfterTime(const GaitSequence& gaitSequence, scalar_t time); + + /** Applies the provided function to the current gait. The function can adapt the current phase and gait. If the current gait is the last + * scheduled gait, it is repeated before adaptation */ + void adaptCurrentGait( + const std::function& gaitAdaptor); + + /** Gets the gaitSchedule as a mode schedule from the current time, and for the specified horizon */ + ocs2::ModeSchedule getModeSchedule(scalar_t timeHorizon) const; + + /** Gets the currently active gait */ + const Gait& getCurrentGait() const { return gaitSchedule_.front(); } + + /** Gets phase variable for the current gait */ + scalar_t getCurrentPhase() const { return phase_; } + + /** Gets time variable for the current gait */ + scalar_t getCurrentTime() const { return time_; } + + /** Gets the currently active mode */ + size_t getCurrentMode() const { return getModeFromPhase(getCurrentPhase(), getCurrentGait()); } + + /** Returns time until current gait ends a cycle */ + scalar_t timeLeftInCurrentGait() const { return timeLeftInGait(getCurrentPhase(), getCurrentGait()); } + + private: + /** Makes the implicit looping of the last gait explicit until the specified time */ + void rolloutGaitScheduleTillTime(scalar_t time); + + scalar_t time_; + scalar_t phase_; + std::deque gaitSchedule_; +}; + +bool isStandingDuringTimeHorizon(scalar_t timeHorizon, const GaitSchedule& gaitSchedule); + +bool isStanding(const GaitSchedule& gaitSchedule); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSwitching.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSwitching.h new file mode 100644 index 000000000..fd772bcee --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/GaitSwitching.h @@ -0,0 +1,86 @@ +// +// Created by rgrandia on 15.03.20. +// + +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/Gait.h" + +namespace switched_model { + +/** + * Selects the next gait from iterators. Repeating the final gait when the final gait is reached. + * @tparam GaitIt : Gait iterator + * @param currentGait : iterator pointing to the current gait + * @param pastTheEndGait : iterator pointing part the end of the last gait to be considered. (e.g. obtained from vector::end()) + * @return next gait in the sequence + */ +template +GaitIt nextGait(GaitIt currentGait, GaitIt pastTheEndGait) { + GaitIt nextGait = currentGait + 1; + if (nextGait == pastTheEndGait) { + return currentGait; + } else { + return nextGait; + } +} + +/** + * Recursively progresses to the next gait in a sequence while keeping track of the phase variable. + * When the final gait is reached, it is repeated as long as required by the specified dt. + * + * @tparam GaitIt : Gait iterator + * @param phase : phase variable in the current gait. + * @param dt : time to progress in the gait sequence + * @param currentGait : iterator pointing to the current gait + * @param pastTheEndGait : iterator pointing part the end of the last gait to be considered. (e.g. obtained from vector::end()) + * @return {phase in new gait, iterator to newly active gait. + */ +template +std::pair advancePhase(scalar_t phase, scalar_t dt, GaitIt currentGait, GaitIt pastTheEndGait) { + assert(isValidPhase(phase)); + assert(dt >= 0); + + // Phase change within current gait + scalar_t dphase = dt / currentGait->duration; + + if (phase + dphase < 1.0) { // Advance within current gait + phase += dphase; + return {phase, currentGait}; + } else { // Advance to next gait + const scalar_t dtRemaining = std::max(dt - timeLeftInGait(phase, *currentGait), 0.0); + const GaitIt nexGait = nextGait(currentGait, pastTheEndGait); + // Recurse by setting the phase to the beginning of the next phase + return advancePhase(0.0, dtRemaining, nexGait, pastTheEndGait); + } +} + +template +ocs2::ModeSchedule getModeSchedule(scalar_t phase, scalar_t t0, scalar_t timeHorizon, GaitIt currentGait, GaitIt pastTheEndGait) { + assert(isValidPhase(phase)); + + // Initialize with the current mode + std::vector evenTimes = {}; + std::vector modeSchedule = {getModeFromPhase(phase, *currentGait)}; + + const scalar_t tend = t0 + timeHorizon; + scalar_t t = t0; + while (t < tend) { + scalar_t dt = timeLeftInMode(phase, *currentGait); + t += dt; + if (t < tend) { // Next event is within horizon: Add the event time and advance the phase to that event + std::tie(phase, currentGait) = advancePhase(phase, dt, currentGait, pastTheEndGait); + size_t mode = getModeFromPhase(phase, *currentGait); + if (mode != modeSchedule.back()) { // Only add the mode if it is a switch w.r.t the last mode. + evenTimes.push_back(t); + modeSchedule.push_back(mode); + } + } + } + return {evenTimes, modeSchedule}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/ModeSequenceTemplate.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/ModeSequenceTemplate.h new file mode 100644 index 000000000..a1b20f67d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/ModeSequenceTemplate.h @@ -0,0 +1,104 @@ +#pragma once + +#include +#include + +#include + +#include + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/logic/Gait.h" + +namespace switched_model { + +/** + * ModeSequenceTemplate describes a periodic sequence of modes. It is defined by + * - switching times (size N+1), where the first time is 0, and the last time denotes the period of the cycle + * - modeSequence (size N), indicating the mode between the switching times. + */ +struct ModeSequenceTemplate { + /** + * Constructor for a ModeSequenceTemplate. The number of modes must be greater than zero (N > 0) + * @param [in] switchingTimesInput : switching times of size N + 1 + * @param [in] modeSequenceInput : mode sequence of size N + */ + ModeSequenceTemplate(std::vector switchingTimesInput, std::vector modeSequenceInput) + : switchingTimes(std::move(switchingTimesInput)), modeSequence(std::move(modeSequenceInput)) { + assert(!modeSequence.empty()); + assert(switchingTimes.size() == modeSequence.size() + 1); + } + + /** + * Defined as [t_0=0, t_1, .., t_n, t_(n+1)=T], where T is the overall duration + * of the template logic. t_1 to t_n are the event moments. + */ + std::vector switchingTimes; + + /** + * Defined as [sys_0, sys_n], are the switching systems IDs. Here sys_i is + * active in period [t_i, t_(i+1)] + */ + std::vector modeSequence; +}; + +/** Swap two modesequence templates */ +inline void swap(ModeSequenceTemplate& lh, ModeSequenceTemplate& rh) { + lh.switchingTimes.swap(rh.switchingTimes); + lh.modeSequence.swap(rh.modeSequence); +} + +/** Print the modesequence template */ +std::ostream& operator<<(std::ostream& stream, const ModeSequenceTemplate& modeSequenceTemplate); + +/** Convert mode sequence template to ROS message */ +ocs2_msgs::mode_schedule createModeSequenceTemplateMsg(const ModeSequenceTemplate& modeSequenceTemplate); + +/** Convert ROS message to mode sequence template */ +ModeSequenceTemplate readModeSequenceTemplateMsg(const ocs2_msgs::mode_schedule& modeScheduleMsg); + +/** Converts a mode sequence template to a gait */ +Gait toGait(const ModeSequenceTemplate& modeSequenceTemplate); + +/** + * Load a modesequence template from file. The template needs to be declared as: + * + * topicName + * { + * modeSequence + * { + * [0] mode0 + * [1] mode1 + * } + * switchingTimes + * { + * [0] 0.0 + * [1] t1 + * [2] T + * } + * } + */ +ModeSequenceTemplate loadModeSequenceTemplate(const std::string& filename, const std::string& topicName, bool verbose = true); + +/** + * Load a mode schedule template from file. The schedule needs to be declared as: + * + * topicName + * { + * modeSequence + * { + * [0] mode0 + * [1] mode1 + * [2] mode2 + * } + * eventTimes + * { + * [0] t0 + * [1] t1 + * } + * } + */ +ocs2::ModeSchedule loadModeSchedule(const std::string& filename, const std::string& topicName, bool verbose); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SingleLegLogic.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SingleLegLogic.h new file mode 100644 index 000000000..0bf51cbe4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SingleLegLogic.h @@ -0,0 +1,72 @@ +// +// Created by rgrandia on 27.04.20. +// + +#pragma once + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +struct ContactTiming { + scalar_t start; + scalar_t end; +}; + +inline scalar_t timingNaN() { + return std::numeric_limits::quiet_NaN(); +} + +inline bool hasStartTime(const ContactTiming& timing) { + return !std::isnan(timing.start); +} +inline bool hasEndTime(const ContactTiming& timing) { + return !std::isnan(timing.end); +} +inline bool startsWithSwingPhase(const std::vector& timings) { + return timings.empty() || hasStartTime(timings.front()); +} +inline bool startsWithStancePhase(const std::vector& timings) { + return !startsWithSwingPhase(timings); +} +inline bool endsWithSwingPhase(const std::vector& timings) { + return timings.empty() || hasEndTime(timings.back()); +} +inline bool endsWithStancePhase(const std::vector& timings) { + return !endsWithSwingPhase(timings); +} + +inline bool touchesDownAtLeastOnce(const std::vector& timings) { + return std::any_of(timings.begin(), timings.end(), [](const ContactTiming& timing) { return hasStartTime(timing); }); +} + +inline bool liftsOffAtLeastOnce(const std::vector& timings) { + return !timings.empty() && hasEndTime(timings.front()); +} + +/** Extracts the contact timings for all legs from a modeSchedule */ +feet_array_t> extractContactTimingsPerLeg(const ocs2::ModeSchedule& modeSchedule); + +/** Returns time of the next lift off. Returns nan if leg is not lifting off */ +scalar_t getTimeOfNextLiftOff(scalar_t currentTime, const std::vector& contactTimings); + +/** Returns time of the touch down for all legs from a modeschedule. Returns nan if leg does not touch down */ +scalar_t getTimeOfNextTouchDown(scalar_t currentTime, const std::vector& contactTimings); + +/** + * Get {startTime, endTime} for all contact phases. Swingphases are always implied in between: endTime[i] < startTime[i+1] + * times are NaN if they cannot be identified at the boundaries + * Vector is empty if there are no contact phases + */ +std::vector extractContactTimings(const std::vector& eventTimes, const std::vector& contactFlags); + +/** + * Extracts for each leg the contact sequence over the motion phase sequence. + * @param modeSequence : Sequence of contact modes. + * @return Sequence of contact flags per leg. + */ +feet_array_t> extractContactFlags(const std::vector& modeSequence); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h new file mode 100644 index 000000000..cfd54bd80 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h @@ -0,0 +1,43 @@ +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h" +#include "ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h" +#include "ocs2_switched_model_interface/logic/GaitSchedule.h" +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +/** + * Manages the Target Trajectories and ModeSchedule for switched model. + */ +class SwitchedModelModeScheduleManager : public ocs2::ReferenceManager { + public: + SwitchedModelModeScheduleManager(std::unique_ptr gaitSchedule, std::unique_ptr swingTrajectory, + std::unique_ptr terrainModel); + + ~SwitchedModelModeScheduleManager() override = default; + + contact_flag_t getContactFlags(scalar_t time) const; + + ocs2::Synchronized& getGaitSchedule() { return gaitSchedule_; } + const ocs2::Synchronized& getGaitSchedule() const { return gaitSchedule_; } + + const SwingTrajectoryPlanner& getSwingTrajectoryPlanner() const { return *swingTrajectoryPtr_; } + + ocs2::Synchronized& getTerrainModel() { return terrainModel_; } + const ocs2::Synchronized& getTerrainModel() const { return terrainModel_; } + + private: + void modifyReferences(scalar_t initTime, scalar_t finalTime, const vector_t& initState, ocs2::TargetTrajectories& targetTrajectories, + ocs2::ModeSchedule& modeSchedule) override; + + ocs2::Synchronized gaitSchedule_; + std::unique_ptr swingTrajectoryPtr_; + ocs2::Synchronized terrainModel_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/ros_msg_conversions/RosMsgConversions.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/ros_msg_conversions/RosMsgConversions.h new file mode 100644 index 000000000..d6aa3a4ce --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/ros_msg_conversions/RosMsgConversions.h @@ -0,0 +1,35 @@ +/* + * RosMsgConversions.h + * + * Created on: Jul 7, 2020 + * Author: Oliver Harley, Marko Bjelonic, Ruben Grandia + */ + +#pragma once + +#include +#include +#include + +#include +#include +#include +#include + +#include "ocs2_switched_model_interface/logic/Gait.h" +#include "ocs2_switched_model_interface/logic/GaitSchedule.h" + +namespace switched_model { +namespace ros_msg_conversions { + +ocs2_switched_model_msgs::gait toMessage(const Gait& gait); +Gait fromMessage(const ocs2_switched_model_msgs::gait& msg); + +ocs2_switched_model_msgs::gait_sequence toMessage(const GaitSchedule::GaitSequence& gaitSequence); +GaitSchedule::GaitSequence fromMessage(const ocs2_switched_model_msgs::gait_sequence& msg); + +ocs2_switched_model_msgs::scheduled_gait_sequence toMessage(scalar_t startTime, const GaitSchedule::GaitSequence& gaitSequence); +std::pair fromMessage(const ocs2_switched_model_msgs::scheduled_gait_sequence& msg); + +} // namespace ros_msg_conversions +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/ConvexTerrain.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/ConvexTerrain.h new file mode 100644 index 000000000..219e39e4b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/ConvexTerrain.h @@ -0,0 +1,96 @@ +// +// Created by rgrandia on 23.06.20. +// + +#pragma once + +#include +#include + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +struct ConvexTerrain { + /// Plane coordinate defining the origin of the terrain + TerrainPlane plane; + + /// Boundary points x-y in the terrain frame, points are order counter-clockwise. The last point is connected to the first point + std::vector boundary; +}; + +inline int getNextVertex(int i, size_t N) { + int next = i + 1; + return (next < N) ? next : 0; // next point with wrap around +} + +inline int getPreviousVertex(int i, size_t N) { + return (i > 0) ? (i - 1) : (N - 1); // previous point with wrap around +} + +/** + * Projects a 2D point into boundary of a 2D convex polygon. + * @param [in] boundary: The vertices of the polygon in clockwise or counter-clockwise order. + * @param [in] p: The 2D point. + * @return A pair of signed squared distance to the boundary (negative inside, positive outside) and the projected point. + */ +inline std::pair projectToConvex2dPolygonBoundary(const std::vector& boundary, const vector2_t& p) { + vector2_t image = p; + scalar_t dist2 = std::numeric_limits::max(); + auto saveIfCloser = [&p, &dist2, &image](const vector2_t& q) { + const scalar_t newDist2 = (p - q).squaredNorm(); + if (newDist2 < dist2) { + dist2 = newDist2; + image = q; + } + }; + + bool isInside = true; + for (int i = 0; i < boundary.size(); i++) { + const auto& p1 = boundary[i]; + const auto& p2 = boundary[getNextVertex(i, boundary.size())]; + + const vector2_t p12 = p2 - p1; + const scalar_t r = p12.dot(p - p1) / p12.squaredNorm(); + + if (r > 1.0) { + saveIfCloser(p2); + } else if (r < 0.0) { + saveIfCloser(p1); + isInside = false; // the point is outside since the angle is obtuse + } else { + const vector2_t q = p1 + r * p12; + saveIfCloser(q); + } + } // end of i loop + + return {(isInside ? -dist2 : dist2), image}; +} + +/** + * Projects a 3D point onto a 3D convex polygon. + * @param [in] convexTerrain: The 3D convex polygon. + * @param [in] p: The 3D point. + * @return The projected point. + */ +inline vector3_t projectToConvex3dPolygon(const ConvexTerrain& convexTerrain, const vector3_t& p) { + const vector3_t local_p = positionInTerrainFrameFromPositionInWorld(p, convexTerrain.plane); + const vector2_t local_2d_p(local_p.x(), local_p.y()); + + const auto distance2ImagePair = projectToConvex2dPolygonBoundary(convexTerrain.boundary, local_2d_p); + + vector3_t local_q; + if (distance2ImagePair.first <= 0.0) { + // the 2d local point is inside polygon + local_q << local_2d_p, 0.0; + } else { + // the 2d local point is outside polygon + local_q << distance2ImagePair.second, 0.0; + } + + return positionInWorldFrameFromPositionInTerrain(local_q, convexTerrain.plane); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarSignedDistanceField.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarSignedDistanceField.h new file mode 100644 index 000000000..3e8c25efc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarSignedDistanceField.h @@ -0,0 +1,34 @@ +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/terrain/SignedDistanceField.h" +#include "ocs2_switched_model_interface/terrain/TerrainModel.h" + +namespace switched_model { + +/** + * Implements a flat terrain signed distance field + */ +class PlanarSignedDistanceField : public SignedDistanceField { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + explicit PlanarSignedDistanceField(TerrainPlane terrainPlane); + + ~PlanarSignedDistanceField() override = default; + PlanarSignedDistanceField* clone() const override { return new PlanarSignedDistanceField(*this); }; + + scalar_t value(const vector3_t& position) const override; + + vector3_t derivative(const vector3_t& position) const override; + + std::pair valueAndDerivative(const vector3_t& position) const override; + + protected: + PlanarSignedDistanceField(const PlanarSignedDistanceField& other); + + private: + TerrainPlane terrainPlane_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarTerrainModel.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarTerrainModel.h new file mode 100644 index 000000000..7eeac0cbd --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlanarTerrainModel.h @@ -0,0 +1,36 @@ +// +// Created by rgrandia on 29.04.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/terrain/PlanarSignedDistanceField.h" +#include "ocs2_switched_model_interface/terrain/TerrainModel.h" + +namespace switched_model { + +/** + * This class models the terrain as a single infinite plane. + */ +class PlanarTerrainModel : public TerrainModel { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + explicit PlanarTerrainModel(TerrainPlane terrainPlane); + ~PlanarTerrainModel() override = default; + + TerrainPlane getLocalTerrainAtPositionInWorldAlongGravity(const vector3_t& positionInWorld, + std::function penaltyFunction) const override; + + vector3_t getHighestObstacleAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const override; + + std::vector getHeightProfileAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const override; + + const SignedDistanceField* getSignedDistanceField() const override { return &sdf_; } + + private: + TerrainPlane terrainPlane_; + PlanarSignedDistanceField sdf_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlaneFitting.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlaneFitting.h new file mode 100644 index 000000000..64de1b760 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/PlaneFitting.h @@ -0,0 +1,14 @@ +// +// Created by rgrandia on 27.11.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +NormalAndPosition estimatePlane(const std::vector& regressionPoints); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/SignedDistanceField.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/SignedDistanceField.h new file mode 100644 index 000000000..a50f4f399 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/SignedDistanceField.h @@ -0,0 +1,27 @@ +// +// Created by rgrandia on 14.08.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * This abstract class defines the interface for a signed distance field. + */ +class SignedDistanceField { + public: + SignedDistanceField() = default; + virtual ~SignedDistanceField() = default; + SignedDistanceField(const SignedDistanceField&) = delete; + SignedDistanceField& operator=(const SignedDistanceField&) = delete; + + virtual SignedDistanceField* clone() const = 0; + virtual scalar_t value(const vector3_t& position) const = 0; + virtual Eigen::Vector3d derivative(const vector3_t& position) const = 0; + virtual std::pair valueAndDerivative(const vector3_t& position) const = 0; +}; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainModel.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainModel.h new file mode 100644 index 000000000..d5d4e29af --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainModel.h @@ -0,0 +1,57 @@ +// +// Created by rgrandia on 21.04.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" +#include "ocs2_switched_model_interface/terrain/ConvexTerrain.h" +#include "ocs2_switched_model_interface/terrain/SignedDistanceField.h" +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +namespace switched_model { + +/** + * This abstract class defines the interface for terrain models. + */ +class TerrainModel { + public: + TerrainModel() = default; + virtual ~TerrainModel() = default; + TerrainModel(const TerrainModel&) = delete; + TerrainModel& operator=(const TerrainModel&) = delete; + + /** Returns a linear approximation of the terrain at the query point projected along gravity onto the terrain */ + // TODO: change name and remove "alongGravity" + TerrainPlane getLocalTerrainAtPositionInWorldAlongGravity(const vector3_t& positionInWorld) const { + return getLocalTerrainAtPositionInWorldAlongGravity(positionInWorld, [](const vector3_t&) { return 0.0; }); + } + + /// Penalty function needs to return values >= 0 + virtual TerrainPlane getLocalTerrainAtPositionInWorldAlongGravity(const vector3_t& positionInWorld, + std::function penaltyFunction) const = 0; + + ConvexTerrain getConvexTerrainAtPositionInWorld(const vector3_t& positionInWorld) const { + return getConvexTerrainAtPositionInWorld(positionInWorld, [](const vector3_t&) { return 0.0; }); + } + + /// Penalty function needs to return values >= 0 + virtual ConvexTerrain getConvexTerrainAtPositionInWorld(const vector3_t& positionInWorld, + std::function penaltyFunction) const { + return {getLocalTerrainAtPositionInWorldAlongGravity(positionInWorld, std::move(penaltyFunction)), {}}; + } + + /** Returns the signed distance field for this terrain if one is available */ + virtual const SignedDistanceField* getSignedDistanceField() const { return nullptr; } + + virtual vector3_t getHighestObstacleAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const = 0; + + /** + * Returns the height profiles between two points in world frame. Provided as a set of points {alpha, height}, where alpha in [0, 1] is + * the progress along the line. position1InWorld -> alpha = 0, position2InWorld -> alpha = 1. + * Height is the absolute height in world frame. + */ + virtual std::vector getHeightProfileAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const = 0; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainPlane.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainPlane.h new file mode 100644 index 000000000..f7888385c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/terrain/TerrainPlane.h @@ -0,0 +1,134 @@ +// +// Created by rgrandia on 21.04.20. +// + +#pragma once + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +/** + * Planar terrain represented by a single coordinate frame. + * - The terrain frame is located at positionInWorld. + * - The surface normal points in positive z direction in the terrain frame. + */ +struct TerrainPlane { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + vector3_t positionInWorld; + matrix3_t orientationWorldToTerrain; + + TerrainPlane() : positionInWorld(vector3_t::Zero()), orientationWorldToTerrain(matrix3_t::Identity()) {} + TerrainPlane(vector3_t positionInWorld_, matrix3_t orientationWorldToTerrain_) + : positionInWorld(std::move(positionInWorld_)), orientationWorldToTerrain(std::move(orientationWorldToTerrain_)) {} + + explicit TerrainPlane(const Eigen::Isometry3d& transform) + : positionInWorld(transform.translation()), orientationWorldToTerrain(transform.linear().transpose()) {} +}; + +struct NormalAndPosition { + vector3_t normal; + vector3_t position; +}; + +/** Returns the surface normal = z-axis of the terrain, the unit vector is represented in the world frame*/ +inline vector3_t surfaceNormalInWorld(const TerrainPlane& terrainPlane) { + return terrainPlane.orientationWorldToTerrain.row(2).transpose(); +} + +/** + * Constructs the x-y unit vectors for a given z-axis. The absolute orientation of the x-y vectors is unspecified. + * @param surfaceNormal (z-axis) of the terrain. + * @return 2x3 matrix forming the [x-axis; y-axis] of the terrain + */ +inline Eigen::Matrix tangentialBasisFromSurfaceNormal(const vector3_t& surfaceNormal) { + // Cross with any vector that is not equal to surfaceNormal + Eigen::Vector3d yAxisInGlobal = surfaceNormal.cross(Eigen::Vector3d::UnitX()); + { // Normalize the yAxis. Need to pick a different direction if z happened to intersect with unitX + const auto ySquaredNorm = yAxisInGlobal.squaredNorm(); + const double crossTolerance = 1e-3; + if (ySquaredNorm > crossTolerance) { + yAxisInGlobal /= std::sqrt(ySquaredNorm); + } else { + // normal was almost equal to unitX. Pick the y-axis in a different way (approximately equal to unitY): + yAxisInGlobal = surfaceNormal.cross(Eigen::Vector3d::UnitY().cross(surfaceNormal)).normalized(); + } + } + + // Assumes the surface normal is normalized + Eigen::Matrix tangentBasis; + tangentBasis.row(0) = yAxisInGlobal.cross(surfaceNormal); + tangentBasis.row(1) = yAxisInGlobal; + return tangentBasis; +} + +/** + * Constructs a rotation matrix from the specified surface normal (z-axis). The rotation around the surface normal is unspecified. + * @param surfaceNormal + * @return Rotation matrix world to terrain, where the terrain frame has the z-axis aligned with the specified surface normal. + */ +inline matrix3_t orientationWorldToTerrainFromSurfaceNormalInWorld(const vector3_t& surfaceNormal) { + Eigen::Matrix tangents = tangentialBasisFromSurfaceNormal(surfaceNormal); + matrix3_t orientationWorldToTerrain; + orientationWorldToTerrain.topRows(2) = tangents; + orientationWorldToTerrain.row(2) = surfaceNormal.transpose(); + return orientationWorldToTerrain; +} + +/** Converts a 3D position in world frame to a 3D position in the terrain frame. */ +inline vector3_t positionInTerrainFrameFromPositionInWorld(const vector3_t& positionWorld, const TerrainPlane& terrainPlane) { + return terrainPlane.orientationWorldToTerrain * (positionWorld - terrainPlane.positionInWorld); +} + +/** Converts a 3D position in terrain frame to a 3D position in the world frame. */ +inline vector3_t positionInWorldFrameFromPositionInTerrain(const vector3_t& positionInTerrain, const TerrainPlane& terrainPlane) { + return terrainPlane.orientationWorldToTerrain.transpose() * positionInTerrain + terrainPlane.positionInWorld; +} + +/** Returns the orthogonal signed distance between the terrain a 3D point represented in world frame. */ +inline scalar_t terrainSignedDistanceFromPositionInWorld(const vector3_t& positionWorld, const TerrainPlane& terrainPlane) { + const vector3_t surfaceNormal = surfaceNormalInWorld(terrainPlane); + return surfaceNormal.dot(positionWorld - terrainPlane.positionInWorld); +} + +/** Returns the projection along gravity onto the terrain plane for a 2D position in world. The returned position is in world frame */ +inline vector3_t projectPositionInWorldOntoPlaneAlongGravity(const vector2_t& positionXYWorld, const TerrainPlane& terrainPlane) { + // solve surfaceNormal.dot(projectedPosition - terrainPlane.positionInWorld) = 0 + // Distance = positionWorld.z() - projectedPosition.z() + const vector3_t surfaceNormal = surfaceNormalInWorld(terrainPlane); + const scalar_t projectedPositionZ = (surfaceNormal.dot(terrainPlane.positionInWorld) - positionXYWorld.x() * surfaceNormal.x() - + positionXYWorld.y() * surfaceNormal.y()) / + surfaceNormal.z(); + return {positionXYWorld.x(), positionXYWorld.y(), projectedPositionZ}; +} + +/** Returns the orthogonal projection onto the terrain plane for a 3D position in world. The returned position is in world frame */ +inline vector3_t projectPositionInWorldOntoPlane(const vector3_t& positionWorld, const TerrainPlane& terrainPlane) { + const vector3_t surfaceNormal = surfaceNormalInWorld(terrainPlane); + return surfaceNormal.dot(terrainPlane.positionInWorld - positionWorld) * surfaceNormal + positionWorld; +} + +/** Returns the projection along gravity onto the terrain plane for a 3D position in world. The returned position is in world frame */ +inline vector3_t projectPositionInWorldOntoPlaneAlongGravity(const vector3_t& positionWorld, const TerrainPlane& terrainPlane) { + return projectPositionInWorldOntoPlaneAlongGravity(vector2_t{positionWorld.x(), positionWorld.y()}, terrainPlane); +} + +/** + * Returns the projection along gravity onto the terrain orientation for a vector represented in world frame + * This projection is such that the x-y components of the vector remain unchanged. + * The returned vector is still represented in the world frame. + */ +inline vector3_t projectVectorInWorldOntoPlaneAlongGravity(const vector3_t& vectorInWorld, const TerrainPlane& terrainPlane) { + const vector3_t surfaceNormal = surfaceNormalInWorld(terrainPlane); + vector3_t projectedVector = vectorInWorld; + // solve + // 1. projectedVector.x() = vectorInWorld.x(); + // 2. projectedVector.y() = vectorInWorld.y(); + // 3. surfaceNormal.dot(projectedVector) = 0 + projectedVector.z() = -(vectorInWorld.x() * surfaceNormal.x() + vectorInWorld.y() * surfaceNormal.y()) / surfaceNormal.z(); + return projectedVector; +} + +TerrainPlane loadTerrainPlane(const std::string& filename, bool verbose); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/test/TestEvaluateConstraints.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/test/TestEvaluateConstraints.h new file mode 100644 index 000000000..71cf9e02b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/include/ocs2_switched_model_interface/test/TestEvaluateConstraints.h @@ -0,0 +1,70 @@ +#pragma once + +#include +#include + +namespace switched_model { + +template +int evaluateConstraint(ComModelBase& comModel, + KinematicsModelBase& kinModel, const typename Constraint::settings_t& settings) { + // Set up settings + using ad_com_model_t = ComModelBase; + using ad_kinematic_model_t = KinematicsModelBase; + + // Initialize the Constraint + Constraint constraint(0, settings, comModel, kinModel, true); + + // evaluation point + double t = 0.0; + input_vector_t u; + state_vector_t x; + u.setRandom(); + x.setRandom(); + + auto order = constraint.getOrder(); + switch (order) { + case ocs2::ConstraintOrder::Quadratic: { + std::cerr << "\nConstraintOrder: quadratic.\n"; + auto quadApprox = constraint.getQuadraticApproximation(t, x, u); + std::cerr << "ddhdxdx" << std::endl; + int count = 0; + for (auto ddhdxdx : quadApprox.dfdxx) { + std::cerr << "\t ddhdxdx[" << count << "]" << std::endl; + std::cerr << ddhdxdx << std::endl; + } + + std::cerr << "ddhdudu" << std::endl; + count = 0; + for (auto ddhdudu : quadApprox.dfduu) { + std::cerr << "\t ddhdudu[" << count << "]" << std::endl; + std::cerr << ddhdudu << std::endl; + } + + std::cerr << "ddhdudx" << std::endl; + count = 0; + for (auto ddhdudx : quadApprox.dfdux) { + std::cerr << "\t ddhdudx[" << count << "]" << std::endl; + std::cerr << ddhdudx << std::endl; + } + + std::cerr << "dhdx: \n" << quadApprox.dfdx << std::endl; + std::cerr << "dhdu: \n" << quadApprox.dfdu << std::endl; + std::cerr << "h: " << quadApprox.f.transpose() << std::endl; + } // fallthrough on purpose + case ocs2::ConstraintOrder::Linear: { + std::cerr << "\nConstraintOrder: Linear.\n"; + auto linApprox = constraint.getLinearApproximation(t, x, u); + std::cerr << "dhdx: \n" << linApprox.dfdx << std::endl; + std::cerr << "dhdu: \n" << linApprox.dfdu << std::endl; + std::cerr << "h: " << linApprox.f.transpose() << std::endl; + break; + } + default: + throw std::runtime_error("None or No ConstraintOrder"); + break; + } + return true; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/package.xml new file mode 100644 index 000000000..3b4aff970 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/package.xml @@ -0,0 +1,25 @@ + + + ocs2_switched_model_interface + 0.0.0 + The ocs2_switched_model_interface package + + Farbod Farshidian + Jan Carius + Ruben Grandia + + TODO + + catkin + + cmake_clang_tools + + roscpp + ocs2_core + ocs2_oc + ocs2_msgs + ocs2_ros_interfaces + ocs2_robotic_tools + ocs2_switched_model_msgs + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/AnalyticalInverseKinematics.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/AnalyticalInverseKinematics.cpp new file mode 100644 index 000000000..ef1b1c0cd --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/AnalyticalInverseKinematics.cpp @@ -0,0 +1,69 @@ +#include "ocs2_switched_model_interface/analytical_inverse_kinematics/AnalyticalInverseKinematics.h" + +namespace switched_model { +namespace analytical_inverse_kinematics { + +void getLimbJointPositionsFromPositionBaseToFootInBaseFrame(Eigen::Vector3d& legJoints, + const Eigen::Vector3d& positionBaseToFootInBaseFrame, + const LegInverseKinematicParameters& parameters, size_t limb) { + Eigen::Vector3d positionHAAToFootInBaseFrame = positionBaseToFootInBaseFrame - parameters.positionBaseToHaaCenterInBaseFrame_; + + /// Rescaling target + const double reachSquared{positionHAAToFootInBaseFrame.squaredNorm()}; + if (reachSquared > parameters.maxReachSquared_) { + positionHAAToFootInBaseFrame.array() *= parameters.maxReach_ / std::sqrt(reachSquared); + } else if (reachSquared < parameters.minReachSquared_ && reachSquared > 0.0) { + positionHAAToFootInBaseFrame.array() *= parameters.minReach_ / std::sqrt(reachSquared); + } + + /// Rescaling Yz + double positionYzSquared{positionHAAToFootInBaseFrame.tail<2>().squaredNorm()}; + if (positionYzSquared < parameters.positionHipToFootYoffsetSquared_ && positionYzSquared > 0.0) { + positionHAAToFootInBaseFrame.tail<2>().array() *= std::sqrt(parameters.positionHipToFootYoffsetSquared_ / positionYzSquared); + positionYzSquared = parameters.positionHipToFootYoffsetSquared_; + + if (std::abs(positionHAAToFootInBaseFrame[0]) > parameters.maxReach_SP_ && positionHAAToFootInBaseFrame[0] != 0.0) { + positionHAAToFootInBaseFrame[0] *= parameters.maxReach_SP_ / std::abs(positionHAAToFootInBaseFrame[0]); + } + } + + // HAA + const double rSquared{std::max(0.0, positionYzSquared - parameters.positionHipToFootYoffsetSquared_)}; + const double r{std::sqrt(rSquared)}; + const double delta{std::atan2(positionHAAToFootInBaseFrame.y(), -positionHAAToFootInBaseFrame.z())}; + const double beta{std::atan2(r, parameters.positionHipToFootYoffset_)}; + const double qHAA{beta + delta - M_PI_2}; + legJoints[0] = qHAA; + + /// simplification for anymal + const double l_squared{rSquared + positionHAAToFootInBaseFrame[0] * positionHAAToFootInBaseFrame[0]}; + const double l{std::sqrt(l_squared)}; + + // Phi 1 + double cosphi1{0.5 * (parameters.a1_squared_ + l_squared - parameters.a2_squared_) / (parameters.a1_ * l)}; + cosphi1 = std::max(-1.0, std::min(cosphi1, 1.0)); // Clip to bounds of acos + const double phi1{std::acos(cosphi1)}; + + // Phi 2 + double cosphi2 = {0.5 * (parameters.a2_squared_ + l_squared - parameters.a1_squared_) / (parameters.a2_ * l)}; + cosphi2 = std::max(-1.0, std::min(cosphi2, 1.0)); // Clip to bounds of acos + const double phi2{std::acos(cosphi2)}; + + // HFE + const double theta_prime{std::atan2(positionHAAToFootInBaseFrame[0], r)}; + double qHFE{phi1 - theta_prime}; + if (limb > 1) { + qHFE = -phi1 - theta_prime; + } + legJoints[1] = qHFE; + + // KFE + double qKFE = {phi1 + phi2 - parameters.KFEOffset_}; + if (limb < 2) { + qKFE = -qKFE; + } + legJoints[2] = qKFE; +} + +} // namespace analytical_inverse_kinematics +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/LegInverseKinematicParameters.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/LegInverseKinematicParameters.cpp new file mode 100644 index 000000000..b73a1daa1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/analytical_inverse_kinematics/LegInverseKinematicParameters.cpp @@ -0,0 +1,49 @@ +#include "ocs2_switched_model_interface/analytical_inverse_kinematics/LegInverseKinematicParameters.h" + +namespace switched_model { +namespace analytical_inverse_kinematics { + +LegInverseKinematicParameters::LegInverseKinematicParameters(const Eigen::Vector3d& positionBaseToHipInBaseFrame, + const Eigen::Vector3d& positionHipToThighInBaseFrame, + const Eigen::Vector3d& positionThighToShankInBaseFrame, + const Eigen::Vector3d& positionShankToFootInBaseFrame) + : positionBaseToHipInBaseFrame_(positionBaseToHipInBaseFrame), + positionHipToThighInBaseFrame_(positionHipToThighInBaseFrame), + positionThighToShankInBaseFrame_(positionThighToShankInBaseFrame), + positionShankToFootInBaseFrame_(positionShankToFootInBaseFrame) { + initialize(); +} + +void LegInverseKinematicParameters::initialize() { + // Store HAA center + positionBaseToHaaCenterInBaseFrame_ = positionBaseToHipInBaseFrame_; + positionBaseToHaaCenterInBaseFrame_[0] += positionHipToThighInBaseFrame_[0]; + + // Store Hip Y offset + positionHipToFootYoffset_ = + positionHipToThighInBaseFrame_.y() + positionThighToShankInBaseFrame_.y() + positionShankToFootInBaseFrame_.y(); + positionHipToFootYoffsetSquared_ = positionHipToFootYoffset_ * positionHipToFootYoffset_; + + // Compute max / min extension limits + const double thighToShankXZLength{ + Eigen::Vector3d(positionThighToShankInBaseFrame_.x(), 0.0, positionThighToShankInBaseFrame_.z()).norm()}; + const double shankToFootXZLength{Eigen::Vector3d(positionShankToFootInBaseFrame_.x(), 0.0, positionShankToFootInBaseFrame_.z()).norm()}; + minReach_SP_ = std::abs(shankToFootXZLength - thighToShankXZLength); + maxReach_SP_ = std::abs(thighToShankXZLength + shankToFootXZLength); + minReachSquared_ = positionHipToFootYoffsetSquared_ + minReach_SP_ * minReach_SP_; + maxReachSquared_ = positionHipToFootYoffsetSquared_ + maxReach_SP_ * maxReach_SP_; + minReach_ = std::sqrt(minReachSquared_); + maxReach_ = std::sqrt(maxReachSquared_); + + // Trigonometry factors + KFEOffset_ = std::abs(std::atan(positionShankToFootInBaseFrame_[0] / positionShankToFootInBaseFrame_[2])); + a1_squared_ = positionThighToShankInBaseFrame_[0] * positionThighToShankInBaseFrame_[0] + + positionThighToShankInBaseFrame_[2] * positionThighToShankInBaseFrame_[2]; + a1_ = std::sqrt(a1_squared_); + a2_squared_ = positionShankToFootInBaseFrame_[0] * positionShankToFootInBaseFrame_[0] + + positionShankToFootInBaseFrame_[2] * positionShankToFootInBaseFrame_[2]; + a2_ = std::sqrt(a2_squared_); +} + +} // namespace analytical_inverse_kinematics +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/EndEffectorVelocityConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/EndEffectorVelocityConstraint.cpp new file mode 100644 index 000000000..9230d9441 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/EndEffectorVelocityConstraint.cpp @@ -0,0 +1,51 @@ +// +// Created by rgrandia on 05.07.21. +// + +#include "ocs2_switched_model_interface/constraint/EndEffectorVelocityConstraint.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" + +namespace switched_model { + +EndEffectorVelocityConstraint::EndEffectorVelocityConstraint(int legNumber, const SwitchedModelModeScheduleManager& modeScheduleManager) + : StateInputConstraint(ocs2::ConstraintOrder::Linear), legNumber_(legNumber), modeScheduleManager_(&modeScheduleManager) {} + +EndEffectorVelocityConstraint* EndEffectorVelocityConstraint::clone() const { + return new EndEffectorVelocityConstraint(*this); +}; + +bool EndEffectorVelocityConstraint::isActive(scalar_t time) const { + return modeScheduleManager_->getContactFlags(time)[legNumber_]; +} + +size_t EndEffectorVelocityConstraint::getNumConstraints(scalar_t time) const { + return 2; +} + +vector_t EndEffectorVelocityConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + const auto tangentBasis = tangentialBasisFromSurfaceNormal(switchedModelPreComp.getSurfaceNormalInOriginFrame(legNumber_)); + + const auto& o_footVelocity = switchedModelPreComp.footVelocityInOriginFrame(legNumber_); + return tangentBasis * o_footVelocity; +} + +VectorFunctionLinearApproximation EndEffectorVelocityConstraint::getLinearApproximation(scalar_t time, const vector_t& state, + const vector_t& input, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + const auto tangentBasis = tangentialBasisFromSurfaceNormal(switchedModelPreComp.getSurfaceNormalInOriginFrame(legNumber_)); + + const auto& o_footVelocity = switchedModelPreComp.footVelocityInOriginFrame(legNumber_); + const auto& o_footVelocityDerivative = switchedModelPreComp.footVelocityInOriginFrameDerivative(legNumber_); + + VectorFunctionLinearApproximation constraint; + constraint.f.noalias() = tangentBasis * o_footVelocity; + constraint.dfdx.noalias() = tangentBasis * o_footVelocityDerivative.dfdx; + constraint.dfdu.noalias() = tangentBasis * o_footVelocityDerivative.dfdu; + return constraint; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FootNormalConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FootNormalConstraint.cpp new file mode 100644 index 000000000..237c33274 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FootNormalConstraint.cpp @@ -0,0 +1,97 @@ +// +// Created by rgrandia on 29.04.20. +// + +#include "ocs2_switched_model_interface/constraint/FootNormalConstraint.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" + +namespace switched_model { + +namespace { + +/** + * Linear constraint A_p * p_world + A_v * v_world + b = 0 + */ +struct FootNormalConstraintMatrix { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Eigen::Matrix positionMatrix = Eigen::Matrix::Zero(); + Eigen::Matrix velocityMatrix = Eigen::Matrix::Zero(); + scalar_t constant = 0.0; +}; + +/** + * Constructs a velocity constraint in surface normal direction : + * ==> v_foot = v_ff - kp * (p_foot - p_des) + * ==> (n')* v_foot + (kp* n')* p_foot - (n') * (v_ff + kp* p_des) = 0 + * + * Gives us + * ==> A_p * p_world + A_v * v_world + b = 0 + * A_p = kp * n' + * A_v = n' + * b = (n') * (v_ff + kp* p_des) + */ +FootNormalConstraintMatrix computeFootNormalConstraint(const vector3_t& surfaceNormalInWorld, const vector3_t& feedforwardVelocityInWorld, + const vector3_t& feedforwardPositionInWorld, scalar_t positionGain) { + FootNormalConstraintMatrix footNormalConstraint; + footNormalConstraint.velocityMatrix = surfaceNormalInWorld.transpose(); + footNormalConstraint.positionMatrix = positionGain * surfaceNormalInWorld.transpose(); + footNormalConstraint.constant = -surfaceNormalInWorld.dot(feedforwardVelocityInWorld + positionGain * feedforwardPositionInWorld); + return footNormalConstraint; +} +} // namespace + +FootNormalConstraint::FootNormalConstraint(int legNumber, scalar_t positionGain) + : ocs2::StateInputConstraint(ocs2::ConstraintOrder::Linear), legNumber_(legNumber), positionGain_(positionGain) {} + +FootNormalConstraint::FootNormalConstraint(const FootNormalConstraint& rhs) + : ocs2::StateInputConstraint(rhs), legNumber_(rhs.legNumber_), positionGain_(rhs.positionGain_) {} + +FootNormalConstraint* FootNormalConstraint::clone() const { + return new FootNormalConstraint(*this); +} + +vector_t FootNormalConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + const auto& motionReference = switchedModelPreComp.getMotionReference(); + const auto& normalConstraint = + computeFootNormalConstraint(switchedModelPreComp.getSurfaceNormalInOriginFrame(legNumber_), motionReference.footVelocity[legNumber_], + motionReference.footPosition[legNumber_], positionGain_); + const auto& o_footPosition = switchedModelPreComp.footPositionInOriginFrame(legNumber_); + const auto& o_footVelocity = switchedModelPreComp.footVelocityInOriginFrame(legNumber_); + + vector_t h(1); + h[0] = + normalConstraint.positionMatrix.dot(o_footPosition) + normalConstraint.velocityMatrix.dot(o_footVelocity) + normalConstraint.constant; + return h; +} + +VectorFunctionLinearApproximation FootNormalConstraint::getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + const auto& motionReference = switchedModelPreComp.getMotionReference(); + const auto& normalConstraint = + computeFootNormalConstraint(switchedModelPreComp.getSurfaceNormalInOriginFrame(legNumber_), motionReference.footVelocity[legNumber_], + motionReference.footPosition[legNumber_], positionGain_); + const auto& o_footPosition = switchedModelPreComp.footPositionInOriginFrame(legNumber_); + const auto& o_footPositionDerivative = switchedModelPreComp.footPositionInOriginFrameStateDerivative(legNumber_); + const auto& o_footVelocity = switchedModelPreComp.footVelocityInOriginFrame(legNumber_); + const auto& o_footVelocityDerivative = switchedModelPreComp.footVelocityInOriginFrameDerivative(legNumber_); + + VectorFunctionLinearApproximation constraint; + // Constant + constraint.f.resize(1); + constraint.f[0] = + normalConstraint.positionMatrix.dot(o_footPosition) + normalConstraint.velocityMatrix.dot(o_footVelocity) + normalConstraint.constant; + + // State derivative + constraint.dfdx.noalias() = normalConstraint.positionMatrix * o_footPositionDerivative; + constraint.dfdx.noalias() += normalConstraint.velocityMatrix * o_footVelocityDerivative.dfdx; + + // Input derivative + constraint.dfdu.noalias() = normalConstraint.velocityMatrix * o_footVelocityDerivative.dfdu; + return constraint; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FrictionConeConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FrictionConeConstraint.cpp new file mode 100644 index 000000000..96ec73a02 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/FrictionConeConstraint.cpp @@ -0,0 +1,77 @@ +// +// Created by rgrandia on 06.08.20. +// + +#include + +#include + +namespace switched_model { + +namespace friction_cone { +scalar_t frictionConeConstraint(const Config& config, const vector3_t& forcesInTerrainFrame) { + const auto& localForces = forcesInTerrainFrame; + + const auto F_tangent_square = localForces.x() * localForces.x() + localForces.y() * localForces.y() + config.regularization; + const auto F_tangent_norm = std::sqrt(F_tangent_square); + + return config.frictionCoefficient * (localForces.z() + config.gripperForce) - F_tangent_norm; +} + +ConeLocalDerivatives frictionConeLocalDerivatives(const Config& config, const vector3_t& forcesInTerrainFrame) { + const auto& localForces = forcesInTerrainFrame; + + const auto F_x_square = localForces.x() * localForces.x(); + const auto F_y_square = localForces.y() * localForces.y(); + const auto F_tangent_square = F_x_square + F_y_square + config.regularization; + const auto F_tangent_norm = std::sqrt(F_tangent_square); + const auto F_tangent_square_pow32 = F_tangent_norm * F_tangent_square; // = F_tangent_square ^ (3/2) + + ConeLocalDerivatives coneLocalDerivatives{}; + coneLocalDerivatives.coneConstraint = config.frictionCoefficient * (localForces.z() + config.gripperForce) - F_tangent_norm; + + coneLocalDerivatives.dCone_dF(0) = -localForces.x() / F_tangent_norm; + coneLocalDerivatives.dCone_dF(1) = -localForces.y() / F_tangent_norm; + coneLocalDerivatives.dCone_dF(2) = config.frictionCoefficient; + + coneLocalDerivatives.d2Cone_dF2(0, 0) = -(F_y_square + config.regularization) / F_tangent_square_pow32 - config.hessianDiagonalShift; + coneLocalDerivatives.d2Cone_dF2(0, 1) = localForces.x() * localForces.y() / F_tangent_square_pow32; + coneLocalDerivatives.d2Cone_dF2(0, 2) = 0.0; + coneLocalDerivatives.d2Cone_dF2(1, 0) = coneLocalDerivatives.d2Cone_dF2(0, 1); + coneLocalDerivatives.d2Cone_dF2(1, 1) = -(F_x_square + config.regularization) / F_tangent_square_pow32 - config.hessianDiagonalShift; + coneLocalDerivatives.d2Cone_dF2(1, 2) = 0.0; + coneLocalDerivatives.d2Cone_dF2(2, 0) = 0.0; + coneLocalDerivatives.d2Cone_dF2(2, 1) = 0.0; + coneLocalDerivatives.d2Cone_dF2(2, 2) = -config.hessianDiagonalShift; + return coneLocalDerivatives; +} + +ConeDerivatives frictionConeDerivatives(const Config& config, const vector3_t& forcesInTerrainFrame, const matrix3_t& t_R_w, + const matrix3_t& w_R_b, const vector3_t& eulerXYZ, const vector3_t& forcesInBodyFrame) { + const auto coneLocalDerivatives = frictionConeLocalDerivatives(config, forcesInTerrainFrame); + + // Local to body Derivatives + matrix3_t dF_deuler = t_R_w * rotationBaseToOriginJacobian(eulerXYZ, forcesInBodyFrame); + matrix3_t dF_du = t_R_w * w_R_b; + + ConeDerivatives coneDerivatives; + // Zero order + coneDerivatives.coneConstraint = coneLocalDerivatives.coneConstraint; + + // First order derivatives + coneDerivatives.dCone_deuler.noalias() = coneLocalDerivatives.dCone_dF.transpose() * dF_deuler; + coneDerivatives.dCone_du.noalias() = coneLocalDerivatives.dCone_dF.transpose() * dF_du; + + // Second order derivatives + matrix3_t tmp = coneLocalDerivatives.d2Cone_dF2 * dF_deuler; + coneDerivatives.d2Cone_deuler2.noalias() = dF_deuler.transpose() * tmp; + coneDerivatives.d2Cone_dudeuler.noalias() = dF_du.transpose() * tmp; + + tmp.noalias() = coneLocalDerivatives.d2Cone_dF2 * dF_du; + coneDerivatives.d2Cone_du2.noalias() = dF_du.transpose() * tmp; + + return coneDerivatives; +} +} // namespace friction_cone + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/ZeroForceConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/ZeroForceConstraint.cpp new file mode 100644 index 000000000..bb19cdb1a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/constraint/ZeroForceConstraint.cpp @@ -0,0 +1,42 @@ +// +// Created by rgrandia on 05.07.21. +// + +#include "ocs2_switched_model_interface/constraint/ZeroForceConstraint.h" + +namespace switched_model { + +ZeroForceConstraint::ZeroForceConstraint(int legNumber, const SwitchedModelModeScheduleManager& modeScheduleManager) + : ocs2::StateInputConstraint(ocs2::ConstraintOrder::Linear), + legStartIdx_(3 * legNumber), + legNumber_(legNumber), + modeScheduleManager_(&modeScheduleManager) {} + +ZeroForceConstraint* ZeroForceConstraint::clone() const { + return new ZeroForceConstraint(*this); +} + +bool ZeroForceConstraint::isActive(scalar_t time) const { + return !modeScheduleManager_->getContactFlags(time)[legNumber_]; +} + +size_t ZeroForceConstraint::getNumConstraints(scalar_t time) const { + return 3; +}; + +vector_t ZeroForceConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const { + return input.segment(legStartIdx_, 3); +}; + +VectorFunctionLinearApproximation ZeroForceConstraint::getLinearApproximation(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::PreComputation& preComp) const { + VectorFunctionLinearApproximation linearApproximation; + linearApproximation.f = input.segment(legStartIdx_, 3); + linearApproximation.dfdx.setZero(3, state.rows()); + linearApproximation.dfdu.setZero(3, input.rows()); + linearApproximation.dfdu.block<3, 3>(0, legStartIdx_).setIdentity(); + return linearApproximation; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ComModelBase.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ComModelBase.cpp new file mode 100644 index 000000000..306f455e2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ComModelBase.cpp @@ -0,0 +1,41 @@ +/* + * ComModelBase.h + * + * Created on: Aug 10, 2017 + * Author: farbod + */ + +#include "ocs2_switched_model_interface/core/ComModelBase.h" + +#include + +namespace switched_model { + +comkino_input_t weightCompensatingInputs(const ComModelBase& comModel, const contact_flag_t& contactFlags, + const vector3_t& baseOrientation) { + return weightCompensatingInputs(comModel.totalMass(), contactFlags, baseOrientation); +} + +comkino_input_t weightCompensatingInputs(scalar_t mass, const contact_flag_t& contactFlags, const vector3_t& baseOrientation) { + const int numStanceLegs = numberOfClosedContacts(contactFlags); + + comkino_input_t inputs = comkino_input_t::Zero(); + if (numStanceLegs > 0) { + const scalar_t totalWeight = mass * 9.81; + const vector3_t forceInWorld = vector3_t{0.0, 0.0, totalWeight / numStanceLegs}; + const vector3_t forceInBase = rotateVectorOriginToBase(forceInWorld, baseOrientation); + + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + if (contactFlags[i]) { + inputs.segment<3>(3 * i) = forceInBase; + } + } + } + + return inputs; +} + +template class ComModelBase; +template class ComModelBase; + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/KinematicsModelBase.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/KinematicsModelBase.cpp new file mode 100644 index 000000000..4dc579322 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/KinematicsModelBase.cpp @@ -0,0 +1,194 @@ +/* + * KinematicsModelBase.h + * + * Created on: Aug 3, 2017 + * Author: Farbod + */ + +#include "ocs2_switched_model_interface/core/KinematicsModelBase.h" + +#include + +namespace switched_model { + +template +vector3_s_t KinematicsModelBase::legRootInOriginFrame(size_t footIndex, + const base_coordinate_s_t& basePose) const { + const vector3_s_t o_basePosition = getPositionInOrigin(basePose); + + const vector3_s_t b_baseTolegRoot = baseToLegRootInBaseFrame(footIndex); + const vector3_s_t o_baseTolegRoot = rotateVectorBaseToOrigin(b_baseTolegRoot, getOrientation(basePose)); + return o_baseTolegRoot + o_basePosition; +} + +template +matrix3_s_t KinematicsModelBase::orientationLegRootToOriginFrame(size_t footIndex, + const base_coordinate_s_t& basePose) const { + auto rotationLegRootToOrigin = rotationMatrixBaseToOrigin(getOrientation(basePose)); + if (footIndex == 1 || footIndex == 3) { // Right side, need to point the x-axis backwards and y outwards = 180deg turn around z-axis + rotationLegRootToOrigin.col(0) = -rotationLegRootToOrigin.col(0); // flip x-axis + rotationLegRootToOrigin.col(1) = -rotationLegRootToOrigin.col(1); // flip y-axis + } + return rotationLegRootToOrigin; +} + +template +vector3_s_t KinematicsModelBase::legRootVelocityInBaseFrame( + size_t footIndex, const base_coordinate_s_t& baseTwistInBaseFrame) const { + const auto b_baseTolegRoot = baseToLegRootInBaseFrame(footIndex); + return getLinearVelocity(baseTwistInBaseFrame) + getAngularVelocity(baseTwistInBaseFrame).cross(b_baseTolegRoot); +} + +template +vector3_s_t KinematicsModelBase::legRootVelocityInOriginFrame( + size_t footIndex, const base_coordinate_s_t& basePoseInOriginFrame, + const base_coordinate_s_t& baseTwistInBaseFrame) const { + const vector3_s_t b_legRootVelocity = legRootVelocityInBaseFrame(footIndex, baseTwistInBaseFrame); + return rotateVectorBaseToOrigin(b_legRootVelocity, getOrientation(basePoseInOriginFrame)); +} + +template +feet_array_t> KinematicsModelBase::positionBaseToFeetInBaseFrame( + const joint_coordinate_s_t& jointPositions) const { + feet_array_t> baseToFeetPositions; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + baseToFeetPositions[i] = positionBaseToFootInBaseFrame(i, jointPositions); + } + return baseToFeetPositions; +} + +template +vector3_s_t KinematicsModelBase::footPositionInOriginFrame(size_t footIndex, + const base_coordinate_s_t& basePose, + const joint_coordinate_s_t& jointPositions) const { + const vector3_s_t o_basePosition = getPositionInOrigin(basePose); + + const vector3_s_t b_baseToFoot = positionBaseToFootInBaseFrame(footIndex, jointPositions); + const vector3_s_t o_baseToFoot = rotateVectorBaseToOrigin(b_baseToFoot, getOrientation(basePose)); + return o_baseToFoot + o_basePosition; +} + +template +matrix3_s_t KinematicsModelBase::footOrientationInOriginFrame( + size_t footIndex, const base_coordinate_s_t& basePose, const joint_coordinate_s_t& jointPositions) const { + const matrix3_s_t o_R_b = rotationMatrixBaseToOrigin(getOrientation(basePose)); + return o_R_b * footOrientationInBaseFrame(footIndex, jointPositions); +} + +template +feet_array_t> KinematicsModelBase::feetPositionsInOriginFrame( + const base_coordinate_s_t& basePoseInOriginFrame, const joint_coordinate_s_t& jointPositions) const { + const vector3_s_t o_basePosition = getPositionInOrigin(basePoseInOriginFrame); + const vector3_s_t baseOrientation = getOrientation(basePoseInOriginFrame); + + feet_array_t> feetPositionsInOriginFrame; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + vector3_s_t b_baseToFoot = positionBaseToFootInBaseFrame(i, jointPositions); + vector3_s_t o_baseToFoot = rotateVectorBaseToOrigin(b_baseToFoot, baseOrientation); + feetPositionsInOriginFrame[i] = o_baseToFoot + o_basePosition; + } + return feetPositionsInOriginFrame; +} + +template +typename KinematicsModelBase::joint_jacobian_t KinematicsModelBase::baseToFootJacobianInBaseFrame( + size_t footIndex, const joint_coordinate_s_t& jointPositions) const { + joint_jacobian_t footJacobian = joint_jacobian_t::Zero(); + const auto footStartIdx = 3 * footIndex; + footJacobian.template block<6, 3>(0, footStartIdx) = baseToFootJacobianBlockInBaseFrame(footIndex, jointPositions); + return footJacobian; +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +vector3_s_t KinematicsModelBase::footVelocityRelativeToBaseInBaseFrame( + size_t footIndex, const joint_coordinate_s_t& jointPositions, const joint_coordinate_s_t& jointVelocities) const { + const auto b_baseToFootJacobianBlock = baseToFootJacobianBlockInBaseFrame(footIndex, jointPositions); + const auto legStartIdx = 3 * footIndex; + return b_baseToFootJacobianBlock.template bottomRows<3>() * jointVelocities.template segment<3>(legStartIdx); +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +vector3_s_t KinematicsModelBase::footVelocityInBaseFrame(size_t footIndex, + const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const { + const vector3_s_t b_footRelativeVelocity = footVelocityRelativeToBaseInBaseFrame(footIndex, jointPositions, jointVelocities); + const vector3_s_t b_baseToFoot = positionBaseToFootInBaseFrame(footIndex, jointPositions); + return b_footRelativeVelocity + getLinearVelocity(baseTwistInBaseFrame) + getAngularVelocity(baseTwistInBaseFrame).cross(b_baseToFoot); +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +vector3_s_t KinematicsModelBase::footVelocityInOriginFrame( + size_t footIndex, const base_coordinate_s_t& basePoseInOriginFrame, const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, const joint_coordinate_s_t& jointVelocities) const { + const vector3_s_t b_footVelocity = footVelocityInBaseFrame(footIndex, baseTwistInBaseFrame, jointPositions, jointVelocities); + return rotateVectorBaseToOrigin(b_footVelocity, getOrientation(basePoseInOriginFrame)); +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +vector3_s_t KinematicsModelBase::footVelocityInFootFrame(size_t footIndex, + const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, + const joint_coordinate_s_t& jointVelocities) const { + const vector3_s_t b_footVelocity = footVelocityInBaseFrame(footIndex, baseTwistInBaseFrame, jointPositions, jointVelocities); + const matrix3_s_t foot_R_b = footOrientationInBaseFrame(footIndex, jointPositions).transpose(); + return foot_R_b * b_footVelocity; +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +feet_array_t> KinematicsModelBase::feetVelocitiesInOriginFrame( + const base_coordinate_s_t& basePoseInOriginFrame, const base_coordinate_s_t& baseTwistInBaseFrame, + const joint_coordinate_s_t& jointPositions, const joint_coordinate_s_t& jointVelocities) const { + std::array, 4> feetVelocitiesInOriginFrame; + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + feetVelocitiesInOriginFrame[i] = + footVelocityInOriginFrame(i, basePoseInOriginFrame, baseTwistInBaseFrame, jointPositions, jointVelocities); + } + return feetVelocitiesInOriginFrame; +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +std::vector::CollisionSphere> KinematicsModelBase::collisionSpheresInOriginFrame( + const base_coordinate_s_t& basePoseInOriginFrame, const joint_coordinate_s_t& jointPositions) const { + const vector3_s_t o_basePosition = getPositionInOrigin(basePoseInOriginFrame); + const vector3_s_t baseOrientation = getOrientation(basePoseInOriginFrame); + + auto collisionSpheres = collisionSpheresInBaseFrame(jointPositions); + for (auto& sphere : collisionSpheres) { + sphere.position = rotateVectorBaseToOrigin(sphere.position, baseOrientation) + o_basePosition; + } + + return collisionSpheres; +} + +///******************************************************************************************************/ +///******************************************************************************************************/ +///******************************************************************************************************/ +template +std::vector::CollisionSphere> KinematicsModelBase::collisionSpheresInBaseFrame( + const joint_coordinate_s_t& jointPositions) const { + return {}; +} + +template class KinematicsModelBase; +template class KinematicsModelBase; + +} // end of namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ModelSettings.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ModelSettings.cpp new file mode 100644 index 000000000..ff28646f9 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/ModelSettings.cpp @@ -0,0 +1,84 @@ +// +// Created by rgrandia on 24.10.19. +// + +#include "ocs2_switched_model_interface/core/ModelSettings.h" + +#include +#include + +#include +#include + +#include + +namespace switched_model { + +std::string toAlgorithmName(Algorithm type) { + static const std::unordered_map map{{Algorithm::DDP, "DDP"}, {Algorithm::SQP, "SQP"}}; + return map.at(type); +} + +Algorithm fromAlgorithmName(std::string name) { + static const std::unordered_map map{{"DDP", Algorithm::DDP}, {"SQP", Algorithm::SQP}}; + std::transform(name.begin(), name.end(), name.begin(), ::toupper); + return map.at(name); +} + +ModelSettings loadModelSettings(const std::string& filename, bool verbose) { + ModelSettings modelSettings; + + boost::property_tree::ptree pt; + boost::property_tree::read_info(filename, pt); + + const std::string prefix{"model_settings."}; + + if (verbose) { + std::cerr << "\n #### Robot Model Settings:" << std::endl; + std::cerr << " #### ==================================================" << std::endl; + } + + std::string algorithmName = toAlgorithmName(modelSettings.algorithm_); + ocs2::loadData::loadPtreeValue(pt, algorithmName, prefix + "algorithm", verbose); + modelSettings.algorithm_ = fromAlgorithmName(algorithmName); + + ocs2::loadData::loadPtreeValue(pt, modelSettings.phaseTransitionStanceTime_, prefix + "phaseTransitionStanceTime", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.recompileLibraries_, prefix + "recompileLibraries", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.robotName_, prefix + "robotName", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.autodiffLibraryFolder_, prefix + "autodiffLibraryFolder", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.analyticalInverseKinematics_, prefix + "analyticalInverseKinematics", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.frictionCoefficient_, prefix + "frictionCoefficient", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.coneRegularization_, prefix + "coneRegularization", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.gripperForce_, prefix + "gripperForce", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muFrictionCone_, prefix + "muFrictionCone", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaFrictionCone_, prefix + "deltaFrictionCone", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muFootPlacement_, prefix + "muFootPlacement", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaFootPlacement_, prefix + "deltaFootPlacement", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muSdf_, prefix + "muSdf", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaSdf_, prefix + "deltaSdf", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muJointsPosition_, prefix + "muJointsPosition", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaJointsPosition_, prefix + "deltaJointsPosition", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muJointsVelocity_, prefix + "muJointsVelocity", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaJointsVelocity_, prefix + "deltaJointsVelocity", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.muJointsTorque_, prefix + "muJointsTorque", verbose); + ocs2::loadData::loadPtreeValue(pt, modelSettings.deltaJointsTorque_, prefix + "deltaJointsTorque", verbose); + ocs2::loadData::loadEigenMatrix(filename, prefix + "joint_lower_limits", modelSettings.lowerJointLimits_); + ocs2::loadData::loadEigenMatrix(filename, prefix + "joint_upper_limits", modelSettings.upperJointLimits_); + ocs2::loadData::loadEigenMatrix(filename, prefix + "joint_velocity_limits", modelSettings.jointVelocityLimits); + ocs2::loadData::loadEigenMatrix(filename, prefix + "joint_torque_limits", modelSettings.jointTorqueLimits); + + if (verbose) { + std::cerr << " joint lower limits: " << modelSettings.lowerJointLimits_.transpose() << "\n"; + std::cerr << " joint upper limits: " << modelSettings.upperJointLimits_.transpose() << "\n"; + std::cerr << " joint velocity limits: " << modelSettings.jointVelocityLimits.transpose() << "\n"; + std::cerr << " joint torque limits: " << modelSettings.jointTorqueLimits.transpose() << "\n"; + } + + if (verbose) { + std::cerr << " #### ================================================ ####" << std::endl; + } + + return modelSettings; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/SwitchedModelPrecomputation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/SwitchedModelPrecomputation.cpp new file mode 100644 index 000000000..11a9dd3c3 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/SwitchedModelPrecomputation.cpp @@ -0,0 +1,290 @@ +// +// Created by rgrandia on 21.09.21. +// + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" + +#include +#include + +namespace switched_model { + +SwitchedModelPreComputation::SwitchedModelPreComputation(const SwingTrajectoryPlanner& swingTrajectoryPlanner, + const kinematic_model_t& kinematicModel, + const ad_kinematic_model_t& adKinematicModel, const com_model_t& comModel, + const ad_com_model_t& adComModel, ModelSettings settings) + : swingTrajectoryPlannerPtr_(&swingTrajectoryPlanner), robotMass_(comModel.totalMass()) { + // intermediate linear outputs + std::string intermediateLibName = settings.robotName_ + "_Precomputation_intermediateLinearOutputs"; + auto intermediateDiffFunc = [&](const ad_vector_t& x, ad_vector_t& y) { + // Extract elements from taped input + comkino_state_ad_t state = x.segment(0, STATE_DIM); + comkino_input_ad_t input = x.segment(STATE_DIM, INPUT_DIM); + intermediateLinearOutputs(adComModel, adKinematicModel, state, input, y); + }; + intermediateLinearOutputAdInterface_.reset( + new ocs2::CppAdInterface(intermediateDiffFunc, STATE_DIM + INPUT_DIM, intermediateLibName, settings.autodiffLibraryFolder_)); + tapedStateInput_.resize(STATE_DIM + INPUT_DIM); + + const auto initCollisions = kinematicModel.collisionSpheresInBaseFrame(joint_coordinate_t::Zero()); + for (const auto& collision : initCollisions) { + collisionRadii_.push_back(collision.radius); + } + + // Resize collision containers + const size_t maxNumCollisions = NUM_CONTACT_POINTS + collisionRadii_.size(); + collisionSpheresActive_.resize(maxNumCollisions); + collisionSpheresInOriginFrame_.resize(maxNumCollisions); + collisionSpheresDerivative_.resize(maxNumCollisions); + + // pre jump linear outputs + std::string prejumpLibName = settings.robotName_ + "_Precomputation_prejumpLinearOutputs"; + auto prejumpDiffFunc = [&](const ad_vector_t& x, ad_vector_t& y) { prejumpLinearOutputs(adComModel, adKinematicModel, x, y); }; + prejumpLinearOutputAdInterface_.reset( + new ocs2::CppAdInterface(prejumpDiffFunc, STATE_DIM, prejumpLibName, settings.autodiffLibraryFolder_)); + + // Generate the models + const bool verbose = true; + const auto order = ocs2::CppAdInterface::ApproximationOrder::First; + if (settings.recompileLibraries_) { + intermediateLinearOutputAdInterface_->createModels(order, verbose); + prejumpLinearOutputAdInterface_->createModels(order, verbose); + } else { + intermediateLinearOutputAdInterface_->loadModelsIfAvailable(order, verbose); + prejumpLinearOutputAdInterface_->loadModelsIfAvailable(order, verbose); + } +} + +SwitchedModelPreComputation::SwitchedModelPreComputation(const SwitchedModelPreComputation& other) + : ocs2::PreComputation(other), + swingTrajectoryPlannerPtr_(other.swingTrajectoryPlannerPtr_), + intermediateLinearOutputAdInterface_(new ocs2::CppAdInterface(*other.intermediateLinearOutputAdInterface_)), + prejumpLinearOutputAdInterface_(new ocs2::CppAdInterface(*other.prejumpLinearOutputAdInterface_)), + collisionRadii_(other.collisionRadii_), + collisionSpheresActive_(other.collisionSpheresActive_), + collisionSpheresInOriginFrame_(other.collisionSpheresInOriginFrame_), + collisionSpheresDerivative_(other.collisionSpheresDerivative_), + tapedStateInput_(other.tapedStateInput_), + robotMass_(other.robotMass_) {} + +void SwitchedModelPreComputation::request(ocs2::RequestSet request, scalar_t t, const vector_t& x, const vector_t& u) { + updateFeetPhases(t); + + if (request.containsAny(ocs2::Request::Cost + ocs2::Request::Constraint + ocs2::Request::SoftConstraint)) { + updateMotionReference(t); + + tapedStateInput_ << x, u; + + updateIntermediateLinearOutputs(t, tapedStateInput_); + if (request.contains(ocs2::Request::Approximation)) { + updateIntermediateLinearOutputDerivatives(t, tapedStateInput_); + } + } +} + +void SwitchedModelPreComputation::requestPreJump(ocs2::RequestSet request, scalar_t t, const vector_t& x) { + updateFeetPhases(t); + + if (request.containsAny(ocs2::Request::Cost + ocs2::Request::Constraint + ocs2::Request::SoftConstraint)) { + updateMotionReference(t); + + updatePrejumpLinearOutputs(t, x); + if (request.contains(ocs2::Request::Approximation)) { + updatePrejumpLinearOutputDerivatives(t, x); + } + } +} + +void SwitchedModelPreComputation::requestFinal(ocs2::RequestSet request, scalar_t t, const vector_t& x) { + updateFeetPhases(t); + + if (request.containsAny(ocs2::Request::Cost + ocs2::Request::Constraint + ocs2::Request::SoftConstraint)) { + updateMotionReference(t); + } +} + +void SwitchedModelPreComputation::updateFeetPhases(scalar_t t) { + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + feetPhases_[leg] = &swingTrajectoryPlannerPtr_->getFootPhase(leg, t); + const auto& footPhase = *feetPhases_[leg]; + contactFlags_[leg] = footPhase.contactFlag(); + surfaceNormalsInOriginFrame_[leg] = footPhase.normalDirectionInWorldFrame(t); + footTangentialConstraintInWorldFrame_[leg] = footPhase.getFootTangentialConstraintInWorldFrame(); + } +} + +void SwitchedModelPreComputation::updateMotionReference(scalar_t t) { + // Interpolate reference + stateReference_ = swingTrajectoryPlannerPtr_->getTargetTrajectories().getDesiredState(t); + vector_t uRef = swingTrajectoryPlannerPtr_->getTargetTrajectories().getDesiredInput(t); + + // Extract elements from reference + const auto basePose = getBasePose(stateReference_); + const auto baseTwist = getBaseLocalVelocities(stateReference_); + const auto eulerAngles = getOrientation(basePose); + const auto qJoints = getJointPositions(stateReference_); + const auto dqJoints = getJointVelocities(uRef); + + // If the contact force reference has zero values, overwrite it. + if (uRef.head<3 * NUM_CONTACT_POINTS>().isZero()) { + uRef.head<3 * NUM_CONTACT_POINTS>() = weightCompensatingInputs(robotMass_, contactFlags_, eulerAngles).head<3 * NUM_CONTACT_POINTS>(); + } + + motionReference_.eulerXYZ = eulerAngles; + motionReference_.comPosition = getPositionInOrigin(basePose); + motionReference_.comAngularVelocity = rotateVectorBaseToOrigin(getAngularVelocity(baseTwist), eulerAngles); + motionReference_.comLinearVelocity = rotateVectorBaseToOrigin(getLinearVelocity(baseTwist), eulerAngles); + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const auto& footPhase = getFootPhase(leg); // already updated in updateFeetPhases + motionReference_.jointPosition[leg] = qJoints.template segment<3>(3 * leg); + motionReference_.footPosition[leg] = footPhase.getPositionInWorld(t); + motionReference_.jointVelocity[leg] = dqJoints.template segment<3>(3 * leg); + motionReference_.footVelocity[leg] = footPhase.getVelocityInWorld(t); + motionReference_.contactForce[leg] = uRef.template segment<3>(3 * leg); + } +} + +void SwitchedModelPreComputation::intermediateLinearOutputs(const ad_com_model_t& adComModel, const ad_kinematic_model_t& adKinematicsModel, + const ad_vector_t& state, const ad_vector_t& input, ad_vector_t& outputs) { + // Copy to fixed size + comkino_state_ad_t x = state; + comkino_input_ad_t u = input; + + // Extract elements from state + const base_coordinate_ad_t basePose = getBasePose(x); + const base_coordinate_ad_t baseTwist = getBaseLocalVelocities(x); + const joint_coordinate_ad_t qJoints = getJointPositions(x); + const joint_coordinate_ad_t dqJoints = getJointVelocities(u); + const feet_array_t contactForcesInBase = toArray(u.head<3 * NUM_CONTACT_POINTS>()); + + const auto o_feetPositionsAsArray = adKinematicsModel.feetPositionsInOriginFrame(basePose, qJoints); + const auto o_footVelocitiesAsArray = adKinematicsModel.feetVelocitiesInOriginFrame(basePose, baseTwist, qJoints, dqJoints); + const auto jointTorques = torqueApproximation(qJoints, contactForcesInBase, adKinematicsModel); + const auto o_collisions = adKinematicsModel.collisionSpheresInOriginFrame(basePose, qJoints); + + const int numberOfOutputs = 3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS + JOINT_COORDINATE_SIZE + 3 * o_collisions.size(); + outputs.resize(numberOfOutputs); + + outputs.head<3 * NUM_CONTACT_POINTS>() = fromArray(o_feetPositionsAsArray); + outputs.segment<3 * NUM_CONTACT_POINTS>(3 * NUM_CONTACT_POINTS) = fromArray(o_footVelocitiesAsArray); + outputs.segment(3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS) = jointTorques; + + int i = 3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS + JOINT_COORDINATE_SIZE; + for (const auto& sphere : o_collisions) { + outputs.segment<3>(i) = sphere.position; + i += 3; + } +} + +void SwitchedModelPreComputation::updateIntermediateLinearOutputs(scalar_t t, const vector_t& tapedStateInput) { + // Evaluate autodiff + const auto intermediateLinearOutputs = intermediateLinearOutputAdInterface_->getFunctionValue(tapedStateInput); + + // Read feet positions, add swing feet as collision bodies + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * leg; + feetPositionInOriginFrame_[leg] = intermediateLinearOutputs.segment<3>(indexInOutputs); + const auto& footPhase = getFootPhase(leg); + collisionSpheresActive_[leg] = !footPhase.contactFlag(); + if (collisionSpheresActive_[leg]) { + collisionSpheresInOriginFrame_[leg].position = feetPositionInOriginFrame_[leg]; + collisionSpheresInOriginFrame_[leg].radius = footPhase.getMinimumFootClearance(t); + } + } + + // Read feet Velocities + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * (NUM_CONTACT_POINTS + leg); + feetVelocitiesInOriginFrame_[leg] = intermediateLinearOutputs.segment<3>(indexInOutputs); + } + + // Read joint Torques + jointTorques_ = intermediateLinearOutputs.segment(3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS); + + // Read collision bodies (excluding the feet) + for (int collisionIndex = 0; collisionIndex < collisionRadii_.size(); ++collisionIndex) { + const int indexInOutputs = JOINT_COORDINATE_SIZE + 3 * (NUM_CONTACT_POINTS + NUM_CONTACT_POINTS + collisionIndex); + const auto collisionGlobalId = NUM_CONTACT_POINTS + collisionIndex; + collisionSpheresActive_[collisionGlobalId] = true; + collisionSpheresInOriginFrame_[collisionGlobalId].position = intermediateLinearOutputs.segment<3>(indexInOutputs); + collisionSpheresInOriginFrame_[collisionGlobalId].radius = collisionRadii_[collisionIndex]; + } +} + +void SwitchedModelPreComputation::updateIntermediateLinearOutputDerivatives(scalar_t t, const vector_t& tapedStateInput) { + // Evaluate autodiff + const auto intermediateLinearOutputDerivatives = intermediateLinearOutputAdInterface_->getJacobian(tapedStateInput); + + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * leg; + feetPositionInOriginFrameStateDerivative_[leg] = intermediateLinearOutputDerivatives.block<3, STATE_DIM>(indexInOutputs, 0); + const auto& footPhase = getFootPhase(leg); + collisionSpheresActive_[leg] = !footPhase.contactFlag(); + if (collisionSpheresActive_[leg]) { + collisionSpheresDerivative_[leg] = feetPositionInOriginFrameStateDerivative_[leg]; + } + } + + // Read feet Velocities + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * (NUM_CONTACT_POINTS + leg); + feetVelocitiesInOriginFrameDerivative_[leg].f = feetVelocitiesInOriginFrame_[leg]; + feetVelocitiesInOriginFrameDerivative_[leg].dfdx = intermediateLinearOutputDerivatives.block<3, STATE_DIM>(indexInOutputs, 0); + feetVelocitiesInOriginFrameDerivative_[leg].dfdu = intermediateLinearOutputDerivatives.block<3, INPUT_DIM>(indexInOutputs, STATE_DIM); + } + + // Read joint Torques + jointTorquesDerivative_.f = jointTorques_; + jointTorquesDerivative_.dfdx = + intermediateLinearOutputDerivatives.block(3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS, 0); + jointTorquesDerivative_.dfdu = intermediateLinearOutputDerivatives.block( + 3 * NUM_CONTACT_POINTS + 3 * NUM_CONTACT_POINTS, STATE_DIM); + + // Read collision bodies (excluding the feet) + for (int collisionIndex = 0; collisionIndex < collisionRadii_.size(); ++collisionIndex) { + const int indexInOutputs = JOINT_COORDINATE_SIZE + 3 * (NUM_CONTACT_POINTS + NUM_CONTACT_POINTS + collisionIndex); + const auto collisionGlobalId = NUM_CONTACT_POINTS + collisionIndex; + collisionSpheresActive_[collisionGlobalId] = true; + collisionSpheresDerivative_[collisionGlobalId] = intermediateLinearOutputDerivatives.block<3, STATE_DIM>(indexInOutputs, 0); + } +} + +void SwitchedModelPreComputation::prejumpLinearOutputs(const ad_com_model_t& adComModel, const ad_kinematic_model_t& adKinematicsModel, + const ad_vector_t& state, ad_vector_t& outputs) { + // Copy to fixed size + comkino_state_ad_t x = state; + + // Extract elements from state + const base_coordinate_ad_t basePose = getBasePose(x); + const joint_coordinate_ad_t qJoints = getJointPositions(x); + + const auto o_feetPositionsAsArray = adKinematicsModel.feetPositionsInOriginFrame(basePose, qJoints); + + const int numberOfOutputs = 3 * NUM_CONTACT_POINTS; + outputs.resize(numberOfOutputs); + + outputs.head<3 * NUM_CONTACT_POINTS>() = fromArray(o_feetPositionsAsArray); +} + +void SwitchedModelPreComputation::updatePrejumpLinearOutputs(scalar_t t, const vector_t& state) { + // Evaluate autodiff + const auto prejumpLinearOutputs = prejumpLinearOutputAdInterface_->getFunctionValue(state); + + // Read feet positions, add swing feet as collision bodies + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * leg; + feetPositionInOriginFrame_[leg] = prejumpLinearOutputs.segment<3>(indexInOutputs); + } +} + +void SwitchedModelPreComputation::updatePrejumpLinearOutputDerivatives(scalar_t t, const vector_t& state) { + // Evaluate autodiff + const auto prejumpLinearOutputDerivatives = prejumpLinearOutputAdInterface_->getJacobian(state); + + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int indexInOutputs = 3 * leg; + feetPositionInOriginFrameStateDerivative_[leg] = prejumpLinearOutputDerivatives.block<3, STATE_DIM>(indexInOutputs, 0); + } +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/TorqueApproximation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/TorqueApproximation.cpp new file mode 100644 index 000000000..93b82e0a4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/core/TorqueApproximation.cpp @@ -0,0 +1,31 @@ +// +// Created by rgrandia on 08.12.21. +// + +#include "ocs2_switched_model_interface/core/TorqueApproximation.h" + +namespace switched_model { + +template +joint_coordinate_s_t torqueApproximation(const joint_coordinate_s_t& jointPositions, + const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics) { + joint_coordinate_s_t torques; + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + // Part of the foot Jacobian that corresponds to the joints in this leg. + const auto b_baseToFootJacobianBlock = kinematics.baseToFootJacobianBlockInBaseFrame(leg, jointPositions); + + // tau = -J^T * F, (bottom 3 rows = translational part) + torques.template segment<3>(3 * leg) = -b_baseToFootJacobianBlock.bottomRows(3).transpose() * contactForcesInBase[leg]; + } + return torques; +} + +template joint_coordinate_s_t torqueApproximation(const joint_coordinate_s_t& jointPositions, + const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics); +template joint_coordinate_s_t torqueApproximation( + const joint_coordinate_s_t& jointPositions, const feet_array_t>& contactForcesInBase, + const KinematicsModelBase& kinematics); + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/CollisionAvoidanceCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/CollisionAvoidanceCost.cpp new file mode 100644 index 000000000..46d2a5144 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/CollisionAvoidanceCost.cpp @@ -0,0 +1,90 @@ +// +// Created by rgrandia on 26.06.20. +// + +#include "ocs2_switched_model_interface/cost/CollisionAvoidanceCost.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h" + +namespace switched_model { + +CollisionAvoidanceCost::CollisionAvoidanceCost(ocs2::RelaxedBarrierPenalty::Config settings) + : penalty_(new ocs2::RelaxedBarrierPenalty(settings)) {} + +CollisionAvoidanceCost::CollisionAvoidanceCost(const CollisionAvoidanceCost& rhs) : penalty_(rhs.penalty_->clone()) {} + +CollisionAvoidanceCost* CollisionAvoidanceCost::clone() const { + return new CollisionAvoidanceCost(*this); +} + +scalar_t CollisionAvoidanceCost::getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + const auto* sdfPtr = switchedModelPreComp.getSignedDistanceField(); + + scalar_t cost(0.0); + if (sdfPtr != nullptr) { + const auto& collisionSpheresActive = switchedModelPreComp.collisionSpheresActive(); + const auto& collisionSpheres = switchedModelPreComp.collisionSpheresInOriginFrame(); + + for (size_t i = 0; i < collisionSpheres.size(); ++i) { + if (collisionSpheresActive[i]) { + const auto& collisionSphere = collisionSpheres[i]; + const auto sdfDistance = sdfPtr->value(collisionSphere.position); + const auto h_sdf = sdfDistance - collisionSphere.radius; + + SingleLinearStateInequalitySoftConstraint linearStateInequalitySoftConstraint; + linearStateInequalitySoftConstraint.penalty = penalty_.get(); + // linearStateInequalitySoftConstraint.A = Leave empty + linearStateInequalitySoftConstraint.h = h_sdf; + + cost += switched_model::getValue(linearStateInequalitySoftConstraint, collisionSphere.position); + } + } + } + + return cost; +} + +ScalarFunctionQuadraticApproximation CollisionAvoidanceCost::getQuadraticApproximation(scalar_t time, const vector_t& state, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + + ScalarFunctionQuadraticApproximation cost; + cost.f = 0.0; + cost.dfdx = vector_t::Zero(STATE_DIM); + cost.dfdxx = matrix_t::Zero(STATE_DIM, STATE_DIM); + + const auto* sdfPtr = switchedModelPreComp.getSignedDistanceField(); + + if (sdfPtr != nullptr) { + const auto& collisionSpheresActive = switchedModelPreComp.collisionSpheresActive(); + const auto& collisionSpheres = switchedModelPreComp.collisionSpheresInOriginFrame(); + const auto& collisionSphereDerivatives = switchedModelPreComp.collisionSpheresInOriginFrameStateDerivative(); + for (size_t i = 0; i < collisionSpheres.size(); ++i) { + if (collisionSpheresActive[i]) { + const auto& collisionSphere = collisionSpheres[i]; + const auto& collisionSphereDerivative = collisionSphereDerivatives[i]; + const auto sdfFirstOrder = sdfPtr->valueAndDerivative(collisionSphere.position); + const auto h_sdf = sdfFirstOrder.first - collisionSphere.radius; + + SingleLinearStateInequalitySoftConstraint linearStateInequalitySoftConstraint; + linearStateInequalitySoftConstraint.penalty = penalty_.get(); + linearStateInequalitySoftConstraint.A = sdfFirstOrder.second.transpose(); + linearStateInequalitySoftConstraint.h = h_sdf; + + const auto targetcost = switched_model::getQuadraticApproximation(linearStateInequalitySoftConstraint, collisionSphere.position, + collisionSphereDerivative); + cost.f += targetcost.f; + cost.dfdx += targetcost.dfdx; + cost.dfdxx += targetcost.dfdxx; + } + } + } + + return cost; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FootPlacementCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FootPlacementCost.cpp new file mode 100644 index 000000000..0608bc487 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FootPlacementCost.cpp @@ -0,0 +1,77 @@ +// +// Created by rgrandia on 26.06.20. +// + +#include "ocs2_switched_model_interface/cost/FootPlacementCost.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h" + +namespace switched_model { + +FootPlacementCost::FootPlacementCost(ocs2::RelaxedBarrierPenalty::Config settings) + : polygonPenalty_(new ocs2::RelaxedBarrierPenalty(settings)) {} + +FootPlacementCost::FootPlacementCost(const FootPlacementCost& rhs) : polygonPenalty_(rhs.polygonPenalty_->clone()) {} + +FootPlacementCost* FootPlacementCost::clone() const { + return new FootPlacementCost(*this); +} + +scalar_t FootPlacementCost::getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + + scalar_t cost(0.0); + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const auto* constraintMatrixPtr = switchedModelPreComp.getFootTangentialConstraintInWorldFrame(leg); + + if (constraintMatrixPtr != nullptr) { + const auto& footPosition = switchedModelPreComp.footPositionInOriginFrame(leg); + + LinearStateInequalitySoftConstraint linearStateInequalitySoftConstraint; + linearStateInequalitySoftConstraint.penalty = polygonPenalty_.get(); + linearStateInequalitySoftConstraint.A = constraintMatrixPtr->A; + linearStateInequalitySoftConstraint.h = constraintMatrixPtr->b; + linearStateInequalitySoftConstraint.h.noalias() += constraintMatrixPtr->A * footPosition; + + cost += switched_model::getValue(linearStateInequalitySoftConstraint, footPosition); + } + } + + return cost; +} + +ScalarFunctionQuadraticApproximation FootPlacementCost::getQuadraticApproximation(scalar_t time, const vector_t& state, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + + ScalarFunctionQuadraticApproximation cost; + cost.f = 0.0; + cost.dfdx = vector_t::Zero(STATE_DIM); + cost.dfdxx = matrix_t::Zero(STATE_DIM, STATE_DIM); + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const auto* constraintMatrixPtr = switchedModelPreComp.getFootTangentialConstraintInWorldFrame(leg); + + if (constraintMatrixPtr != nullptr) { + const auto& footPosition = switchedModelPreComp.footPositionInOriginFrame(leg); + const auto& footJacobian = switchedModelPreComp.footPositionInOriginFrameStateDerivative(leg); + + LinearStateInequalitySoftConstraint linearStateInequalitySoftConstraint; + linearStateInequalitySoftConstraint.penalty = polygonPenalty_.get(); + linearStateInequalitySoftConstraint.A = constraintMatrixPtr->A; + linearStateInequalitySoftConstraint.h = constraintMatrixPtr->b; + linearStateInequalitySoftConstraint.h.noalias() += constraintMatrixPtr->A * footPosition; + + const auto targetcost = switched_model::getQuadraticApproximation(linearStateInequalitySoftConstraint, footPosition, footJacobian); + cost.f += targetcost.f; + cost.dfdx += targetcost.dfdx; + cost.dfdxx += targetcost.dfdxx; + } + } + + return cost; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FrictionConeCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FrictionConeCost.cpp new file mode 100644 index 000000000..d21700691 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/FrictionConeCost.cpp @@ -0,0 +1,101 @@ +// +// Created by rgrandia on 22.09.21. +// + +#include "ocs2_switched_model_interface/cost/FrictionConeCost.h" + +#include +#include + +namespace switched_model { + +FrictionConeCost::FrictionConeCost(friction_cone::Config config, const SwitchedModelModeScheduleManager& modeScheduleManager, + std::unique_ptr penaltyFunction) + : config_(config), modeScheduleManager_(&modeScheduleManager), penalty_(std::move(penaltyFunction)) {} + +FrictionConeCost::FrictionConeCost(const FrictionConeCost& rhs) + : config_(rhs.config_), modeScheduleManager_(rhs.modeScheduleManager_), penalty_(rhs.penalty_->clone()) {} + +FrictionConeCost* FrictionConeCost::clone() const { + return new FrictionConeCost(*this); +} + +bool FrictionConeCost::isActive(scalar_t time) const { + return numberOfClosedContacts(modeScheduleManager_->getContactFlags(time)) > 0; +} + +scalar_t FrictionConeCost::getValue(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::TargetTrajectories& targetTrajectories, const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + + const vector3_t eulerXYZ = getOrientation(getBasePose(state)); + const matrix3_t w_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + + const auto& contactFlags = switchedModelPreComp.getContactFlags(); + + scalar_t cost = 0.0; + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + if (contactFlags[leg]) { + const int legIdx = 3 * leg; + + const matrix3_t t_R_w = orientationWorldToTerrainFromSurfaceNormalInWorld(switchedModelPreComp.getSurfaceNormalInOriginFrame(leg)); + const vector3_t forcesInWorld = w_R_b * input.segment(legIdx, 3); + const vector3_t forcesInTerrain = t_R_w * forcesInWorld; + const scalar_t h = frictionConeConstraint(config_, forcesInTerrain); + cost += penalty_->getValue(time, h); + } + } + + return cost; +} + +ScalarFunctionQuadraticApproximation FrictionConeCost::getQuadraticApproximation(scalar_t time, const vector_t& state, + const vector_t& input, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + + const vector3_t eulerXYZ = getOrientation(getBasePose(state)); + const matrix3_t w_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + + const auto& contactFlags = switchedModelPreComp.getContactFlags(); + + ScalarFunctionQuadraticApproximation penaltyApproximation = ScalarFunctionQuadraticApproximation::Zero(STATE_DIM, INPUT_DIM); + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + if (contactFlags[leg]) { + const int legIdx = 3 * leg; + + const matrix3_t t_R_w = orientationWorldToTerrainFromSurfaceNormalInWorld(switchedModelPreComp.getSurfaceNormalInOriginFrame(leg)); + const vector3_t forcesInBodyFrame = input.segment(legIdx, 3); + const vector3_t forcesInWorld = w_R_b * forcesInBodyFrame; + const vector3_t forcesInTerrain = t_R_w * forcesInWorld; + const auto coneDerivatives = frictionConeDerivatives(config_, forcesInTerrain, t_R_w, w_R_b, eulerXYZ, forcesInBodyFrame); + + const scalar_t penaltyValue = penalty_->getValue(time, coneDerivatives.coneConstraint); + const scalar_t penaltyDerivative = penalty_->getDerivative(time, coneDerivatives.coneConstraint); + const scalar_t penaltySecondDerivative = penalty_->getSecondDerivative(time, coneDerivatives.coneConstraint); + + const vector3_t penaltySecondDev_dhdx = penaltySecondDerivative * coneDerivatives.dCone_deuler; + + penaltyApproximation.f += penaltyValue; + + penaltyApproximation.dfdx.segment<3>(0) += penaltyDerivative * coneDerivatives.dCone_deuler; + + penaltyApproximation.dfdu.segment<3>(legIdx) = penaltyDerivative * coneDerivatives.dCone_du; + + penaltyApproximation.dfdxx.block<3, 3>(0, 0) += penaltyDerivative * coneDerivatives.d2Cone_deuler2; + penaltyApproximation.dfdxx.block<3, 3>(0, 0).noalias() += penaltySecondDev_dhdx * coneDerivatives.dCone_deuler.transpose(); + + penaltyApproximation.dfdux.block<3, 3>(legIdx, 0) = penaltyDerivative * coneDerivatives.d2Cone_dudeuler; + penaltyApproximation.dfdux.block<3, 3>(legIdx, 0).noalias() += coneDerivatives.dCone_du * penaltySecondDev_dhdx.transpose(); + + penaltyApproximation.dfduu.block<3, 3>(legIdx, legIdx) = penaltyDerivative * coneDerivatives.d2Cone_du2; + penaltyApproximation.dfduu.block<3, 3>(legIdx, legIdx).noalias() += + penaltySecondDerivative * coneDerivatives.dCone_du * coneDerivatives.dCone_du.transpose(); + } + } + + return penaltyApproximation; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/LinearStateInequalitySoftConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/LinearStateInequalitySoftConstraint.cpp new file mode 100644 index 000000000..67e3d4f4b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/LinearStateInequalitySoftConstraint.cpp @@ -0,0 +1,64 @@ +// +// Created by rgrandia on 26.07.21. +// + +#include "ocs2_switched_model_interface/cost/LinearStateInequalitySoftconstraint.h" + +namespace switched_model { + +scalar_t getValue(const LinearStateInequalitySoftConstraint& constraints, const vector_t& f) { + scalar_t cost(0.0); + for (int j = 0; j < constraints.h.size(); ++j) { // Loop through all faces of the constraint + cost += constraints.penalty->getValue(0.0, constraints.h(j)); + } + + return cost; +} + +scalar_t getValue(const SingleLinearStateInequalitySoftConstraint& constraint, const vector_t& f) { + return constraint.penalty->getValue(0.0, constraint.h); +} + +ScalarFunctionQuadraticApproximation getQuadraticApproximation(const LinearStateInequalitySoftConstraint& constraints, const vector_t& f, + const matrix_t& dfdx) { + ScalarFunctionQuadraticApproximation cost; + + const auto& h = constraints.h; + + cost.f = 0.0; + for (int j = 0; j < h.size(); ++j) { // Loop through all faces of the constraint + cost.f += constraints.penalty->getValue(0.0, h(j)); + } + + const auto penaltyDerivatives = h.unaryExpr([&](scalar_t hi) { return constraints.penalty->getDerivative(0.0, hi); }); + const vector_t taskSpaceDerivative = constraints.A.transpose() * penaltyDerivatives; + cost.dfdx.noalias() = dfdx.transpose() * taskSpaceDerivative; + + const auto penaltySecondDerivatives = h.unaryExpr([&](scalar_t hi) { return constraints.penalty->getSecondDerivative(0.0, hi); }); + const matrix_t scaledConstraint = penaltySecondDerivatives.asDiagonal() * constraints.A; + const matrix_t taskSpaceSecondDerivative = constraints.A.transpose() * scaledConstraint; + const matrix_t scaledJacobian = taskSpaceSecondDerivative * dfdx; + cost.dfdxx.noalias() = dfdx.transpose() * scaledJacobian; + + return cost; +} + +ScalarFunctionQuadraticApproximation getQuadraticApproximation(const SingleLinearStateInequalitySoftConstraint& constraint, + const vector_t& f, const matrix_t& dfdx) { + ScalarFunctionQuadraticApproximation cost; + + const auto& h = constraint.h; + + cost.f = constraint.penalty->getValue(0.0, constraint.h); + + const Eigen::Matrix taskSpaceDerivative = constraint.A.transpose() * constraint.penalty->getDerivative(0.0, h); + cost.dfdx.noalias() = dfdx.transpose() * taskSpaceDerivative; + + const matrix_t jacobian = constraint.A * dfdx; + const matrix_t scaledJacobian = constraint.penalty->getSecondDerivative(0.0, h) * jacobian; + cost.dfdxx.noalias() = jacobian.transpose() * scaledJacobian; + + return cost; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingCost.cpp new file mode 100644 index 000000000..26c5fb3d0 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingCost.cpp @@ -0,0 +1,149 @@ +// +// Created by rgrandia on 30.04.21. +// + +#include "ocs2_switched_model_interface/cost/MotionTrackingCost.h" + +#include +#include + +#include + +#include "ocs2_switched_model_interface/core/Rotations.h" +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/cost/CostElements.h" + +namespace switched_model { + +namespace { + +template +Eigen::Matrix computeMotionTargets(const comkino_state_s_t& x, const comkino_input_s_t& u, + const KinematicsModelBase& kinematics) { + // Extract elements from reference + const auto basePose = getBasePose(x); + const auto base_baseTwist = getBaseLocalVelocities(x); + const auto eulerAngles = getOrientation(basePose); + const auto qJoints = getJointPositions(x); + const auto dqJoints = getJointVelocities(u); + + CostElements motionTarget; + motionTarget.eulerXYZ = eulerAngles; + motionTarget.comPosition = getPositionInOrigin(basePose); + motionTarget.comAngularVelocity = rotateVectorBaseToOrigin(getAngularVelocity(base_baseTwist), eulerAngles); + motionTarget.comLinearVelocity = rotateVectorBaseToOrigin(getLinearVelocity(base_baseTwist), eulerAngles); + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + motionTarget.jointPosition[leg] = qJoints.template segment<3>(3 * leg); + motionTarget.footPosition[leg] = kinematics.footPositionInOriginFrame(leg, basePose, qJoints); + motionTarget.jointVelocity[leg] = dqJoints.template segment<3>(3 * leg); + motionTarget.footVelocity[leg] = kinematics.footVelocityInOriginFrame(leg, basePose, base_baseTwist, qJoints, dqJoints); + motionTarget.contactForce[leg] = u.template segment<3>(3 * leg); + } + return motionTarget.asVector(); +} + +} // namespace + +MotionTrackingCost::MotionTrackingCost(const Weights& settings, const ad_kinematic_model_t& adKinematicModel, + const ModelSettings& modelSettings) + : adKinematicModelPtr_(adKinematicModel.clone()), modelSettings_(modelSettings) { + // Weights are sqrt of settings + CostElements weightStruct; + weightStruct.eulerXYZ = settings.eulerXYZ.cwiseSqrt(); + weightStruct.comPosition = settings.comPosition.cwiseSqrt(); + weightStruct.comAngularVelocity = settings.comAngularVelocity.cwiseSqrt(); + weightStruct.comLinearVelocity = settings.comLinearVelocity.cwiseSqrt(); + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + weightStruct.jointPosition[leg] = settings.jointPosition[leg].cwiseSqrt(); + weightStruct.footPosition[leg] = settings.footPosition[leg].cwiseSqrt(); + weightStruct.jointVelocity[leg] = settings.jointVelocity[leg].cwiseSqrt(); + weightStruct.footVelocity[leg] = settings.footVelocity[leg].cwiseSqrt(); + weightStruct.contactForce[leg] = settings.contactForce[leg].cwiseSqrt(); + } + sqrtWeights_ = weightStruct.asVector(); + + initialize(STATE_DIM, INPUT_DIM, CostElements::Size() + sqrtWeights_.size(), + modelSettings_.robotName_ + "_MotionTrackingCost", modelSettings_.autodiffLibraryFolder_, modelSettings_.recompileLibraries_); +}; + +ocs2::vector_t MotionTrackingCost::getParameters(ocs2::scalar_t time, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const { + const auto& switchedModelPreComp = ocs2::cast(preComputation); + + ocs2::vector_t parameters(CostElements::Size() + sqrtWeights_.size()); + parameters << switchedModelPreComp.getMotionReference().asVector(), sqrtWeights_; + return parameters; +} + +MotionTrackingCost::MotionTrackingCost(const MotionTrackingCost& other) + : ocs2::StateInputCostGaussNewtonAd(other), + adKinematicModelPtr_(other.adKinematicModelPtr_->clone()), + sqrtWeights_(other.sqrtWeights_), + modelSettings_(other.modelSettings_) {} + +ocs2::ad_vector_t MotionTrackingCost::costVectorFunction(ocs2::ad_scalar_t time, const ocs2::ad_vector_t& state, + const ocs2::ad_vector_t& input, const ocs2::ad_vector_t& parameters) const { + auto referenceTargets = parameters.head(CostElements::Size()); + auto sqrtWeights = parameters.tail(sqrtWeights_.size()); + + const auto currentTargets = computeMotionTargets(state, input, *adKinematicModelPtr_); + ocs2::ad_vector_t errors = (currentTargets - referenceTargets).cwiseProduct(sqrtWeights); + + // Rotation error, expressed in base frame + auto rotationErrorInBase = rotationErrorInLocalEulerXYZ(currentTargets.head<3>(), parameters.head<3>()); + + // For the orientation, we replace the error in Euler angles coordinates with a proper rotation error. + errors.head<3>() = rotationErrorInBase.cwiseProduct(sqrtWeights.head<3>()); + return errors; +} + +MotionTrackingCost::Weights loadWeightsFromFile(const std::string& filename, const std::string& fieldname, bool verbose) { + MotionTrackingCost::Weights weights; + + boost::property_tree::ptree pt; + boost::property_tree::read_info(filename, pt); + + if (verbose) { + std::cerr << "\n #### Tacking Cost Weights:" << std::endl; + std::cerr << " #### ==================================================" << std::endl; + } + + ocs2::loadData::loadPtreeValue(pt, weights.eulerXYZ.x(), fieldname + ".roll", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.eulerXYZ.y(), fieldname + ".pitch", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.eulerXYZ.z(), fieldname + ".yaw", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comPosition.x(), fieldname + ".base_position_x", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comPosition.y(), fieldname + ".base_position_y", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comPosition.z(), fieldname + ".base_position_z", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comAngularVelocity.x(), fieldname + ".base_angular_vel_x", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comAngularVelocity.y(), fieldname + ".base_angular_vel_y", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comAngularVelocity.z(), fieldname + ".base_angular_vel_z", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comLinearVelocity.x(), fieldname + ".base_linear_vel_x", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comLinearVelocity.y(), fieldname + ".base_linear_vel_y", verbose); + ocs2::loadData::loadPtreeValue(pt, weights.comLinearVelocity.z(), fieldname + ".base_linear_vel_z", verbose); + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + bool legVerbose = verbose && (leg == 0); + ocs2::loadData::loadPtreeValue(pt, weights.jointPosition[leg].x(), fieldname + ".joint_position_HAA", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.jointPosition[leg].y(), fieldname + ".joint_position_HFE", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.jointPosition[leg].z(), fieldname + ".joint_position_KFE", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footPosition[leg].x(), fieldname + ".foot_position_x", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footPosition[leg].y(), fieldname + ".foot_position_y", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footPosition[leg].z(), fieldname + ".foot_position_z", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.jointVelocity[leg].x(), fieldname + ".joint_velocity_HAA", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.jointVelocity[leg].y(), fieldname + ".joint_velocity_HFE", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.jointVelocity[leg].z(), fieldname + ".joint_velocity_KFE", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footVelocity[leg].x(), fieldname + ".foot_velocity_x", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footVelocity[leg].y(), fieldname + ".foot_velocity_y", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.footVelocity[leg].z(), fieldname + ".foot_velocity_z", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.contactForce[leg].x(), fieldname + ".contact_force_x", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.contactForce[leg].y(), fieldname + ".contact_force_y", legVerbose); + ocs2::loadData::loadPtreeValue(pt, weights.contactForce[leg].z(), fieldname + ".contact_force_z", legVerbose); + } + + if (verbose) { + std::cerr << " #### ================================================ ####" << std::endl; + } + + return weights; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingTerminalCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingTerminalCost.cpp new file mode 100644 index 000000000..153f3f113 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/MotionTrackingTerminalCost.cpp @@ -0,0 +1,42 @@ +// +// Created by rgrandia on 10.03.22. +// + +#include "ocs2_switched_model_interface/cost/MotionTrackingTerminalCost.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" + +namespace switched_model { + +MotionTrackingTerminalCost::MotionTrackingTerminalCost(matrix_t Q) : Q_(std::move(Q)) {} + +MotionTrackingTerminalCost* MotionTrackingTerminalCost::clone() const { + return new MotionTrackingTerminalCost(*this); +} + +MotionTrackingTerminalCost::MotionTrackingTerminalCost(const MotionTrackingTerminalCost& other) : Q_(other.Q_) {} + +scalar_t MotionTrackingTerminalCost::getValue(scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const { + const vector_t xDeviation = getStateDeviation(state, preComputation); + return 0.5 * xDeviation.dot(Q_ * xDeviation); +} + +ScalarFunctionQuadraticApproximation MotionTrackingTerminalCost::getQuadraticApproximation( + scalar_t time, const vector_t& state, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComputation) const { + const vector_t xDeviation = getStateDeviation(state, preComputation); + + ScalarFunctionQuadraticApproximation Phi; + Phi.dfdxx = Q_; + Phi.dfdx.noalias() = Q_ * xDeviation; + Phi.f = 0.5 * xDeviation.dot(Phi.dfdx); + return Phi; +} + +vector_t MotionTrackingTerminalCost::getStateDeviation(const vector_t& state, const ocs2::PreComputation& preComputation) const { + const auto& switchedModelPreComp = ocs2::cast(preComputation); + return state - switchedModelPreComp.getStateReference(); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/TorqueLimitsSoftConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/TorqueLimitsSoftConstraint.cpp new file mode 100644 index 000000000..a580cab75 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/cost/TorqueLimitsSoftConstraint.cpp @@ -0,0 +1,93 @@ +// +// Created by rgrandia on 26.07.21. +// + +#include "ocs2_switched_model_interface/cost/TorqueLimitsSoftConstraint.h" + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/core/TorqueApproximation.h" + +namespace switched_model { + +TorqueLimitsSoftConstraint::TorqueLimitsSoftConstraint(const joint_coordinate_t& torqueLimits, ocs2::RelaxedBarrierPenalty::Config settings, + const joint_coordinate_t& nominalTorques) + : jointTorquePenalty_(new ocs2::RelaxedBarrierPenalty(settings)), torqueLimits_(torqueLimits), offset_(0.0) { + // Obtain the offset at zero joint angles. Just to compensate high negative costs when being far away from an infinite joint limit + offset_ = -getValue(nominalTorques); +} + +TorqueLimitsSoftConstraint::TorqueLimitsSoftConstraint(const TorqueLimitsSoftConstraint& rhs) + : jointTorquePenalty_(rhs.jointTorquePenalty_->clone()), torqueLimits_(rhs.torqueLimits_), offset_(rhs.offset_) {} + +scalar_t TorqueLimitsSoftConstraint::getValue(scalar_t time, const vector_t& state, const vector_t& input, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + return getValue(switchedModelPreComp.jointTorques()); +} + +ScalarFunctionQuadraticApproximation TorqueLimitsSoftConstraint::getQuadraticApproximation( + scalar_t time, const vector_t& state, const vector_t& input, const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::PreComputation& preComp) const { + const auto& switchedModelPreComp = ocs2::cast(preComp); + return getQuadraticApproximation(switchedModelPreComp.jointTorquesDerivative()); +} + +scalar_t TorqueLimitsSoftConstraint::getValue(const joint_coordinate_t& jointTorques) const { + const joint_coordinate_t upperBoundTorqueOffset = torqueLimits_ - jointTorques; + const joint_coordinate_t lowerBoundTorqueOffset = torqueLimits_ + jointTorques; // = qd - (-qd_limit) + + return upperBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getValue(0.0, hi); }).sum() + + lowerBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getValue(0.0, hi); }).sum() + offset_; +} + +ScalarFunctionQuadraticApproximation TorqueLimitsSoftConstraint::getQuadraticApproximation( + const VectorFunctionLinearApproximation& jointTorquesDerivative) const { + const joint_coordinate_t upperBoundTorqueOffset = torqueLimits_ - jointTorquesDerivative.f; + const joint_coordinate_t lowerBoundTorqueOffset = torqueLimits_ + jointTorquesDerivative.f; // = qd - (-qd_limit) + + ScalarFunctionQuadraticApproximation cost; + cost.f = upperBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getValue(0.0, hi); }).sum() + + lowerBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getValue(0.0, hi); }).sum() + offset_; + + // Penalty derivatives w.r.t. the constraint + const joint_coordinate_t penaltyDerivatives = lowerBoundTorqueOffset.unaryExpr([&](scalar_t hi) { + return jointTorquePenalty_->getDerivative(0.0, hi); + }) - upperBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getDerivative(0.0, hi); }); + const joint_coordinate_t penaltySecondDerivatives = lowerBoundTorqueOffset.unaryExpr([&](scalar_t hi) { + return jointTorquePenalty_->getSecondDerivative(0.0, hi); + }) + upperBoundTorqueOffset.unaryExpr([&](scalar_t hi) { return jointTorquePenalty_->getSecondDerivative(0.0, hi); }); + + cost.dfdx = vector_t::Zero(STATE_DIM); + cost.dfdu = vector_t::Zero(INPUT_DIM); + cost.dfdxx = matrix_t::Zero(STATE_DIM, STATE_DIM); + cost.dfduu = matrix_t::Zero(INPUT_DIM, INPUT_DIM); + cost.dfdux = matrix_t::Zero(INPUT_DIM, STATE_DIM); + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const int torqueStartIndex = 3 * leg; + const int forceStartIndex = 3 * leg; + const int jointStartStateIndex = 2 * BASE_COORDINATE_SIZE + 3 * leg; + + // Shorthand for blocks of the full derivatives. + const auto dhdjoints = jointTorquesDerivative.dfdx.block<3, 3>(torqueStartIndex, jointStartStateIndex); + const auto dhdforce = jointTorquesDerivative.dfdu.block<3, 3>(torqueStartIndex, forceStartIndex); + const auto dpenaltydh = penaltyDerivatives.segment<3>(torqueStartIndex); + const auto d2penaltydh2 = penaltySecondDerivatives.segment<3>(torqueStartIndex); + + // State derivative only has elements for joints of this leg + cost.dfdx.segment<3>(jointStartStateIndex).noalias() = dhdjoints.transpose() * dpenaltydh; + cost.dfdxx.block<3, 3>(jointStartStateIndex, jointStartStateIndex).noalias() = + dhdjoints.transpose() * d2penaltydh2.asDiagonal() * dhdjoints; + + // Input derivative only has elements for contact forces of this leg + cost.dfdu.segment<3>(forceStartIndex).noalias() = dhdforce.transpose() * dpenaltydh; + cost.dfduu.block<3, 3>(forceStartIndex, forceStartIndex).noalias() = dhdforce.transpose() * d2penaltydh2.asDiagonal() * dhdforce; + + // Cross terms + cost.dfdux.block<3, 3>(forceStartIndex, jointStartStateIndex).noalias() = dhdforce.transpose() * d2penaltydh2.asDiagonal() * dhdjoints; + } + + return cost; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoDynamicsParameters.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoDynamicsParameters.cpp new file mode 100644 index 000000000..8ee49f88a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoDynamicsParameters.cpp @@ -0,0 +1,25 @@ +// +// Created by rgrandia on 04.06.21. +// + +#include "ocs2_switched_model_interface/dynamics/ComKinoDynamicsParameters.h" + +namespace switched_model { + +template +ComKinoSystemDynamicsParameters::ComKinoSystemDynamicsParameters( + const Eigen::Matrix& parameterVector) + : externalForceInOrigin(parameterVector.template segment<3>(0)), externalTorqueInBase(parameterVector.template segment<3>(3)) {} + +template +Eigen::Matrix ComKinoSystemDynamicsParameters::asVector() const { + Eigen::Matrix parameters(ComKinoSystemDynamicsParameters::getNumParameters()); + parameters.template head<3>() = externalForceInOrigin; + parameters.template tail<3>() = externalTorqueInBase; + return parameters; +} + +template class ComKinoSystemDynamicsParameters; +template class ComKinoSystemDynamicsParameters; + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoSystemDynamicsAd.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoSystemDynamicsAd.cpp new file mode 100644 index 000000000..2ce5e8527 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/dynamics/ComKinoSystemDynamicsAd.cpp @@ -0,0 +1,120 @@ +// +// Created by rgrandia on 18.09.19. +// + +#include "ocs2_switched_model_interface/dynamics/ComKinoSystemDynamicsAd.h" + +#include + +namespace switched_model { + +namespace { +template +base_coordinate_s_t computeExternalForcesInBaseFrame(const KinematicsModelBase& kinematicsModel, + const comkino_state_s_t& comKinoState, + const comkino_input_s_t& comKinoInput, + const ComKinoSystemDynamicsParameters& parameters) { + // Extract elements from state + const base_coordinate_s_t basePose = getBasePose(comKinoState); + const joint_coordinate_s_t qJoints = getJointPositions(comKinoState); + const vector3_s_t baseEulerAngles = getOrientation(basePose); + + // contact JacobianTransposeLambda + base_coordinate_s_t JcTransposeLambda = base_coordinate_s_t::Zero(); + for (size_t i = 0; i < NUM_CONTACT_POINTS; i++) { + const vector3_s_t baseToFootInBase = kinematicsModel.positionBaseToFootInBaseFrame(i, qJoints); + const vector3_s_t contactForce = comKinoInput.template segment<3>(3 * i); + JcTransposeLambda.head(3) += baseToFootInBase.cross(contactForce); + JcTransposeLambda.tail(3) += contactForce; + } + + // External forces + const vector3_s_t externalForceInBase = rotateVectorOriginToBase(parameters.externalForceInOrigin, baseEulerAngles); + JcTransposeLambda.head(3) += parameters.externalTorqueInBase; + JcTransposeLambda.tail(3) += externalForceInBase; + + return JcTransposeLambda; +}; +} // namespace + +ComKinoSystemDynamicsAd::ComKinoSystemDynamicsAd(const ad_kinematic_model_t& adKinematicModel, const ad_com_model_t& adComModel, + const DynamicsParametersSynchronizedModule& dynamicsParametersModule, + ModelSettings settings) + : adKinematicModelPtr_(adKinematicModel.clone()), + adComModelPtr_(adComModel.clone()), + dynamicsParametersModulePtr_(&dynamicsParametersModule), + settings_(settings) { + const std::string libName = settings_.robotName_ + "_dynamics"; + this->initialize(STATE_DIM, INPUT_DIM, libName, settings_.autodiffLibraryFolder_, settings_.recompileLibraries_); +} + +ComKinoSystemDynamicsAd::ComKinoSystemDynamicsAd(const ComKinoSystemDynamicsAd& rhs) + : Base(rhs), + adKinematicModelPtr_(rhs.adKinematicModelPtr_->clone()), + adComModelPtr_(rhs.adComModelPtr_->clone()), + dynamicsParametersModulePtr_(rhs.dynamicsParametersModulePtr_), + settings_(rhs.settings_) {} + +ComKinoSystemDynamicsAd* ComKinoSystemDynamicsAd::clone() const { + return new ComKinoSystemDynamicsAd(*this); +} + +ocs2::ad_vector_t ComKinoSystemDynamicsAd::systemFlowMap(ocs2::ad_scalar_t time, const ocs2::ad_vector_t& state, + const ocs2::ad_vector_t& input, const ocs2::ad_vector_t& parameters) const { + const comkino_state_ad_t comkinoState = state; + const comkino_input_ad_t comkinoInput = input; + + const joint_coordinate_ad_t dqJoints = getJointVelocities(comkinoInput); + + const com_state_ad_t comStateDerivative = + computeComStateDerivative(*adComModelPtr_, *adKinematicModelPtr_, comkinoState, comkinoInput, ad_parameters_t(parameters)); + + // extended state time derivatives + ocs2::ad_vector_t stateDerivative(state.rows()); + stateDerivative << comStateDerivative, dqJoints; + return stateDerivative; +} + +template +com_state_s_t ComKinoSystemDynamicsAd::computeComStateDerivative(const ComModelBase& comModel, + const KinematicsModelBase& kinematicsModel, + const comkino_state_s_t& comKinoState, + const comkino_input_s_t& comKinoInput, + const ComKinoSystemDynamicsParameters& parameters) { + // Extract elements from state + const base_coordinate_s_t basePose = getBasePose(comKinoState); + const vector3_s_t baseEulerAngles = getOrientation(basePose); + const base_coordinate_s_t baseLocalVelocities = getBaseLocalVelocities(comKinoState); + const vector3_s_t baseLocalAngularVelocity = getAngularVelocity(baseLocalVelocities); + const vector3_s_t baseLocalLinearVelocity = getLinearVelocity(baseLocalVelocities); + const joint_coordinate_s_t qJoints = getJointPositions(comKinoState); + const joint_coordinate_s_t qdJoints = getJointVelocities(comKinoInput); + + const base_coordinate_s_t extForce = computeExternalForcesInBaseFrame(kinematicsModel, comKinoState, comKinoInput, parameters); + + // pose dynamics + com_state_s_t stateDerivativeCoM; + stateDerivativeCoM.segment(0, 3) = switched_model::angularVelocitiesToEulerAngleDerivatives(baseLocalAngularVelocity, baseEulerAngles); + stateDerivativeCoM.segment(3, 3) = rotateVectorBaseToOrigin(baseLocalLinearVelocity, baseEulerAngles); + + /* + * Base dynamics with the following assumptions: + * - Zero joint acceleration + */ + stateDerivativeCoM.segment(6, 6) = comModel.calculateBaseLocalAccelerations(basePose, baseLocalVelocities, qJoints, qdJoints, + joint_coordinate_s_t::Zero(), extForce); + return stateDerivativeCoM; +} + +template com_state_t ComKinoSystemDynamicsAd::computeComStateDerivative(const ComModelBase& comModel, + const KinematicsModelBase& kinematicsModel, + const comkino_state_t& comKinoState, + const comkino_input_t& comKinoInput, + const parameters_t& parameters); +template com_state_ad_t ComKinoSystemDynamicsAd::computeComStateDerivative(const ComModelBase& comModel, + const KinematicsModelBase& kinematicsModel, + const comkino_state_ad_t& comKinoState, + const comkino_input_ad_t& comKinoInput, + const ad_parameters_t& parameters); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/CubicSpline.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/CubicSpline.cpp new file mode 100644 index 000000000..813d84d66 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/CubicSpline.cpp @@ -0,0 +1,64 @@ +// +// Created by rgrandia on 13.03.20. +// + +#include "ocs2_switched_model_interface/foot_planner/CubicSpline.h" + +namespace switched_model { + +CubicSpline::CubicSpline(Node start, Node end) { + assert(start.time < end.time); + t0_ = start.time; + t1_ = end.time; + dt_ = end.time - start.time; + + scalar_t dp = end.position - start.position; + scalar_t dv = end.velocity - start.velocity; + + dc0_ = 0.0; + dc1_ = start.velocity; + dc2_ = -(3.0 * start.velocity + dv); + dc3_ = (2.0 * start.velocity + dv); + + c0_ = dc0_ * dt_ + start.position; + c1_ = dc1_ * dt_; + c2_ = dc2_ * dt_ + 3.0 * dp; + c3_ = dc3_ * dt_ - 2.0 * dp; +} + +scalar_t CubicSpline::position(scalar_t time) const { + scalar_t tn = normalizedTime(time); + return c3_ * tn * tn * tn + c2_ * tn * tn + c1_ * tn + c0_; +} + +scalar_t CubicSpline::velocity(scalar_t time) const { + scalar_t tn = normalizedTime(time); + return (3.0 * c3_ * tn * tn + 2.0 * c2_ * tn + c1_) / dt_; +} + +scalar_t CubicSpline::acceleration(scalar_t time) const { + scalar_t tn = normalizedTime(time); + return (6.0 * c3_ * tn + 2.0 * c2_) / (dt_ * dt_); +} + +scalar_t CubicSpline::startTimeDerivative(scalar_t t) const { + scalar_t tn = normalizedTime(t); + scalar_t dCoff = -(dc3_ * tn * tn * tn + dc2_ * tn * tn + dc1_ * tn + dc0_); + scalar_t dTn = -(t1_ - t) / (dt_ * dt_); + return velocity(t) * dt_ * dTn + dCoff; +} + +scalar_t CubicSpline::finalTimeDerivative(scalar_t t) const { + scalar_t tn = normalizedTime(t); + scalar_t dCoff = (dc3_ * tn * tn * tn + dc2_ * tn * tn + dc1_ * tn + dc0_); + scalar_t dTn = -(t - t0_) / (dt_ * dt_); + return velocity(t) * dt_ * dTn + dCoff; +} + +scalar_t CubicSpline::normalizedTime(scalar_t t) const { + assert(t >= t0_); + assert(t <= t1_); + return (t - t0_) / dt_; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/FootPhase.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/FootPhase.cpp new file mode 100644 index 000000000..934d6dbcf --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/FootPhase.cpp @@ -0,0 +1,279 @@ +// +// Created by rgrandia on 24.04.20. +// + +#include "ocs2_switched_model_interface/foot_planner/FootPhase.h" + +#include + +#include "ocs2_switched_model_interface/foot_planner/CubicSpline.h" + +namespace switched_model { + +FootTangentialConstraintMatrix tangentialConstraintsFromConvexTerrain(const ConvexTerrain& stanceTerrain, scalar_t margin) { + FootTangentialConstraintMatrix constraints{}; + + int numberOfConstraints = stanceTerrain.boundary.size(); + constraints.A.resize(numberOfConstraints, 3); + constraints.b.resize(numberOfConstraints, 1); + + if (numberOfConstraints > 0) { + for (int i = 0; i < stanceTerrain.boundary.size(); ++i) { + // Determine next point in counter clockwise direction + int j = getNextVertex(i, stanceTerrain.boundary.size()); + vector2_t start2end = stanceTerrain.boundary[j] - stanceTerrain.boundary[i]; + + // Get 2D constraint A_terrain * p_terrain + b - margin >= 0 + vector2_t A_terrain{-start2end.y(), start2end.x()}; // rotate 90deg around z to get a vector pointing to interior of the polygon + A_terrain.normalize(); // make it a unit vector. + scalar_t b_terrain = -A_terrain.dot(stanceTerrain.boundary[i]) - margin; // Take offset of one of the points + + // 3D position in terrain frame = T_R_W * (p_w - p_0) + // Take x-y only for the constraints: p_terrain = diag(1, 1, 0) * T_R_W * (p_w - p_0) + // Gives: + // A_world = A_terrain * diag(1, 1, 0) * T_R_W + // b_world = b_terrain - A_terrain * diag(1, 1, 0) * T_R_W * p_0 = b_terrain - A_world * p_0 + constraints.A.row(i) = A_terrain.transpose() * stanceTerrain.plane.orientationWorldToTerrain.topRows<2>(); + constraints.b(i) = b_terrain - constraints.A.row(i) * stanceTerrain.plane.positionInWorld; + } + } + + return constraints; +} + +StancePhase::StancePhase(ConvexTerrain stanceTerrain, scalar_t terrainMargin) + : stanceTerrain_(std::move(stanceTerrain)), + nominalFootholdLocation_(stanceTerrain_.plane.positionInWorld), + surfaceNormalInWorldFrame_(surfaceNormalInWorld(stanceTerrain_.plane)), + footTangentialConstraint_(tangentialConstraintsFromConvexTerrain(stanceTerrain_, terrainMargin)) {} + +vector3_t StancePhase::normalDirectionInWorldFrame(scalar_t time) const { + return surfaceNormalInWorldFrame_; +} + +vector3_t StancePhase::nominalFootholdLocation() const { + return nominalFootholdLocation_; +} + +const ConvexTerrain* StancePhase::nominalFootholdConstraint() const { + return &stanceTerrain_; +}; + +vector3_t StancePhase::getPositionInWorld(scalar_t time) const { + return nominalFootholdLocation(); +} + +vector3_t StancePhase::getVelocityInWorld(scalar_t time) const { + return vector3_t::Zero(); +} + +vector3_t StancePhase::getAccelerationInWorld(scalar_t time) const { + return vector3_t::Zero(); +} + +const FootTangentialConstraintMatrix* StancePhase::getFootTangentialConstraintInWorldFrame() const { + if (footTangentialConstraint_.A.rows() > 0) { + return &footTangentialConstraint_; + } else { + return nullptr; + } +} + +SwingPhase::SwingPhase(SwingEvent liftOff, SwingEvent touchDown, const SwingProfile& swingProfile, const TerrainModel* terrainModel) + : liftOff_(liftOff), touchDown_(touchDown) { + if (touchDown_.terrainPlane == nullptr) { + setHalveSwing(swingProfile, terrainModel); + } else { + setFullSwing(swingProfile, terrainModel); + } +} + +void SwingPhase::setFullSwing(const SwingProfile& swingProfile, const TerrainModel* terrainModel) { + const scalar_t sdfMidswingMargin = swingProfile.sdfMidswingMargin; + const scalar_t sdfStartEndMargin = swingProfile.sdfStartEndMargin; + const scalar_t swingDuration = (touchDown_.time - liftOff_.time); + + // liftoff conditions: lifting off in vertical direction + const auto& liftOffPositionInWorld = liftOff_.terrainPlane->positionInWorld; + const vector3_t liftOffVelocityInWorld = {0.0, 0.0, liftOff_.velocity}; + const SwingNode3d start{liftOff_.time, liftOffPositionInWorld, liftOffVelocityInWorld}; + + // touchdown conditions: touching down in surface normal direction + const auto& touchDownPositionInWorld = touchDown_.terrainPlane->positionInWorld; + const vector3_t touchDownVelocityInWorld = touchDown_.velocity * surfaceNormalInWorld(*touchDown_.terrainPlane); + const SwingNode3d end{touchDown_.time, touchDownPositionInWorld, touchDownVelocityInWorld}; + + // Apex + std::vector swingPoints = {start}; + const vector3_t swingVector = touchDownPositionInWorld - liftOffPositionInWorld; + if (swingVector.head<2>().norm() > 0.01) { + // Get a unit vector perpendicular to the swing vector and in the plane formed by the World-Z axis and the swing vector. + const vector3_t swingTrajectoryNormal = swingVector.cross(vector3_t(0.0, 0.0, 1.0).cross(swingVector)).normalized(); + + // Terrain adaptation if information is available + scalar_t maxObstacleHeight = 0.0; + if (terrainModel != nullptr) { + const auto heightProfile = terrainModel->getHeightProfileAlongLine(liftOffPositionInWorld, touchDownPositionInWorld); + + // Find the maximum obstacle. An obstacle is a height point sticking out above the line between liftoff and touchdown. + for (const auto& point : heightProfile) { + const scalar_t pointProgress = point[0]; + const scalar_t pointHeight = point[1]; + const scalar_t heightRelativeToSwingLine = pointHeight - (liftOffPositionInWorld.z() + pointProgress * swingVector.z()); + const scalar_t relativeHeightProjectedOnNormal = heightRelativeToSwingLine * swingTrajectoryNormal.z(); + if (relativeHeightProjectedOnNormal > maxObstacleHeight) { + maxObstacleHeight = relativeHeightProjectedOnNormal; + } + } + // Clip max obstacle to two times swing height to protect against outliers. (Total swing height will be max 3 * swing height) + maxObstacleHeight = std::min(maxObstacleHeight, swingProfile.maxSwingHeightAdaptation); + } + + for (const auto& node : swingProfile.nodes) { + SwingNode3d midPoint; + midPoint.time = liftOff_.time + node.phase * swingDuration; + // position = liftoff + progress towards touchdown + height offset in normal direction + midPoint.position = + liftOffPositionInWorld + node.tangentialProgress * swingVector + (maxObstacleHeight + node.swingHeight) * swingTrajectoryNormal; + // velocity = factor * average velocity between liftoff and touchdown + velocity in normal direction + midPoint.velocity = node.tangentialVelocityFactor / swingDuration * swingVector + node.normalVelocity * swingTrajectoryNormal; + swingPoints.push_back(midPoint); + } + } else { // (cases where target is above or intersecting with current position) + // No point in checking the terrain. Start and end point will fall in the same cell. + for (const auto& node : swingProfile.nodes) { + SwingNode3d midPoint; + midPoint.time = liftOff_.time + node.phase * swingDuration; + midPoint.position = touchDownPositionInWorld; + midPoint.position.z() = std::max(liftOffPositionInWorld.z(), touchDownPositionInWorld.z()) + node.swingHeight; + midPoint.velocity = vector3_t::Zero(); + midPoint.velocity.z() = node.normalVelocity; + swingPoints.push_back(midPoint); + } + } + + swingPoints.push_back(end); + + motion_.reset(new SwingSpline3d(swingPoints)); + + // Terrain clearance + if (terrainModel != nullptr && terrainModel->getSignedDistanceField() != nullptr) { + const auto& sdf = *terrainModel->getSignedDistanceField(); + const scalar_t sdfStartClearance = std::min(sdf.value(liftOffPositionInWorld), 0.0) + sdfStartEndMargin; + const scalar_t sdfEndClearance = std::min(sdf.value(touchDownPositionInWorld), 0.0) + sdfStartEndMargin; + const scalar_t midSwingTime = 0.5 * (liftOff_.time + touchDown_.time); + SwingNode startNode{liftOff_.time, sdfStartClearance, liftOff_.velocity}; + SwingNode apexNode{midSwingTime, sdfMidswingMargin, 0.0}; + SwingNode endNode{touchDown_.time, sdfEndClearance, touchDown_.velocity}; + terrainClearanceMotion_.reset(new QuinticSwing(startNode, apexNode, endNode)); + } else { + terrainClearanceMotion_.reset(); + } +} + +void SwingPhase::setHalveSwing(const SwingProfile& swingProfile, const TerrainModel* terrainModel) { + const scalar_t sdfMidswingMargin = swingProfile.sdfMidswingMargin; + const scalar_t sdfStartEndMargin = swingProfile.sdfStartEndMargin; + const scalar_t swingDuration = (touchDown_.time - liftOff_.time); + + // liftoff conditions + const auto& liftOffPositionInWorld = liftOff_.terrainPlane->positionInWorld; + const vector3_t liftOffVelocityInWorld = liftOff_.velocity * surfaceNormalInWorld(*liftOff_.terrainPlane); + const SwingNode3d start{liftOff_.time, liftOffPositionInWorld, liftOffVelocityInWorld}; + + // touchdown conditions + touchDown_.terrainPlane = liftOff_.terrainPlane; + const vector3_t touchDownPositionInWorld = liftOffPositionInWorld + vector3_t(0.0, 0.0, swingProfile.nodes.back().swingHeight); + const vector3_t touchDownVelocityInWorld = vector3_t::Zero(); + const SwingNode3d end{touchDown_.time, touchDownPositionInWorld, touchDownVelocityInWorld}; + + std::vector swingPoints = {start}; + for (const auto& node : swingProfile.nodes) { + SwingNode3d midPoint; + midPoint.time = liftOff_.time + node.phase * swingDuration; + midPoint.position = touchDownPositionInWorld; + midPoint.position.z() = std::max(liftOffPositionInWorld.z(), touchDownPositionInWorld.z()) + node.swingHeight; + midPoint.velocity = vector3_t::Zero(); + midPoint.velocity.z() = node.normalVelocity; + swingPoints.push_back(midPoint); + } + swingPoints.push_back(end); + + // The two motions are equal and defined in the liftoff plane + motion_.reset(new SwingSpline3d(swingPoints)); + + { // Terrain clearance + if (terrainModel != nullptr && terrainModel->getSignedDistanceField() != nullptr) { + const auto& sdf = *terrainModel->getSignedDistanceField(); + const scalar_t sdfStartClearance = std::min(sdf.value(liftOffPositionInWorld), 0.0) + sdfStartEndMargin; + SwingNode startNode{liftOff_.time, sdfStartClearance, liftOff_.velocity}; + SwingNode endNode{touchDown_.time, sdfMidswingMargin, 0.0}; + terrainClearanceMotion_.reset(new QuinticSwing(startNode, sdfMidswingMargin, endNode)); + } else { + terrainClearanceMotion_.reset(); + } + } +} + +vector3_t SwingPhase::normalDirectionInWorldFrame(scalar_t time) const { + // Returns "average" surface normal. + const scalar_t scaling = getScaling(time); + return ((1.0 - scaling) * surfaceNormalInWorld(*liftOff_.terrainPlane) + scaling * surfaceNormalInWorld(*touchDown_.terrainPlane)) + .normalized(); +} + +vector3_t SwingPhase::nominalFootholdLocation() const { + return touchDown_.terrainPlane->positionInWorld; +} + +vector3_t SwingPhase::getPositionInWorld(scalar_t time) const { + return motion_->position(time); +} + +vector3_t SwingPhase::getVelocityInWorld(scalar_t time) const { + return motion_->velocity(time); +} + +vector3_t SwingPhase::getAccelerationInWorld(scalar_t time) const { + return motion_->acceleration(time); +} + +scalar_t SwingPhase::getMinimumFootClearance(scalar_t time) const { + if (terrainClearanceMotion_ != nullptr) { + return terrainClearanceMotion_->position(time); + } else { + return 0.0; + } +} + +scalar_t SwingPhase::getScaling(scalar_t time) const { + // Cubic scaling from 25% till 75% of swing duration + const scalar_t startInterpolation = 0.25; + const scalar_t endInterpolation = 0.75; + static const CubicSpline scalingSpline({startInterpolation, 0.0, 0.0}, {endInterpolation, 1.0, 0.0}); + + const scalar_t normalizedTime = (time - liftOff_.time) / (touchDown_.time - liftOff_.time); + if (normalizedTime < startInterpolation) { + return 0.0; + } else if (normalizedTime < endInterpolation) { + return scalingSpline.position(normalizedTime); + } else { + return 1.0; + } +} + +ExternalSwingPhase::ExternalSwingPhase(std::vector timeTrajectory, std::vector positionTrajectory, + std::vector velocityTrajectory) + : timeTrajectory_(std::move(timeTrajectory)), + positionTrajectory_(std::move(positionTrajectory)), + velocityTrajectory_(std::move(velocityTrajectory)) {} + +vector3_t ExternalSwingPhase::getPositionInWorld(scalar_t time) const { + return ocs2::LinearInterpolation::interpolate(time, timeTrajectory_, positionTrajectory_); +} + +vector3_t ExternalSwingPhase::getVelocityInWorld(scalar_t time) const { + return ocs2::LinearInterpolation::interpolate(time, timeTrajectory_, velocityTrajectory_); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/KinematicFootPlacementPenalty.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/KinematicFootPlacementPenalty.cpp new file mode 100644 index 000000000..223135ac2 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/KinematicFootPlacementPenalty.cpp @@ -0,0 +1,36 @@ +// +// Created by rgrandia on 17.02.22. +// + +#include "ocs2_switched_model_interface/foot_planner/KinematicFootPlacementPenalty.h" + +#include "ocs2_switched_model_interface/core/Rotations.h" + +namespace switched_model { + +namespace { +scalar_t computeInwardStepDistance(const vector3_t& footPositionInHip, const vector3_t& gravityNormalInHip) { + const vector3_t inwardDirection = gravityNormalInHip.cross(vector3_t::UnitX()).normalized(); + return std::max(0.0, inwardDirection.dot(footPositionInHip)); +} + +scalar_t computeLegOverExtension(const vector3_t& footPositionInHip, const ApproximateKinematicsConfig& config) { + return std::max(0.0, footPositionInHip.norm() - config.maxLegExtension); +} +} // namespace + +scalar_t computeKinematicPenalty(const vector3_t& footPositionInHip, const vector3_t& gravityNormalInHip, + const ApproximateKinematicsConfig& config) { + const auto instep = computeInwardStepDistance(footPositionInHip, gravityNormalInHip); + const auto extension = computeLegOverExtension(footPositionInHip, config); + return config.kinematicPenaltyWeight * (instep * instep + extension * extension); +} + +scalar_t computeKinematicPenalty(const vector3_t& footPositionInWorld, const vector3_t& hipPositionInWorld, + const matrix3_t& rotationHipToWorld, const ApproximateKinematicsConfig& config) { + const vector3_t footPositionInHip = rotationHipToWorld.transpose() * (footPositionInWorld - hipPositionInWorld); + const vector3_t gravityNormalInHip = rotationHipToWorld.transpose() * vector3_t(0.0, 0.0, -1.0); + return computeKinematicPenalty(footPositionInHip, gravityNormalInHip, config); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/QuinticSplineSwing.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/QuinticSplineSwing.cpp new file mode 100644 index 000000000..6618b6d2e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/QuinticSplineSwing.cpp @@ -0,0 +1,223 @@ +// +// Created by rgrandia on 21.01.21. +// + +#include "ocs2_switched_model_interface/foot_planner/QuinticSplineSwing.h" + +#include + +#include + +namespace switched_model { + +scalar_t QuinticSpline::position(scalar_t time) const { + const scalar_t tau1 = normalizedTime(time); + const scalar_t tau2 = tau1 * tau1; + const scalar_t tau3 = tau2 * tau1; + const scalar_t tau4 = tau3 * tau1; + const scalar_t tau5 = tau4 * tau1; + return c_[0] * tau5 + c_[1] * tau4 + c_[2] * tau3 + c_[3] * tau2 + c_[4] * tau1 + c_[5]; +} + +scalar_t QuinticSpline::velocity(scalar_t time) const { + const scalar_t tau1 = normalizedTime(time); + const scalar_t tau2 = tau1 * tau1; + const scalar_t tau3 = tau2 * tau1; + const scalar_t tau4 = tau3 * tau1; + return (c_[0] * 5.0 * tau4 + c_[1] * 4.0 * tau3 + c_[2] * 3.0 * tau2 + c_[3] * 2.0 * tau1 + c_[4]) / dt_; +} + +scalar_t QuinticSpline::acceleration(scalar_t time) const { + const scalar_t tau1 = normalizedTime(time); + const scalar_t tau2 = tau1 * tau1; + const scalar_t tau3 = tau2 * tau1; + return (c_[0] * 20.0 * tau3 + c_[1] * 12.0 * tau2 + c_[2] * 6.0 * tau1 + c_[3] * 2.0) / (dt_ * dt_); +} + +scalar_t QuinticSpline::jerk(scalar_t time) const { + const scalar_t tau1 = normalizedTime(time); + const scalar_t tau2 = tau1 * tau1; + return (c_[0] * 60.0 * tau2 + c_[1] * 24.0 * tau1 + c_[2] * 6.0) / (dt_ * dt_ * dt_); +} + +scalar_t QuinticSpline::normalizedTime(scalar_t t) const { + return (t - t0_) / dt_; +} + +// helper functions +namespace { +void addStartPositionConstraint(scalar_t p, Eigen::SparseMatrix& A, vector_t& b, int constraintIdx, + int splineIdx) { + A.insert(constraintIdx, splineIdx + 5) = 1.0; + b(constraintIdx) = p; +} + +void addEndPositionConstraint(scalar_t p, Eigen::SparseMatrix& A, vector_t& b, int constraintIdx, + int splineIdx) { + A.insert(constraintIdx, splineIdx + 0) = 1.0; + A.insert(constraintIdx, splineIdx + 1) = 1.0; + A.insert(constraintIdx, splineIdx + 2) = 1.0; + A.insert(constraintIdx, splineIdx + 3) = 1.0; + A.insert(constraintIdx, splineIdx + 4) = 1.0; + A.insert(constraintIdx, splineIdx + 5) = 1.0; + b(constraintIdx) = p; +} + +void addStartVelocityConstraint(scalar_t v, scalar_t dt, Eigen::SparseMatrix& A, vector_t& b, int constraintIdx, + int splineIdx) { + A.insert(constraintIdx, splineIdx + 4) = 1.0; + b(constraintIdx) = v * dt; +} + +void addEndVelocityConstraint(scalar_t v, scalar_t dt, Eigen::SparseMatrix& A, vector_t& b, int constraintIdx, + int splineIdx) { + A.insert(constraintIdx, splineIdx + 0) = 5.0; + A.insert(constraintIdx, splineIdx + 1) = 4.0; + A.insert(constraintIdx, splineIdx + 2) = 3.0; + A.insert(constraintIdx, splineIdx + 3) = 2.0; + A.insert(constraintIdx, splineIdx + 4) = 1.0; + b(constraintIdx) = v * dt; +} + +void addStartAccelerationConstraint(scalar_t a, scalar_t dt, Eigen::SparseMatrix& A, vector_t& b, + int constraintIdx, int splineIdx) { + A.insert(constraintIdx, splineIdx + 3) = 2.0; + b(constraintIdx) = a * dt * dt; +} + +void addEndAccelerationConstraint(scalar_t a, scalar_t dt, Eigen::SparseMatrix& A, vector_t& b, + int constraintIdx, int splineIdx) { + A.insert(constraintIdx, splineIdx + 0) = 20.0; + A.insert(constraintIdx, splineIdx + 1) = 12.0; + A.insert(constraintIdx, splineIdx + 2) = 6.0; + A.insert(constraintIdx, splineIdx + 3) = 2.0; + b(constraintIdx) = a * dt * dt; +} + +void addAccelerationContinuity(scalar_t dt_lhs, scalar_t dt_rhs, Eigen::SparseMatrix& A, vector_t& b, + int constraintIdx, int splineIdx_lhs, int splineIdx_rhs) { + const scalar_t scaling = dt_lhs / dt_rhs; + const scalar_t scaling2 = scaling * scaling; + + A.insert(constraintIdx, splineIdx_lhs + 0) = 20.0; + A.insert(constraintIdx, splineIdx_lhs + 1) = 12.0; + A.insert(constraintIdx, splineIdx_lhs + 2) = 6.0; + A.insert(constraintIdx, splineIdx_lhs + 3) = 2.0; + A.insert(constraintIdx, splineIdx_rhs + 3) = -2.0 * scaling2; + b(constraintIdx) = 0.0; +} + +void addJerkContinuity(scalar_t dt_lhs, scalar_t dt_rhs, Eigen::SparseMatrix& A, vector_t& b, int constraintIdx, + int splineIdx_lhs, int splineIdx_rhs) { + const scalar_t scaling = dt_lhs / dt_rhs; + const scalar_t scaling2 = scaling * scaling; + const scalar_t scaling3 = scaling2 * scaling; + + A.insert(constraintIdx, splineIdx_lhs + 0) = 60.0; + A.insert(constraintIdx, splineIdx_lhs + 1) = 24.0; + A.insert(constraintIdx, splineIdx_lhs + 2) = 6.0; + A.insert(constraintIdx, splineIdx_rhs + 2) = -6.0 * scaling3; + b(constraintIdx) = 0.0; +} + +} // namespace + +QuinticSwing::QuinticSwing() : splines({QuinticSpline()}) {} + +QuinticSwing::QuinticSwing(const SwingNode& start, scalar_t midHeight, const SwingNode& end) + : QuinticSwing(start, SwingNode{0.5 * (start.time + end.time), midHeight, 0.0}, end) {} + +QuinticSwing::QuinticSwing(const SwingNode& start, const SwingNode& mid, const SwingNode& end) + : QuinticSwing(std::vector{start, mid, end}) {} + +QuinticSwing::QuinticSwing(const std::vector& nodes) { + if (nodes.size() < 3) { + throw std::runtime_error("[QuinticSwing] need at least 3 nodes for spline fitting"); + } + + // Set up normalized spline conditions as a linear system + const size_t numSplines = nodes.size() - 1; + const size_t numVariablesPerSpline = 6; + const size_t numConditions = numVariablesPerSpline * numSplines; + + // Initialize sparse linear system A*x = b + Eigen::SparseMatrix A(numConditions, numConditions); + A.reserve(Eigen::VectorXi::Constant(numConditions, 6)); // Each constraint has max 6 entries + vector_t b(numConditions); + + int constraintIdx = 0; + for (int splineNum = 0; splineNum < numSplines; ++splineNum) { + const int splineIdx = splineNum * numVariablesPerSpline; + const scalar_t dt = nodes[splineNum + 1].time - nodes[splineNum].time; + + // check sorting + assert(dt > 0.0); + + // Position is given + addStartPositionConstraint(nodes[splineNum].position, A, b, constraintIdx++, splineIdx); + addEndPositionConstraint(nodes[splineNum + 1].position, A, b, constraintIdx++, splineIdx); + + // Velocity is given + addStartVelocityConstraint(nodes[splineNum].velocity, dt, A, b, constraintIdx++, splineIdx); + addEndVelocityConstraint(nodes[splineNum + 1].velocity, dt, A, b, constraintIdx++, splineIdx); + + // Acceleration is 0.0 at start and end of the curve + if (splineNum == 0) { + addStartAccelerationConstraint(0.0, dt, A, b, constraintIdx++, splineIdx); + } + if (splineNum == (numSplines - 1)) { + addEndAccelerationConstraint(0.0, dt, A, b, constraintIdx++, splineIdx); + } + + // Acceleration and jerk continuity for middle nodes + if (splineNum != (numSplines - 1)) { + const scalar_t dt_next = nodes[splineNum + 2].time - nodes[splineNum + 1].time; + addAccelerationContinuity(dt, dt_next, A, b, constraintIdx++, splineIdx, splineIdx + numVariablesPerSpline); + addJerkContinuity(dt, dt_next, A, b, constraintIdx++, splineIdx, splineIdx + numVariablesPerSpline); + } + } + // Expected number of constraints was added + assert(constraintIdx == numConditions); + + // Solve with x = inv(A'*A) * A' * b + Eigen::SparseMatrix AtA = A.adjoint() * A; + Eigen::SimplicialCholesky> chol(AtA); + vector_t rhs = A.adjoint() * b; + vector_t coefficients = chol.solve(rhs); + + assert(coefficients.allFinite()); + + // Extract and store results + for (int splineNum = 0; splineNum < numSplines; ++splineNum) { + const int splineIdx = splineNum * numVariablesPerSpline; + const scalar_t dt = nodes[splineNum + 1].time - nodes[splineNum].time; + splines.push_back(QuinticSpline(coefficients.segment(splineIdx), nodes[splineNum].time, dt)); + + // add when this spline ends (except for the last one) + if (splineNum != (numSplines - 1)) { + nodeTimes.push_back(nodes[splineNum + 1].time); + } + } +} + +scalar_t QuinticSwing::position(scalar_t time) const { + const auto index = ocs2::lookup::findIndexInTimeArray(nodeTimes, time); + return splines[index].position(time); +} + +scalar_t QuinticSwing::velocity(scalar_t time) const { + const auto index = ocs2::lookup::findIndexInTimeArray(nodeTimes, time); + return splines[index].velocity(time); +} + +scalar_t QuinticSwing::acceleration(scalar_t time) const { + const auto index = ocs2::lookup::findIndexInTimeArray(nodeTimes, time); + return splines[index].acceleration(time); +} + +scalar_t QuinticSwing::jerk(scalar_t time) const { + const auto index = ocs2::lookup::findIndexInTimeArray(nodeTimes, time); + return splines[index].jerk(time); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SplineCpg.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SplineCpg.cpp new file mode 100644 index 000000000..454db8824 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SplineCpg.cpp @@ -0,0 +1,43 @@ +// +// Created by rgrandia on 13.03.20. +// + +#include "ocs2_switched_model_interface/foot_planner/SplineCpg.h" + +namespace switched_model { + +SplineCpg::SplineCpg(CubicSpline::Node liftOff, scalar_t midHeight, CubicSpline::Node touchDown) + : SplineCpg(liftOff, CubicSpline::Node{(liftOff.time + touchDown.time) / 2.0, midHeight, 0.0}, touchDown) {} + +SplineCpg::SplineCpg(CubicSpline::Node liftOff, CubicSpline::Node midNode, CubicSpline::Node touchDown) + : midTime_(midNode.time), leftSpline_(liftOff, midNode), rightSpline_(midNode, touchDown) {} + +scalar_t SplineCpg::position(scalar_t time) const { + return (time < midTime_) ? leftSpline_.position(time) : rightSpline_.position(time); +} + +scalar_t SplineCpg::velocity(scalar_t time) const { + return (time < midTime_) ? leftSpline_.velocity(time) : rightSpline_.velocity(time); +} + +scalar_t SplineCpg::acceleration(scalar_t time) const { + return (time < midTime_) ? leftSpline_.acceleration(time) : rightSpline_.acceleration(time); +} + +scalar_t SplineCpg::startTimeDerivative(scalar_t time) const { + if (time <= midTime_) { + return leftSpline_.startTimeDerivative(time) + 0.5 * leftSpline_.startTimeDerivative(time); + } else { + return 0.5 * rightSpline_.startTimeDerivative(time); + } +} + +scalar_t SplineCpg::finalTimeDerivative(scalar_t time) const { + if (time <= midTime_) { + return 0.5 * leftSpline_.finalTimeDerivative(time); + } else { + return rightSpline_.finalTimeDerivative(time) + 0.5 * rightSpline_.finalTimeDerivative(time); + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingSpline3d.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingSpline3d.cpp new file mode 100644 index 000000000..7667ad125 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingSpline3d.cpp @@ -0,0 +1,45 @@ +// +// Created by rgrandia on 03.08.21. +// + +#include "ocs2_switched_model_interface/foot_planner/SwingSpline3d.h" + +namespace switched_model { + +SwingSpline3d::SwingSpline3d(const SwingNode3d& start, const SwingNode3d& mid, const SwingNode3d& end) + : SwingSpline3d(std::vector{start, mid, end}) {} + +SwingSpline3d::SwingSpline3d(const std::vector& nodes) { + std::vector x; + x.reserve(nodes.size()); + std::vector y; + y.reserve(nodes.size()); + std::vector z; + y.reserve(nodes.size()); + for (const auto& node : nodes) { + x.push_back({node.time, node.position.x(), node.velocity.x()}); + y.push_back({node.time, node.position.y(), node.velocity.y()}); + z.push_back({node.time, node.position.z(), node.velocity.z()}); + } + x_ = QuinticSwing(x); + y_ = QuinticSwing(y); + z_ = QuinticSwing(z); +} + +vector3_t SwingSpline3d::position(scalar_t time) const { + return {x_.position(time), y_.position(time), z_.position(time)}; +} + +vector3_t SwingSpline3d::velocity(scalar_t time) const { + return {x_.velocity(time), y_.velocity(time), z_.velocity(time)}; +} + +vector3_t SwingSpline3d::acceleration(scalar_t time) const { + return {x_.acceleration(time), y_.acceleration(time), z_.acceleration(time)}; +} + +vector3_t SwingSpline3d::jerk(scalar_t time) const { + return {x_.jerk(time), y_.jerk(time), z_.jerk(time)}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingTrajectoryPlanner.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingTrajectoryPlanner.cpp new file mode 100644 index 000000000..4e8ca4172 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/foot_planner/SwingTrajectoryPlanner.cpp @@ -0,0 +1,614 @@ +// +// Created by rgrandia on 13.03.20. +// + +#include "ocs2_switched_model_interface/foot_planner/SwingTrajectoryPlanner.h" + +#include +#include + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/core/Rotations.h" +#include "ocs2_switched_model_interface/foot_planner/KinematicFootPlacementPenalty.h" + +namespace switched_model { + +SwingTrajectoryPlanner::SwingTrajectoryPlanner(SwingTrajectoryPlannerSettings settings, + const KinematicsModelBase& kinematicsModel, + const InverseKinematicsModelBase* inverseKinematicsModelPtr) + : settings_(std::move(settings)), + kinematicsModel_(kinematicsModel.clone()), + inverseKinematicsModelPtr_(nullptr), + terrainModel_(nullptr) { + if (inverseKinematicsModelPtr != nullptr) { + inverseKinematicsModelPtr_.reset(inverseKinematicsModelPtr->clone()); + } +} + +void SwingTrajectoryPlanner::updateTerrain(std::unique_ptr terrainModel) { + terrainModel_ = std::move(terrainModel); +} + +const SignedDistanceField* SwingTrajectoryPlanner::getSignedDistanceField() const { + if (terrainModel_) { + return terrainModel_->getSignedDistanceField(); + } else { + return nullptr; + } +} + +void SwingTrajectoryPlanner::updateSwingMotions(scalar_t initTime, scalar_t finalTime, const comkino_state_t& currentState, + const ocs2::TargetTrajectories& targetTrajectories, + const ocs2::ModeSchedule& modeSchedule) { + if (!terrainModel_) { + throw std::runtime_error("[SwingTrajectoryPlanner] terrain cannot be null. Update the terrain before planning swing motions"); + } + + // Need a copy to + // 1. possibly overwrite joint references later (adapted with inverse kinematics) + // 2. ensure a maximum interval between references points. + // 3. unsure we have samples at start and end of the MPC horizon. + subsampleReferenceTrajectory(targetTrajectories, initTime, finalTime); + + const feet_array_t> contactTimingsPerLeg = extractContactTimingsPerLeg(modeSchedule); + + const auto basePose = getBasePose(currentState); + const auto feetPositions = kinematicsModel_->feetPositionsInOriginFrame(basePose, getJointPositions(currentState)); + + for (int leg = 0; leg < NUM_CONTACT_POINTS; leg++) { + const auto& contactTimings = contactTimingsPerLeg[leg]; + + // Update last contacts + if (!contactTimings.empty()) { + if (startsWithStancePhase(contactTimings)) { + // If currently in contact -> update expected liftoff. + if (hasEndTime(contactTimings.front())) { + updateLastContact(leg, contactTimings.front().end, feetPositions[leg], *terrainModel_); + } else { // Expected liftoff unknown, set to end of horizon + updateLastContact(leg, finalTime, feetPositions[leg], *terrainModel_); + } + } else { + // If currently in swing -> verify that liftoff was before the horizon. If not, assume liftoff happened exactly at initTime + if (lastContacts_[leg].first > initTime) { + updateLastContact(leg, initTime, feetPositions[leg], *terrainModel_); + } + } + } + + // Select heuristic footholds. + heuristicFootholdsPerLeg_[leg] = selectHeuristicFootholds(leg, contactTimings, targetTrajectories, initTime, currentState, finalTime); + + // Select terrain constraints based on the heuristic footholds. + nominalFootholdsPerLeg_[leg] = selectNominalFootholdTerrain(leg, contactTimings, heuristicFootholdsPerLeg_[leg], targetTrajectories, + initTime, currentState, finalTime, *terrainModel_); + + // Create swing trajectories + if (settings_.swingTrajectoryFromReference) { + std::tie(feetNormalTrajectoriesEvents_[leg], feetNormalTrajectories_[leg]) = + extractSwingTrajectoriesFromReference(leg, contactTimings, finalTime); + } else { + std::tie(feetNormalTrajectoriesEvents_[leg], feetNormalTrajectories_[leg]) = + generateSwingTrajectories(leg, contactTimings, finalTime); + } + } + + if (inverseKinematicsModelPtr_ && !settings_.swingTrajectoryFromReference) { + adaptJointReferencesWithInverseKinematics(finalTime); + } +} + +const FootPhase& SwingTrajectoryPlanner::getFootPhase(size_t leg, scalar_t time) const { + const auto index = ocs2::lookup::findIndexInTimeArray(feetNormalTrajectoriesEvents_[leg], time); + return *feetNormalTrajectories_[leg][index]; +} + +auto SwingTrajectoryPlanner::generateSwingTrajectories(int leg, const std::vector& contactTimings, scalar_t finalTime) const + -> std::pair, std::vector>> { + std::vector eventTimes; + std::vector> footPhases; + + // First swing phase + if (startsWithSwingPhase(contactTimings)) { + SwingPhase::SwingEvent liftOff{lastContacts_[leg].first, settings_.liftOffVelocity, &lastContacts_[leg].second}; + SwingPhase::SwingEvent touchDown = [&] { + if (touchesDownAtLeastOnce(contactTimings)) { + return SwingPhase::SwingEvent{contactTimings.front().start, settings_.touchDownVelocity, + &nominalFootholdsPerLeg_[leg].front().plane}; + } else { + return SwingPhase::SwingEvent{finalTime + settings_.referenceExtensionAfterHorizon, 0.0, nullptr}; + } + }(); + + SwingPhase::SwingProfile swingProfile = getDefaultSwingProfile(); + applySwingMotionScaling(liftOff, touchDown, swingProfile); + + footPhases.emplace_back(new SwingPhase(liftOff, touchDown, swingProfile, terrainModel_.get())); + } + + // Loop through contact phases + for (int i = 0; i < contactTimings.size(); ++i) { + const auto& currentContactTiming = contactTimings[i]; + const ConvexTerrain& nominalFoothold = nominalFootholdsPerLeg_[leg][i]; + + // If phase starts after the horizon, we don't need to plan for it + if (currentContactTiming.start > finalTime) { + break; + } + + // generate contact phase + if (hasStartTime(currentContactTiming)) { + eventTimes.push_back(currentContactTiming.start); + } + footPhases.emplace_back(new StancePhase(nominalFoothold, settings_.terrainMargin)); + + // If contact phase extends beyond the horizon, we can stop planning. + if (!hasEndTime(currentContactTiming) || currentContactTiming.end > finalTime) { + break; + } + + // generate swing phase afterwards + SwingPhase::SwingEvent liftOff{currentContactTiming.end, settings_.liftOffVelocity, &nominalFoothold.plane}; + SwingPhase::SwingEvent touchDown = [&] { + const bool nextContactExists = (i + 1) < contactTimings.size(); + if (nextContactExists) { + return SwingPhase::SwingEvent{contactTimings[i + 1].start, settings_.touchDownVelocity, &nominalFootholdsPerLeg_[leg][i + 1].plane}; + } else { + return SwingPhase::SwingEvent{finalTime + settings_.referenceExtensionAfterHorizon, 0.0, nullptr}; + } + }(); + + SwingPhase::SwingProfile swingProfile = getDefaultSwingProfile(); + applySwingMotionScaling(liftOff, touchDown, swingProfile); + + eventTimes.push_back(currentContactTiming.end); + footPhases.emplace_back(new SwingPhase(liftOff, touchDown, swingProfile, terrainModel_.get())); + } + + return std::make_pair(eventTimes, std::move(footPhases)); +} + +std::pair, std::vector>> SwingTrajectoryPlanner::extractSwingTrajectoriesFromReference( + int leg, const std::vector& contactTimings, scalar_t finalTime) const { + std::vector eventTimes; + std::vector> footPhases; + + // First swing phase + if (startsWithSwingPhase(contactTimings)) { + scalar_t liftOffTime{lastContacts_[leg].first}; + scalar_t touchDownTime = [&] { + if (touchesDownAtLeastOnce(contactTimings)) { + return contactTimings.front().start; + } else { + return finalTime + settings_.referenceExtensionAfterHorizon; + } + }(); + + footPhases.push_back(extractExternalSwingPhase(leg, liftOffTime, touchDownTime)); + } + + // Loop through contact phases + for (int i = 0; i < contactTimings.size(); ++i) { + const auto& currentContactTiming = contactTimings[i]; + const ConvexTerrain& nominalFoothold = nominalFootholdsPerLeg_[leg][i]; + + // If phase starts after the horizon, we don't need to plan for it + if (currentContactTiming.start > finalTime) { + break; + } + + // generate contact phase + if (hasStartTime(currentContactTiming)) { + eventTimes.push_back(currentContactTiming.start); + } + footPhases.emplace_back(new StancePhase(nominalFoothold, settings_.terrainMargin)); + + // If contact phase extends beyond the horizon, we can stop planning. + if (!hasEndTime(currentContactTiming) || currentContactTiming.end > finalTime) { + break; + } + + // generate swing phase afterwards + scalar_t liftOffTime{currentContactTiming.end}; + scalar_t touchDownTime = [&] { + const bool nextContactExists = (i + 1) < contactTimings.size(); + if (nextContactExists) { + return contactTimings[i + 1].start; + } else { + return finalTime + settings_.referenceExtensionAfterHorizon; + } + }(); + + eventTimes.push_back(currentContactTiming.end); + footPhases.push_back(extractExternalSwingPhase(leg, liftOffTime, touchDownTime)); + } + + return std::make_pair(eventTimes, std::move(footPhases)); +} + +void SwingTrajectoryPlanner::applySwingMotionScaling(SwingPhase::SwingEvent& liftOff, SwingPhase::SwingEvent& touchDown, + SwingPhase::SwingProfile& swingProfile) const { + const scalar_t scaling = [&]() { + if (std::isnan(liftOff.time) || std::isnan(touchDown.time)) { + return 1.0; + } else { + return std::min(1.0, (touchDown.time - liftOff.time) / settings_.swingTimeScale); + } + }(); + + if (scaling < 1.0) { + liftOff.velocity *= scaling; + touchDown.velocity *= scaling; + swingProfile.sdfMidswingMargin = scaling * settings_.sdfMidswingMargin; + for (auto& node : swingProfile.nodes) { + node.swingHeight *= scaling; + node.normalVelocity *= scaling; + } + } +} + +std::unique_ptr SwingTrajectoryPlanner::extractExternalSwingPhase(int leg, scalar_t liftOffTime, + scalar_t touchDownTime) const { + std::vector time; + std::vector positions; + std::vector velocities; + + const auto liftoffIndex = ocs2::LinearInterpolation::timeSegment(liftOffTime, targetTrajectories_.timeTrajectory); + const auto touchdownIndex = ocs2::LinearInterpolation::timeSegment(touchDownTime, targetTrajectories_.timeTrajectory); + + // liftoff + if (liftOffTime < targetTrajectories_.timeTrajectory[liftoffIndex.first + 1]) { + const vector_t state = ocs2::LinearInterpolation::interpolate(liftoffIndex, targetTrajectories_.stateTrajectory); + const vector_t input = ocs2::LinearInterpolation::interpolate(liftoffIndex, targetTrajectories_.inputTrajectory); + time.push_back(liftOffTime); + positions.push_back(kinematicsModel_->footPositionInOriginFrame(leg, getBasePose(state), getJointPositions(state))); + velocities.push_back(kinematicsModel_->footVelocityInOriginFrame(leg, getBasePose(state), getBaseLocalVelocities(state), + getJointPositions(state), getJointVelocities(input))); + } + + // intermediate + for (int k = liftoffIndex.first + 1; k < touchdownIndex.first; ++k) { + const auto& state = targetTrajectories_.stateTrajectory[k]; + time.push_back(targetTrajectories_.timeTrajectory[k]); + positions.push_back(kinematicsModel_->footPositionInOriginFrame(leg, getBasePose(state), getJointPositions(state))); + velocities.push_back(kinematicsModel_->footVelocityInOriginFrame(leg, getBasePose(state), getBaseLocalVelocities(state), + getJointPositions(state), + getJointVelocities(targetTrajectories_.inputTrajectory[k]))); + } + + // touchdown + if (time.back() < touchDownTime) { + const vector_t state = ocs2::LinearInterpolation::interpolate(touchdownIndex, targetTrajectories_.stateTrajectory); + const vector_t input = ocs2::LinearInterpolation::interpolate(touchdownIndex, targetTrajectories_.inputTrajectory); + time.push_back(touchDownTime); + positions.push_back(kinematicsModel_->footPositionInOriginFrame(leg, getBasePose(state), getJointPositions(state))); + velocities.push_back(kinematicsModel_->footVelocityInOriginFrame(leg, getBasePose(state), getBaseLocalVelocities(state), + getJointPositions(state), getJointVelocities(input))); + } + + return std::unique_ptr(new ExternalSwingPhase(move(time), move(positions), move(velocities))); +} + +std::vector SwingTrajectoryPlanner::selectHeuristicFootholds(int leg, const std::vector& contactTimings, + const ocs2::TargetTrajectories& targetTrajectories, + scalar_t initTime, const comkino_state_t& currentState, + scalar_t finalTime) const { + // Zmp preparation : measured state + const auto initBasePose = getBasePose(currentState); + const auto initBaseOrientation = getOrientation(initBasePose); + const auto initBaseTwistInBase = getBaseLocalVelocities(currentState); + const auto initBaseLinearVelocityInWorld = rotateVectorBaseToOrigin(getLinearVelocity(initBaseTwistInBase), initBaseOrientation); + + // Zmp preparation : desired state + const vector_t initDesiredState = targetTrajectories.getDesiredState(initTime); + const base_coordinate_t initDesiredBasePose = initDesiredState.head(); + const auto initDesiredOrientation = getOrientation(initDesiredBasePose); + const base_coordinate_t initDesiredBaseTwistInBase = initDesiredState.segment(BASE_COORDINATE_SIZE); + const auto initDesiredBaseLinearVelocityInWorld = + rotateVectorBaseToOrigin(getLinearVelocity(initDesiredBaseTwistInBase), initDesiredOrientation); + + // Compute zmp / inverted pendulum foot placement offset: delta p = sqrt(h / g) * (v - v_des) + scalar_t pendulumFrequency = std::sqrt(settings_.invertedPendulumHeight / 9.81); + scalar_t zmpX = pendulumFrequency * (initBaseLinearVelocityInWorld.x() - initDesiredBaseLinearVelocityInWorld.x()); + scalar_t zmpY = pendulumFrequency * (initBaseLinearVelocityInWorld.y() - initDesiredBaseLinearVelocityInWorld.y()); + const vector3_t zmpReactiveOffset = {zmpX, zmpY, 0.0}; + + // Heuristic footholds to fill + std::vector heuristicFootholds; + + // Heuristic foothold is equal to current foothold for legs in contact + if (startsWithStancePhase(contactTimings)) { + heuristicFootholds.push_back(lastContacts_[leg].second.positionInWorld); + } + + // For future contact phases, use TargetTrajectories at halve the contact phase + int contactCount = 0; + for (const auto& contactPhase : contactTimings) { + if (hasStartTime(contactPhase)) { + const scalar_t contactEndTime = getContactEndTime(contactPhase, finalTime); + const scalar_t middleContactTime = 0.5 * (contactEndTime + contactPhase.start); + + // Compute foot position from cost desired trajectory + const vector_t state = targetTrajectories.getDesiredState(middleContactTime); + const auto desiredBasePose = getBasePose(state); + const auto desiredJointPositions = getJointPositions(state); + vector3_t referenceFootholdPositionInWorld = kinematicsModel_->footPositionInOriginFrame(leg, desiredBasePose, desiredJointPositions); + + // Add ZMP offset to the first upcoming foothold. + if (contactCount == 0) { + referenceFootholdPositionInWorld += zmpReactiveOffset; + } + + // One foothold added per contactPhase + heuristicFootholds.push_back(referenceFootholdPositionInWorld); + + // Can stop for this leg if we have processed one contact phase after (or extending across) the horizon + if (contactEndTime > finalTime) { + break; + } + } + ++contactCount; + } + + return heuristicFootholds; +} + +std::vector SwingTrajectoryPlanner::selectNominalFootholdTerrain(int leg, const std::vector& contactTimings, + const std::vector& heuristicFootholds, + const ocs2::TargetTrajectories& targetTrajectories, + scalar_t initTime, const comkino_state_t& currentState, + scalar_t finalTime, + const TerrainModel& terrainModel) const { + // Will increment the heuristic each time after selecting a nominalFootholdTerrain + auto heuristicFootholdIt = heuristicFootholds.cbegin(); + std::vector nominalFootholdTerrain; + + // Nominal foothold is equal to current foothold for legs in contact + if (startsWithStancePhase(contactTimings)) { + ConvexTerrain convexTerrain; + convexTerrain.plane = lastContacts_[leg].second; + nominalFootholdTerrain.push_back(convexTerrain); + ++heuristicFootholdIt; // Skip this heuristic. Use lastContact directly + } + + // For future contact phases + for (const auto& contactPhase : contactTimings) { + if (hasStartTime(contactPhase)) { + const scalar_t timeTillContact = contactPhase.start - initTime; + const scalar_t contactEndTime = getContactEndTime(contactPhase, finalTime); + const scalar_t middleContactTime = 0.5 * (contactEndTime + contactPhase.start); + + // Get previous foothold if there was one at this time + const FootPhase* previousIterationContact = getFootPhaseIfInContact(leg, middleContactTime); + + if (timeTillContact < settings_.previousFootholdTimeDeadzone && previousIterationContact != nullptr) { + // Simply copy the information out of the previous iteration + nominalFootholdTerrain.push_back(*previousIterationContact->nominalFootholdConstraint()); + ++heuristicFootholdIt; // Skip this heuristic. Using the previous terrain instead + } else { + // Select the terrain base on the heuristic + vector3_t referenceFootholdPositionInWorld = *heuristicFootholdIt; + + // Filter w.r.t. previous foothold + if (previousIterationContact != nullptr) { + referenceFootholdPositionInWorld = + filterFoothold(referenceFootholdPositionInWorld, previousIterationContact->nominalFootholdLocation()); + } + + // Kinematic penalty + const base_coordinate_t basePoseAtTouchdown = getBasePose(targetTrajectories.getDesiredState(contactPhase.start)); + const auto hipPositionInWorldTouchdown = kinematicsModel_->legRootInOriginFrame(leg, basePoseAtTouchdown); + const auto hipOrientationInWorldTouchdown = kinematicsModel_->orientationLegRootToOriginFrame(leg, basePoseAtTouchdown); + const base_coordinate_t basePoseAtLiftoff = getBasePose(targetTrajectories.getDesiredState(contactEndTime)); + const auto hipPositionInWorldLiftoff = kinematicsModel_->legRootInOriginFrame(leg, basePoseAtLiftoff); + const auto hipOrientationInWorldLiftoff = kinematicsModel_->orientationLegRootToOriginFrame(leg, basePoseAtLiftoff); + ApproximateKinematicsConfig config; + config.kinematicPenaltyWeight = settings_.legOverExtensionPenalty; + config.maxLegExtension = settings_.nominalLegExtension; + auto scoringFunction = [&](const vector3_t& footPositionInWorld) { + return computeKinematicPenalty(footPositionInWorld, hipPositionInWorldTouchdown, hipOrientationInWorldTouchdown, config) + + computeKinematicPenalty(footPositionInWorld, hipPositionInWorldLiftoff, hipOrientationInWorldLiftoff, config); + }; + + if (contactPhase.start < finalTime) { + ConvexTerrain convexTerrain = terrainModel.getConvexTerrainAtPositionInWorld(referenceFootholdPositionInWorld, scoringFunction); + nominalFootholdTerrain.push_back(convexTerrain); + ++heuristicFootholdIt; + } else { // After the horizon -> we are only interested in the position and orientation + ConvexTerrain convexTerrain; + convexTerrain.plane = + terrainModel.getLocalTerrainAtPositionInWorldAlongGravity(referenceFootholdPositionInWorld, scoringFunction); + nominalFootholdTerrain.push_back(convexTerrain); + ++heuristicFootholdIt; + } + } + + // Can stop for this leg if we have processed one contact phase after (or extending across) the horizon + if (contactEndTime > finalTime) { + break; + } + } + } + + return nominalFootholdTerrain; +} + +void SwingTrajectoryPlanner::subsampleReferenceTrajectory(const ocs2::TargetTrajectories& targetTrajectories, scalar_t initTime, + scalar_t finalTime) { + if (targetTrajectories.empty()) { + throw std::runtime_error("[SwingTrajectoryPlanner] provided target trajectory cannot be empty."); + } + + targetTrajectories_.clear(); + + // Add first reference + { + const auto initInterpIndex = ocs2::LinearInterpolation::timeSegment(initTime, targetTrajectories.timeTrajectory); + targetTrajectories_.timeTrajectory.push_back(initTime); + targetTrajectories_.stateTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(initInterpIndex, targetTrajectories.stateTrajectory)); + targetTrajectories_.inputTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(initInterpIndex, targetTrajectories.inputTrajectory)); + } + + for (int k = 0; k < targetTrajectories.timeTrajectory.size(); ++k) { + if (targetTrajectories.timeTrajectory[k] < initTime) { + continue; // Drop all samples before init time + } else if (targetTrajectories.timeTrajectory[k] > finalTime) { + // Add final time sample. Samples after final time are also kept for touchdowns after the horizon. + const auto finalInterpIndex = ocs2::LinearInterpolation::timeSegment(finalTime, targetTrajectories.timeTrajectory); + targetTrajectories_.timeTrajectory.push_back(finalTime); + targetTrajectories_.stateTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(finalInterpIndex, targetTrajectories.stateTrajectory)); + targetTrajectories_.inputTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(finalInterpIndex, targetTrajectories.inputTrajectory)); + } + + // Check if we need to add extra intermediate samples + while (targetTrajectories_.timeTrajectory.back() + settings_.maximumReferenceSampleTime < targetTrajectories.timeTrajectory[k]) { + const scalar_t t = targetTrajectories_.timeTrajectory.back() + settings_.maximumReferenceSampleTime; + const auto interpIndex = ocs2::LinearInterpolation::timeSegment(t, targetTrajectories.timeTrajectory); + + targetTrajectories_.timeTrajectory.push_back(t); + targetTrajectories_.stateTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(interpIndex, targetTrajectories.stateTrajectory)); + targetTrajectories_.inputTrajectory.push_back( + ocs2::LinearInterpolation::interpolate(interpIndex, targetTrajectories.inputTrajectory)); + } + + // Add the original reference sample + targetTrajectories_.timeTrajectory.push_back(targetTrajectories.timeTrajectory[k]); + targetTrajectories_.stateTrajectory.push_back(targetTrajectories.stateTrajectory[k]); + targetTrajectories_.inputTrajectory.push_back(targetTrajectories.inputTrajectory[k]); + } +} + +void SwingTrajectoryPlanner::adaptJointReferencesWithInverseKinematics(scalar_t finalTime) { + const scalar_t damping = 0.01; // Quite some damping on the IK to get well conditions references. + + for (int k = 0; k < targetTrajectories_.timeTrajectory.size(); ++k) { + const scalar_t t = targetTrajectories_.timeTrajectory[k]; + + const base_coordinate_t basePose = getBasePose(comkino_state_t(targetTrajectories_.stateTrajectory[k])); + const vector3_t basePositionInWorld = getPositionInOrigin(basePose); + const vector3_t eulerXYZ = getOrientation(basePose); + + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + const auto& footPhase = this->getFootPhase(leg, t); + + // Joint positions + const vector3_t positionBaseToFootInWorldFrame = footPhase.getPositionInWorld(t) - basePositionInWorld; + const vector3_t positionBaseToFootInBaseFrame = rotateVectorOriginToBase(positionBaseToFootInWorldFrame, eulerXYZ); + + const size_t stateOffset = 2 * BASE_COORDINATE_SIZE + 3 * leg; + targetTrajectories_.stateTrajectory[k].segment(stateOffset, 3) = + inverseKinematicsModelPtr_->getLimbJointPositionsFromPositionBaseToFootInBaseFrame(leg, positionBaseToFootInBaseFrame); + + // Joint velocities + auto jointPositions = getJointPositions(targetTrajectories_.stateTrajectory[k]); + auto baseTwistInBaseFrame = getBaseLocalVelocities(targetTrajectories_.stateTrajectory[k]); + + const vector3_t b_baseToFoot = kinematicsModel_->positionBaseToFootInBaseFrame(leg, jointPositions); + const vector3_t footVelocityInBaseFrame = rotateVectorOriginToBase(footPhase.getVelocityInWorld(t), eulerXYZ); + const vector3_t footRelativeVelocityInBaseFrame = + footVelocityInBaseFrame - getLinearVelocity(baseTwistInBaseFrame) - getAngularVelocity(baseTwistInBaseFrame).cross(b_baseToFoot); + + const size_t inputOffset = 3 * NUM_CONTACT_POINTS + 3 * leg; + targetTrajectories_.inputTrajectory[k].segment(inputOffset, 3) = + inverseKinematicsModelPtr_->getLimbVelocitiesFromFootVelocityRelativeToBaseInBaseFrame( + leg, footRelativeVelocityInBaseFrame, kinematicsModel_->baseToFootJacobianBlockInBaseFrame(leg, jointPositions), damping); + } + + // Can stop adaptation as soon as we have processed a point beyond the horizon. + if (t > finalTime) { + break; + } + } +} + +void SwingTrajectoryPlanner::updateLastContact(int leg, scalar_t expectedLiftOff, const vector3_t& currentFootPosition, + const TerrainModel& terrainModel) { + // Get orientation from terrain model, position from the kinematics + auto lastContactTerrain = terrainModel.getLocalTerrainAtPositionInWorldAlongGravity(currentFootPosition); + lastContactTerrain.positionInWorld = currentFootPosition; + lastContacts_[leg] = {expectedLiftOff, lastContactTerrain}; +} + +SwingPhase::SwingProfile SwingTrajectoryPlanner::getDefaultSwingProfile() const { + SwingPhase::SwingProfile defaultSwingProfile; + defaultSwingProfile.sdfMidswingMargin = settings_.sdfMidswingMargin; + defaultSwingProfile.maxSwingHeightAdaptation = 2.0 * settings_.swingHeight; + + SwingPhase::SwingProfile::Node midPoint; + midPoint.phase = 0.5; + midPoint.swingHeight = settings_.swingHeight; + midPoint.normalVelocity = 0.0; + midPoint.tangentialProgress = 0.6; + midPoint.tangentialVelocityFactor = 2.0; + defaultSwingProfile.nodes.push_back(midPoint); + return defaultSwingProfile; +} + +scalar_t SwingTrajectoryPlanner::getContactEndTime(const ContactTiming& contactPhase, scalar_t finalTime) const { + return hasEndTime(contactPhase) ? contactPhase.end : std::max(finalTime + settings_.referenceExtensionAfterHorizon, contactPhase.start); +} + +const FootPhase* SwingTrajectoryPlanner::getFootPhaseIfInContact(size_t leg, scalar_t time) const { + const FootPhase* previousIterationContact = nullptr; + if (!feetNormalTrajectories_[leg].empty()) { + const auto& footPhase = getFootPhase(leg, time); + if (footPhase.contactFlag()) { + previousIterationContact = &footPhase; + } + } + return previousIterationContact; +} + +vector3_t SwingTrajectoryPlanner::filterFoothold(const vector3_t& newFoothold, const vector3_t& previousFoothold) const { + // Apply Position deadzone and low pass filter + if ((newFoothold - previousFoothold).norm() < settings_.previousFootholdDeadzone) { + return previousFoothold; + } else { + // low pass filter + const scalar_t lambda = settings_.previousFootholdFactor; + return lambda * previousFoothold + (1.0 - lambda) * newFoothold; + } +} + +SwingTrajectoryPlannerSettings loadSwingTrajectorySettings(const std::string& filename, bool verbose) { + SwingTrajectoryPlannerSettings settings{}; + + boost::property_tree::ptree pt; + boost::property_tree::read_info(filename, pt); + + const std::string prefix{"model_settings.swing_trajectory_settings."}; + + if (verbose) { + std::cerr << "\n #### Swing trajectory Settings:" << std::endl; + std::cerr << " #### ==================================================" << std::endl; + } + + ocs2::loadData::loadPtreeValue(pt, settings.liftOffVelocity, prefix + "liftOffVelocity", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.touchDownVelocity, prefix + "touchDownVelocity", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.swingHeight, prefix + "swingHeight", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.errorGain, prefix + "errorGain", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.swingTimeScale, prefix + "swingTimeScale", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.sdfMidswingMargin, prefix + "sdfMidswingMargin", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.terrainMargin, prefix + "terrainMargin", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.previousFootholdFactor, prefix + "previousFootholdFactor", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.previousFootholdDeadzone, prefix + "previousFootholdDeadzone", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.previousFootholdTimeDeadzone, prefix + "previousFootholdTimeDeadzone", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.invertedPendulumHeight, prefix + "invertedPendulumHeight", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.nominalLegExtension, prefix + "nominalLegExtension", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.legOverExtensionPenalty, prefix + "legOverExtensionPenalty", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.referenceExtensionAfterHorizon, prefix + "referenceExtensionAfterHorizon", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.maximumReferenceSampleTime, prefix + "maximumReferenceSampleTime", verbose); + ocs2::loadData::loadPtreeValue(pt, settings.swingTrajectoryFromReference, prefix + "swingTrajectoryFromReference", verbose); + + if (verbose) { + std::cerr << " #### ==================================================" << std::endl; + } + + return settings; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/initialization/ComKinoInitializer.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/initialization/ComKinoInitializer.cpp new file mode 100644 index 000000000..822a7437d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/initialization/ComKinoInitializer.cpp @@ -0,0 +1,28 @@ +#include "ocs2_switched_model_interface/initialization/ComKinoInitializer.h" + +#include "ocs2_switched_model_interface/core/SwitchedModel.h" + +namespace switched_model { + +ComKinoInitializer::ComKinoInitializer(const com_model_t& comModel, const SwitchedModelModeScheduleManager& modeScheduleManager) + : comModelPtr_(comModel.clone()), modeScheduleManagerPtr_(&modeScheduleManager) {} + +ComKinoInitializer::ComKinoInitializer(const ComKinoInitializer& rhs) + : ocs2::Initializer(rhs), comModelPtr_(rhs.comModelPtr_->clone()), modeScheduleManagerPtr_(rhs.modeScheduleManagerPtr_) {} + +ComKinoInitializer* ComKinoInitializer::clone() const { + return new ComKinoInitializer(*this); +} + +void ComKinoInitializer::compute(scalar_t time, const vector_t& state, scalar_t nextTime, vector_t& input, vector_t& nextState) { + const comkino_state_t comkinoState = state; + const auto basePose = getBasePose(comkinoState); + const auto contactFlags = modeScheduleManagerPtr_->getContactFlags(time); + + // Initial guess + input = weightCompensatingInputs(*comModelPtr_, contactFlags, getOrientation(basePose)); + + nextState = state; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/DynamicsParametersSynchronizedModule.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/DynamicsParametersSynchronizedModule.cpp new file mode 100644 index 000000000..afa7caa2b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/DynamicsParametersSynchronizedModule.cpp @@ -0,0 +1,16 @@ +#include "ocs2_switched_model_interface/logic/DynamicsParametersSynchronizedModule.h" + +namespace switched_model { + +DynamicsParametersSynchronizedModule::DynamicsParametersSynchronizedModule() + : activeDynamicsParameters_(), + newDynamicsParameters_(std::unique_ptr>( + new ComKinoSystemDynamicsParameters(activeDynamicsParameters_))){}; + +void DynamicsParametersSynchronizedModule::preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& initState, + const ocs2::ReferenceManagerInterface& referenceManager) { + auto lockedDynamicsParameterPtr = newDynamicsParameters_.lock(); + activeDynamicsParameters_ = *lockedDynamicsParameterPtr; // Copy external parameters to the active parameter set +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/Gait.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/Gait.cpp new file mode 100644 index 000000000..a834621b0 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/Gait.cpp @@ -0,0 +1,74 @@ +// +// Created by rgrandia on 15.03.20. +// + +#include "ocs2_switched_model_interface/logic/Gait.h" +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" + +#include + +#include +#include +#include + +namespace switched_model { + +bool isValidGait(const Gait& gait) { + bool validGait = true; + validGait &= gait.duration > 0.0; + validGait &= std::all_of(gait.eventPhases.begin(), gait.eventPhases.end(), [](scalar_t phase) { return 0.0 < phase && phase < 1.0; }); + validGait &= std::is_sorted(gait.eventPhases.begin(), gait.eventPhases.end()); + validGait &= gait.eventPhases.size() + 1 == gait.modeSequence.size(); + return validGait; +} + +bool isValidPhase(scalar_t phase) { + return phase >= 0.0 && phase < 1.0; +} + +scalar_t wrapPhase(scalar_t phase) { + phase = std::fmod(phase, 1.0); + if (phase < 0.0) { + phase += 1.0; + } + return phase; +} + +int getModeIndexFromPhase(scalar_t phase, const Gait& gait) { + assert(isValidPhase(phase)); + assert(isValidGait(gait)); + auto firstLargerValueIterator = std::upper_bound(gait.eventPhases.begin(), gait.eventPhases.end(), phase); + return static_cast(firstLargerValueIterator - gait.eventPhases.begin()); +} + +size_t getModeFromPhase(scalar_t phase, const Gait& gait) { + assert(isValidPhase(phase)); + assert(isValidGait(gait)); + return gait.modeSequence[getModeIndexFromPhase(phase, gait)]; +} + +scalar_t timeLeftInGait(scalar_t phase, const Gait& gait) { + assert(isValidPhase(phase)); + assert(isValidGait(gait)); + return (1.0 - phase) * gait.duration; +} + +scalar_t timeLeftInMode(scalar_t phase, const Gait& gait) { + assert(isValidPhase(phase)); + assert(isValidGait(gait)); + int modeIndex = getModeIndexFromPhase(phase, gait); + if (modeIndex < gait.eventPhases.size()) { + return (gait.eventPhases[modeIndex] - phase) * gait.duration; + } else { + return timeLeftInGait(phase, gait); + } +} + +std::ostream& operator<<(std::ostream& stream, const Gait& gait) { + stream << "Duration: " << gait.duration << "\n"; + stream << "Event phases: {" << ocs2::toDelimitedString(gait.eventPhases) << "}\n"; + stream << "Mode sequence: {" << ocs2::toDelimitedString(gait.modeSequence) << "}\n"; + return stream; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitAdaptation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitAdaptation.cpp new file mode 100644 index 000000000..4d709f449 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitAdaptation.cpp @@ -0,0 +1,170 @@ +/* + * GaitAdaptation.cpp + * + * Created on: Jun 4, 2020 + * Author: Marko Bjelonic + */ + +// anymal ctrl ocs2 +#include "ocs2_switched_model_interface/logic/GaitAdaptation.h" + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/logic/SingleLegLogic.h" + +namespace switched_model { + +GaitAdaptation::GaitAdaptation(const GaitAdaptationSettings& settings, const contact_flag_t& measuredContactFlags) + : timeUntilNextTouchDownPerLeg_(constantFeetArray(0.0)), + timeUntilNextLiftOffPerLeg_(constantFeetArray(0.0)), + hasLiftedSinceLastContact_(constantFeetArray(true)), // initialize at true to enable immediate early touchdown + settings_(settings) {} + +void GaitAdaptation::advance(GaitSchedule& gaitSchedule, const contact_flag_t& measuredContactFlags, scalar_t dt) { + const auto desiredContactFlags = modeNumber2StanceLeg(gaitSchedule.getCurrentMode()); + + // Update tracking if lift off happened + advanceLiftoffTracking(desiredContactFlags, measuredContactFlags); + + // Update internal knowledge of next touchdown / liftoff + advanceSwingEvents(gaitSchedule); + + // Decide on a strategy per leg and schedule adaptation + const auto& scheduledAdaptation = advanceLegStrategies(desiredContactFlags, measuredContactFlags); + + // Apply all scheduled + applyAdaptation(gaitSchedule, scheduledAdaptation); +} + +void GaitAdaptation::advanceLiftoffTracking(const contact_flag_t& desiredContactFlags, const contact_flag_t& measuredContactFlags) { + // Lift off tracking resets to false whenever there is a planned + measured contact. The flag changes to true any time there is a measured + // swing phase since then. + for (size_t leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + if (desiredContactFlags[leg] && measuredContactFlags[leg]) { + hasLiftedSinceLastContact_[leg] = false; + } else if (!measuredContactFlags[leg]) { + hasLiftedSinceLastContact_[leg] = true; + } + } +} + +void GaitAdaptation::advanceSwingEvents(const GaitSchedule& gaitSchedule) { + // Only interested in events within the specified windows + const auto checkHorizon = settings_.earlyTouchDownTimeWindow; + + // Extract contact timings from the gait schedule + const auto modeSchedule = gaitSchedule.getModeSchedule(checkHorizon); + const auto contactTimingsPerLeg = switched_model::extractContactTimingsPerLeg(modeSchedule); + const auto currentTime = gaitSchedule.getCurrentTime(); + + for (size_t leg = 0; leg < switched_model::NUM_CONTACT_POINTS; ++leg) { + timeUntilNextTouchDownPerLeg_[leg] = getTimeOfNextTouchDown(currentTime, contactTimingsPerLeg[leg]) - currentTime; + timeUntilNextLiftOffPerLeg_[leg] = getTimeOfNextLiftOff(currentTime, contactTimingsPerLeg[leg]) - currentTime; + } +} + +auto GaitAdaptation::advanceLegStrategies(const contact_flag_t& desiredContactFlags, const contact_flag_t& measuredContactFlags) + -> feet_array_t { + auto adaptations = constantFeetArray(ScheduledAdaptation::None); + + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + bool desiredContact = desiredContactFlags[leg]; + bool measuredContact = measuredContactFlags[leg]; + + if (desiredContact) { + if (measuredContact) { + // Leg was planned to be in contact, and is measured to be in contact + adaptations[leg] = desiredContactMeasuredContact(leg); + } else { + // Leg was planned to be in contact, but is measured to be in swing + adaptations[leg] = desiredContactMeasuredMotion(leg); + } + } else { + if (measuredContact) { + // Leg was planned to be in swing, but is measured to be in contact + adaptations[leg] = desiredMotionMeasuredContact(leg); + } else { + // Leg was planned to be in swing, and is measured to be in swing + adaptations[leg] = desiredMotionMeasuredMotion(leg); + } + } + } + + return adaptations; +} + +auto GaitAdaptation::desiredContactMeasuredContact(size_t leg) -> ScheduledAdaptation { + return ScheduledAdaptation::None; +} + +auto GaitAdaptation::desiredContactMeasuredMotion(size_t leg) -> ScheduledAdaptation { + return ScheduledAdaptation::None; +} + +auto GaitAdaptation::desiredMotionMeasuredContact(size_t leg) -> ScheduledAdaptation { + if (hasLiftedSinceLastContact_[leg] && !std::isnan(timeUntilNextTouchDownPerLeg_[leg]) && + timeUntilNextTouchDownPerLeg_[leg] < settings_.earlyTouchDownTimeWindow) { + // Touchdown was planned to be soon -> Take the contact early + return ScheduledAdaptation::EarlyContact; + } else { + return ScheduledAdaptation::None; + } +} + +auto GaitAdaptation::desiredMotionMeasuredMotion(size_t leg) -> ScheduledAdaptation { + return ScheduledAdaptation::None; +} + +void GaitAdaptation::applyAdaptation(GaitSchedule& gaitSchedule, const feet_array_t& scheduledAdaptations) { + // Early contact + if (std::any_of(scheduledAdaptations.begin(), scheduledAdaptations.end(), isEarlyContact)) { + const auto earlyTouchDownPerLeg = applyPerLeg(isEarlyContact, scheduledAdaptations); + gaitSchedule.adaptCurrentGait(earlyTouchDownAdaptation(earlyTouchDownPerLeg)); + } +} + +std::function +earlyTouchDownAdaptation(const switched_model::feet_array_t& earlyTouchDownPerLeg) { + return [=](scalar_t& currentPhase, Gait& currentGait, scalar_t currTime, Gait& nextGait) { + const int currentModeIndex = getModeIndexFromPhase(currentPhase, currentGait); + for (unsigned int leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + if (earlyTouchDownPerLeg[leg]) { + const int modeIndexOfNextContact = getModeIndexOfNextContactStateOfLeg(true, currentModeIndex, leg, currentGait); + + if (modeIndexOfNextContact < currentGait.modeSequence.size()) { // update current gait + setContactStateOfLegBetweenModes(true, currentModeIndex, modeIndexOfNextContact, leg, currentGait); + } else { // update current gait till end, and next gait + setContactStateOfLegBetweenModes(true, currentModeIndex, modeIndexOfNextContact - 1, leg, currentGait); + + int modeIndexOfNextContactOfNextGait = getModeIndexOfNextContactStateOfLeg(true, 0, leg, nextGait); + if (modeIndexOfNextContactOfNextGait == nextGait.modeSequence.size()) { + --modeIndexOfNextContactOfNextGait; + } + setContactStateOfLegBetweenModes(true, 0, modeIndexOfNextContactOfNextGait, leg, nextGait); + } + } + } + }; +} + +int getModeIndexOfNextContactStateOfLeg(bool contact, int startModeIdx, size_t leg, const Gait& gait) { + int modeIndex = startModeIdx; + while (modeIndex < gait.modeSequence.size()) { + size_t currentMode = gait.modeSequence[modeIndex]; + if (modeNumber2StanceLeg(currentMode)[leg] == contact) { + break; + } else { + ++modeIndex; + } + } + return modeIndex; +} + +void setContactStateOfLegBetweenModes(bool contact, int startModeIdx, int lastModeIdx, size_t leg, Gait& gait) { + for (int modeIndex = startModeIdx; modeIndex <= lastModeIdx; ++modeIndex) { + auto stanceLegs = switched_model::modeNumber2StanceLeg(gait.modeSequence[modeIndex]); + stanceLegs[leg] = contact; + gait.modeSequence[modeIndex] = switched_model::stanceLeg2ModeNumber(stanceLegs); + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitReceiver.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitReceiver.cpp new file mode 100644 index 000000000..a18755644 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitReceiver.cpp @@ -0,0 +1,85 @@ +// +// Created by rgrandia on 16.03.20. +// + +#include "ocs2_switched_model_interface/logic/GaitReceiver.h" +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/logic/ModeSequenceTemplate.h" +#include "ocs2_switched_model_interface/ros_msg_conversions/RosMsgConversions.h" + +namespace switched_model { + +GaitReceiver::GaitReceiver(ros::NodeHandle nodeHandle, ocs2::Synchronized& gaitSchedule, const std::string& robotName) + : gaitSchedulePtr_(&gaitSchedule), gaitUpdated_(false) { + mpcModeSequenceSubscriber_ = nodeHandle.subscribe(robotName + "_mpc_mode_schedule", 1, &GaitReceiver::mpcModeSequenceCallback, this, + ::ros::TransportHints().udp()); + mpcScheduledModeSequenceSubscriber_ = nodeHandle.subscribe( + robotName + "_mpc_scheduled_mode_schedule", 1, &GaitReceiver::mpcModeScheduledGaitCallback, this, ::ros::TransportHints().udp()); + mpcGaitSequenceSubscriber_ = nodeHandle.subscribe(robotName + "_mpc_gait_schedule", 1, &GaitReceiver::mpcGaitSequenceCallback, this, + ::ros::TransportHints().udp()); +} + +void GaitReceiver::preSolverRun(scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::ReferenceManagerInterface& referenceManager) { + if (gaitUpdated_) { + { + std::lock_guard lock(receivedGaitMutex_); + setGaitAction_(initTime, finalTime, currentState, referenceManager.getTargetTrajectories()); + } + std::cout << std::endl; + gaitUpdated_ = false; + } +} + +void GaitReceiver::mpcModeSequenceCallback(const ocs2_msgs::mode_schedule::ConstPtr& msg) { + const auto modeSequenceTemplate = readModeSequenceTemplateMsg(*msg); + const auto gait = toGait(modeSequenceTemplate); + + { + std::lock_guard lock(receivedGaitMutex_); + setGaitAction_ = [=](scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::TargetTrajectories& targetTrajectories) { + std::cout << "[GaitReceiver]: Setting new gait after time " << finalTime << "\n[GaitReceiver]: " << gait; + this->gaitSchedulePtr_->lock()->setGaitAfterTime(gait, finalTime); + }; + gaitUpdated_ = true; + } +} + +void GaitReceiver::mpcModeScheduledGaitCallback(const ocs2_msgs::mode_schedule::ConstPtr& msg) { + const auto modeSequenceTemplate = readModeSequenceTemplateMsg(*msg); + const auto gait = toGait(modeSequenceTemplate); + const auto scheduledGaitTime = modeSequenceTemplate.switchingTimes.front(); + + std::cout << "ScheduledGaitCallback:\n"; + std::cout << "\nReceivedGait:\n" << gait << "\n"; + + { + std::lock_guard lock(receivedGaitMutex_); + setGaitAction_ = [=](scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::TargetTrajectories& targetTrajectories) { + std::cout << "[GaitReceiver]: Received new scheduled gait, setting it at time " << scheduledGaitTime << ", current time: " << initTime + << "\n[GaitReceiver]: " << gait; + this->gaitSchedulePtr_->lock()->setGaitAtTime(gait, scheduledGaitTime); + }; + gaitUpdated_ = true; + } +} + +void GaitReceiver::mpcGaitSequenceCallback(const ocs2_switched_model_msgs::scheduled_gait_sequenceConstPtr& msg) { + const auto scheduledGaitSequence = ros_msg_conversions::fromMessage(*msg); + + std::cout << "ScheduledGaitCallback:\n"; + std::cout << *msg << std::endl; + + { + std::lock_guard lock(receivedGaitMutex_); + setGaitAction_ = [=](scalar_t initTime, scalar_t finalTime, const vector_t& currentState, + const ocs2::TargetTrajectories& targetTrajectories) { + this->gaitSchedulePtr_->lock()->setGaitSequenceAtTime(scheduledGaitSequence.second, scheduledGaitSequence.first); + }; + gaitUpdated_ = true; + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitSchedule.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitSchedule.cpp new file mode 100644 index 000000000..b84af1dd4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/GaitSchedule.cpp @@ -0,0 +1,127 @@ +// +// Created by rgrandia on 15.03.20. +// + +#include "ocs2_switched_model_interface/logic/GaitSchedule.h" + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" +#include "ocs2_switched_model_interface/logic/GaitSwitching.h" + +namespace switched_model { + +GaitSchedule::GaitSchedule(scalar_t time, Gait gait) : time_(time), phase_(0.0), gaitSchedule_{std::move(gait)} {} + +void GaitSchedule::advanceToTime(scalar_t time) { + if (time <= time_) { + return; + } + + const scalar_t dt = time - time_; + std::deque::iterator newActiveGait; + std::tie(phase_, newActiveGait) = advancePhase(phase_, dt, gaitSchedule_.begin(), gaitSchedule_.end()); + time_ = time; + + // Remove gaits that have been completed. + while (newActiveGait != gaitSchedule_.begin()) { + gaitSchedule_.pop_front(); + } +} + +void GaitSchedule::setNextGait(const Gait& gait) { + setGaitSequenceAfterCurrentGait({gait}); +} + +void GaitSchedule::setGaitSequenceAfterCurrentGait(const GaitSequence& gaitSequence) { + gaitSchedule_.erase(gaitSchedule_.begin() + 1, gaitSchedule_.end()); + gaitSchedule_.insert(gaitSchedule_.end(), gaitSequence.begin(), gaitSequence.end()); +} + +void GaitSchedule::setGaitAtTime(const Gait& gait, scalar_t time) { + setGaitSequenceAtTime({gait}, time); +} + +void GaitSchedule::setGaitSequenceAtTime(const GaitSequence& gaitSequence, scalar_t time) { + assert(time >= time_); + + rolloutGaitScheduleTillTime(time); + + scalar_t newPhase; + std::deque::iterator newActiveGait; + std::tie(newPhase, newActiveGait) = advancePhase(phase_, time - time_, gaitSchedule_.begin(), gaitSchedule_.end()); + + // Shrink the gait that is active at "time", s.t. it ends at "time" + if (newActiveGait == gaitSchedule_.begin()) { + // Gait to shrink is already active. Determine new duration from the amount of time and phase left. + newActiveGait->duration = (time - time_) / (1.0 - phase_); + } else { + newActiveGait->duration *= newPhase; + } + + // Check if duration was set to zero + if (newActiveGait->duration > 0.0) { // keep newActiveGait and delete the ones after + gaitSchedule_.erase(newActiveGait + 1, gaitSchedule_.end()); + } else { // delete newActiveGait and the ones after + gaitSchedule_.erase(newActiveGait, gaitSchedule_.end()); + } + + gaitSchedule_.insert(gaitSchedule_.end(), gaitSequence.begin(), gaitSequence.end()); +} + +void GaitSchedule::setGaitAfterTime(const Gait& gait, scalar_t time) { + setGaitSequenceAfterTime({gait}, time); +} + +void GaitSchedule::setGaitSequenceAfterTime(const GaitSequence& gaitSequence, scalar_t time) { + assert(time >= time_); + + rolloutGaitScheduleTillTime(time); + + scalar_t newPhase; + std::deque::iterator newActiveGait; + std::tie(newPhase, newActiveGait) = advancePhase(phase_, time - time_, gaitSchedule_.begin(), gaitSchedule_.end()); + + gaitSchedule_.erase(newActiveGait + 1, gaitSchedule_.end()); + gaitSchedule_.insert(gaitSchedule_.end(), gaitSequence.begin(), gaitSequence.end()); +} + +void GaitSchedule::adaptCurrentGait( + const std::function& gaitAdaptor) { + // Repeat the last gait until we have 3 gaits in the schedule. This prevents that the gaitAdaptor modifies the nominal gait. + while (gaitSchedule_.size() < 3) { + gaitSchedule_.push_back(gaitSchedule_.back()); + } + + // Apply gait adaptation to the current and next gait + gaitAdaptor(phase_, gaitSchedule_.front(), time_, gaitSchedule_[1]); +} + +ocs2::ModeSchedule GaitSchedule::getModeSchedule(scalar_t timeHorizon) const { + return ::switched_model::getModeSchedule(phase_, time_, timeHorizon, gaitSchedule_.begin(), gaitSchedule_.end()); +} + +void GaitSchedule::rolloutGaitScheduleTillTime(scalar_t time) { + scalar_t tGaitEnd = time_ + timeLeftInGait(getCurrentPhase(), getCurrentGait()); + auto gaitIt = gaitSchedule_.begin(); + while (tGaitEnd <= time) { + if (std::next(gaitIt) == gaitSchedule_.end()) { + // End of the schedule reached: make the repetition of the last gait explicit + gaitSchedule_.push_back(gaitSchedule_.back()); + gaitIt = std::prev(gaitSchedule_.end(), 2); // Iterator can be invalidated after push_back, so reset set explicitly. + } + tGaitEnd += gaitIt->duration; + ++gaitIt; + } +} + +bool isStandingDuringTimeHorizon(scalar_t timeHorizon, const GaitSchedule& gaitSchedule) { + const auto modeSchedule = gaitSchedule.getModeSchedule(timeHorizon); + return std::all_of(modeSchedule.modeSequence.begin(), modeSchedule.modeSequence.end(), + [](size_t mode) { return mode == ModeNumber::STANCE; }); +} + +bool isStanding(const GaitSchedule& gaitSchedule) { + const auto& modeSequence = gaitSchedule.getCurrentGait().modeSequence; + return std::all_of(modeSequence.begin(), modeSequence.end(), [](size_t mode) { return mode == ModeNumber::STANCE; }); +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/ModeSequenceTemplate.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/ModeSequenceTemplate.cpp new file mode 100644 index 000000000..e62942b11 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/ModeSequenceTemplate.cpp @@ -0,0 +1,113 @@ +/****************************************************************************** +Copyright (c) 2017, Farbod Farshidian. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +******************************************************************************/ + +#include "ocs2_switched_model_interface/logic/ModeSequenceTemplate.h" + +#include +#include + +namespace switched_model { + +std::ostream& operator<<(std::ostream& stream, const ModeSequenceTemplate& modeSequenceTemplate) { + stream << "Template switching times: {" << ocs2::toDelimitedString(modeSequenceTemplate.switchingTimes) << "}\n"; + stream << "Template mode sequence: {" << ocs2::toDelimitedString(modeSequenceTemplate.modeSequence) << "}\n"; + return stream; +} + +ModeSequenceTemplate loadModeSequenceTemplate(const std::string& filename, const std::string& topicName, bool verbose) { + std::vector switchingTimes; + ocs2::loadData::loadStdVector(filename, topicName + ".switchingTimes", switchingTimes, verbose); + + std::vector modeSequenceString; + ocs2::loadData::loadStdVector(filename, topicName + ".modeSequence", modeSequenceString, verbose); + + if (switchingTimes.empty() || modeSequenceString.empty()) { + throw std::runtime_error("[loadModeSequenceTemplate] failed to load : " + topicName + " from " + filename); + } + + // convert the mode name to mode enum + std::vector modeSequence; + modeSequence.reserve(modeSequenceString.size()); + for (const auto& modeName : modeSequenceString) { + modeSequence.push_back(string2ModeNumber(modeName)); + } + + return {switchingTimes, modeSequence}; +} + +ocs2_msgs::mode_schedule createModeSequenceTemplateMsg(const ModeSequenceTemplate& modeSequenceTemplate) { + ocs2_msgs::mode_schedule modeScheduleMsg; + modeScheduleMsg.eventTimes.assign(modeSequenceTemplate.switchingTimes.begin(), modeSequenceTemplate.switchingTimes.end()); + modeScheduleMsg.modeSequence.assign(modeSequenceTemplate.modeSequence.begin(), modeSequenceTemplate.modeSequence.end()); + return modeScheduleMsg; +} + +ModeSequenceTemplate readModeSequenceTemplateMsg(const ocs2_msgs::mode_schedule& modeScheduleMsg) { + std::vector switchingTimes(modeScheduleMsg.eventTimes.begin(), modeScheduleMsg.eventTimes.end()); + std::vector modeSequence(modeScheduleMsg.modeSequence.begin(), modeScheduleMsg.modeSequence.end()); + return {switchingTimes, modeSequence}; +} + +Gait toGait(const ModeSequenceTemplate& modeSequenceTemplate) { + const auto startTime = modeSequenceTemplate.switchingTimes.front(); + const auto endTime = modeSequenceTemplate.switchingTimes.back(); + Gait gait; + gait.duration = endTime - startTime; + // Events: from time -> phase + gait.eventPhases.reserve(modeSequenceTemplate.switchingTimes.size()); + std::for_each(modeSequenceTemplate.switchingTimes.begin() + 1, modeSequenceTemplate.switchingTimes.end() - 1, + [&](scalar_t eventTime) { gait.eventPhases.push_back((eventTime - startTime) / gait.duration); }); + // Modes: + gait.modeSequence = modeSequenceTemplate.modeSequence; + assert(isValidGait(gait)); + return gait; +} + +ocs2::ModeSchedule loadModeSchedule(const std::string& filename, const std::string& topicName, bool verbose) { + std::vector eventTimes; + ocs2::loadData::loadStdVector(filename, topicName + ".eventTimes", eventTimes, verbose); + + std::vector modeSequenceString; + ocs2::loadData::loadStdVector(filename, topicName + ".modeSequence", modeSequenceString, verbose); + + if (modeSequenceString.empty()) { + throw std::runtime_error("[loadModeSchedule] failed to load : " + topicName + " from " + filename); + } + + // convert the mode name to mode enum + std::vector modeSequence; + modeSequence.reserve(modeSequenceString.size()); + for (const auto& modeName : modeSequenceString) { + modeSequence.push_back(string2ModeNumber(modeName)); + } + + return {eventTimes, modeSequence}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SingleLegLogic.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SingleLegLogic.cpp new file mode 100644 index 000000000..66a87008a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SingleLegLogic.cpp @@ -0,0 +1,93 @@ +// +// Created by rgrandia on 27.04.20. +// + +#include "ocs2_switched_model_interface/logic/SingleLegLogic.h" + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" + +namespace switched_model { + +feet_array_t> extractContactTimingsPerLeg(const ocs2::ModeSchedule& modeSchedule) { + feet_array_t> contactTimingsPerLeg; + + // Convert mode sequence to a contact flag vector per leg + const auto contactSequencePerLeg = extractContactFlags(modeSchedule.modeSequence); + + // Extract timings per leg + for (size_t leg = 0; leg < NUM_CONTACT_POINTS; ++leg) { + contactTimingsPerLeg[leg] = extractContactTimings(modeSchedule.eventTimes, contactSequencePerLeg[leg]); + } + + return contactTimingsPerLeg; +} + +scalar_t getTimeOfNextLiftOff(scalar_t currentTime, const std::vector& contactTimings) { + for (const auto& contactPhase : contactTimings) { + if (hasEndTime(contactPhase) && contactPhase.end > currentTime) { + return contactPhase.end; + } + } + return timingNaN(); +} + +scalar_t getTimeOfNextTouchDown(scalar_t currentTime, const std::vector& contactTimings) { + for (const auto& contactPhase : contactTimings) { + if (hasStartTime(contactPhase) && contactPhase.start > currentTime) { + return contactPhase.start; + } + } + return timingNaN(); +} + +std::vector extractContactTimings(const std::vector& eventTimes, const std::vector& contactFlags) { + assert(eventTimes.size() + 1 == contactFlags.size()); + const int numPhases = contactFlags.size(); + + std::vector contactTimings; + contactTimings.reserve(1 + eventTimes.size() / 2); // Approximate upper bound + int currentPhase = 0; + + while (currentPhase < numPhases) { + // Search where contact phase starts + while (currentPhase < numPhases && !contactFlags[currentPhase]) { + ++currentPhase; + } + if (currentPhase >= numPhases) { + break; // No more contact phases + } + + // Register start of the contact phase + const scalar_t startTime = (currentPhase == 0) ? std::numeric_limits::quiet_NaN() : eventTimes[currentPhase - 1]; + + // Find when the contact phase ends + while (currentPhase + 1 < numPhases && contactFlags[currentPhase + 1]) { + ++currentPhase; + } + + // Register end of the contact phase + const scalar_t endTime = (currentPhase + 1 >= numPhases) ? std::numeric_limits::quiet_NaN() : eventTimes[currentPhase]; + + // Add to phases + contactTimings.push_back({startTime, endTime}); + ++currentPhase; + } + return contactTimings; +} + +feet_array_t> extractContactFlags(const std::vector& modeSequence) { + const size_t numPhases = modeSequence.size(); + + feet_array_t> contactFlagStock; + std::fill(contactFlagStock.begin(), contactFlagStock.end(), std::vector(numPhases)); + + for (size_t i = 0; i < numPhases; i++) { + const auto contactFlag = modeNumber2StanceLeg(modeSequence[i]); + for (size_t j = 0; j < NUM_CONTACT_POINTS; j++) { + contactFlagStock[j][i] = contactFlag[j]; + } + } + return contactFlagStock; +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SwitchedModelModeScheduleManager.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SwitchedModelModeScheduleManager.cpp new file mode 100644 index 000000000..2cf927271 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/logic/SwitchedModelModeScheduleManager.cpp @@ -0,0 +1,40 @@ +// +// Created by rgrandia on 18.03.20. +// + +#include "ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h" + +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" + +namespace switched_model { + +SwitchedModelModeScheduleManager::SwitchedModelModeScheduleManager(std::unique_ptr gaitSchedule, + std::unique_ptr swingTrajectory, + std::unique_ptr terrainModel) + : gaitSchedule_(std::move(gaitSchedule)), swingTrajectoryPtr_(std::move(swingTrajectory)), terrainModel_(std::move(terrainModel)) {} + +contact_flag_t SwitchedModelModeScheduleManager::getContactFlags(scalar_t time) const { + return modeNumber2StanceLeg(this->getModeSchedule().modeAtTime(time)); +} + +void SwitchedModelModeScheduleManager::modifyReferences(scalar_t initTime, scalar_t finalTime, const vector_t& initState, + ocs2::TargetTrajectories& targetTrajectories, ocs2::ModeSchedule& modeSchedule) { + const auto timeHorizon = finalTime - initTime; + { + auto lockedGaitSchedulePtr = gaitSchedule_.lock(); + lockedGaitSchedulePtr->advanceToTime(initTime); + modeSchedule = lockedGaitSchedulePtr->getModeSchedule(timeHorizon + swingTrajectoryPtr_->settings().referenceExtensionAfterHorizon); + } + + // Transfer terrain ownership if a new terrain is available + std::unique_ptr newTerrain; + terrainModel_.swap(newTerrain); // Thread-safe swap with lockable Terrain + if (newTerrain) { + swingTrajectoryPtr_->updateTerrain(std::move(newTerrain)); + } + + // Prepare swing motions + swingTrajectoryPtr_->updateSwingMotions(initTime, finalTime, initState, targetTrajectories, modeSchedule); +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/ros_msg_conversions/RosMsgConversions.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/ros_msg_conversions/RosMsgConversions.cpp new file mode 100644 index 000000000..7f042be2b --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/ros_msg_conversions/RosMsgConversions.cpp @@ -0,0 +1,72 @@ +/* + * RosMsgConversions.h + * + * Created on: Jul 7, 2020 + * Author: Oliver Harley, Marko Bjelonic, Ruben Grandia + */ + +#include "ocs2_switched_model_interface/ros_msg_conversions/RosMsgConversions.h" + +namespace switched_model { +namespace ros_msg_conversions { + +ocs2_switched_model_msgs::gait toMessage(const Gait& gait) { + ocs2_switched_model_msgs::gait msg; + msg.duration = gait.duration; + msg.eventPhases.reserve(gait.eventPhases.size()); + for (const auto& phase : gait.eventPhases) { + msg.eventPhases.push_back(phase); + } + msg.modeSequence.reserve(gait.modeSequence.size()); + for (const auto& mode : gait.modeSequence) { + msg.modeSequence.push_back(mode); + } + return msg; +} + +Gait fromMessage(const ocs2_switched_model_msgs::gait& msg) { + Gait gait; + gait.duration = msg.duration; + gait.eventPhases.reserve(msg.eventPhases.size()); + for (const auto& phase : msg.eventPhases) { + gait.eventPhases.push_back(phase); + } + gait.modeSequence.reserve(msg.modeSequence.size()); + for (const auto& mode : msg.modeSequence) { + gait.modeSequence.push_back(mode); + } + assert(isValidGait(gait)); + return gait; +} + +ocs2_switched_model_msgs::gait_sequence toMessage(const GaitSchedule::GaitSequence& gaitSequence) { + ocs2_switched_model_msgs::gait_sequence msg; + msg.gaits.reserve(gaitSequence.size()); + for (const auto& gait : gaitSequence) { + msg.gaits.emplace_back(toMessage(gait)); + } + return msg; +} + +GaitSchedule::GaitSequence fromMessage(const ocs2_switched_model_msgs::gait_sequence& msg) { + GaitSchedule::GaitSequence gaitSequence; + gaitSequence.reserve(msg.gaits.size()); + for (const auto& gait : msg.gaits) { + gaitSequence.emplace_back(fromMessage(gait)); + } + return gaitSequence; +} + +ocs2_switched_model_msgs::scheduled_gait_sequence toMessage(scalar_t startTime, const GaitSchedule::GaitSequence& gaitSequence) { + ocs2_switched_model_msgs::scheduled_gait_sequence msg; + msg.startTime = startTime; + msg.gaitSequence = toMessage(gaitSequence); + return msg; +} + +std::pair fromMessage(const ocs2_switched_model_msgs::scheduled_gait_sequence& msg) { + return {msg.startTime, fromMessage(msg.gaitSequence)}; +} + +} // namespace ros_msg_conversions +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarSignedDistanceField.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarSignedDistanceField.cpp new file mode 100644 index 000000000..78dacaa8d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarSignedDistanceField.cpp @@ -0,0 +1,25 @@ +// +// Created by rgrandia on 08.09.22. +// + +#include "ocs2_switched_model_interface/terrain/PlanarSignedDistanceField.h" + +namespace switched_model { + +PlanarSignedDistanceField::PlanarSignedDistanceField(TerrainPlane terrainPlane) : terrainPlane_(std::move(terrainPlane)) {} + +PlanarSignedDistanceField::PlanarSignedDistanceField(const PlanarSignedDistanceField& other) : terrainPlane_(other.terrainPlane_) {} + +scalar_t PlanarSignedDistanceField::value(const vector3_t& position) const { + return terrainSignedDistanceFromPositionInWorld(position, terrainPlane_); +} + +vector3_t PlanarSignedDistanceField::derivative(const vector3_t& position) const { + return surfaceNormalInWorld(terrainPlane_); +} + +std::pair PlanarSignedDistanceField::valueAndDerivative(const vector3_t& position) const { + return {value(position), derivative(position)}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarTerrainModel.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarTerrainModel.cpp new file mode 100644 index 000000000..63eb69553 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlanarTerrainModel.cpp @@ -0,0 +1,37 @@ +// +// Created by rgrandia on 29.04.20. +// + +#include "ocs2_switched_model_interface/terrain/PlanarTerrainModel.h" + +namespace switched_model { + +PlanarTerrainModel::PlanarTerrainModel(TerrainPlane terrainPlane) : terrainPlane_(terrainPlane), sdf_(std::move(terrainPlane)) {} + +TerrainPlane PlanarTerrainModel::getLocalTerrainAtPositionInWorldAlongGravity( + const vector3_t& positionInWorld, std::function penaltyFunction) const { + // Project point to plane to find new center, orientation stays the same + return {projectPositionInWorldOntoPlaneAlongGravity(positionInWorld, terrainPlane_), terrainPlane_.orientationWorldToTerrain}; +} + +vector3_t PlanarTerrainModel::getHighestObstacleAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const { + // The highest point on a plane is at the end of the line + const auto projection1 = projectPositionInWorldOntoPlaneAlongGravity(position1InWorld, terrainPlane_); + const auto projection2 = projectPositionInWorldOntoPlaneAlongGravity(position2InWorld, terrainPlane_); + + if (projection1.z() > projection2.z()) { + return projection1; + } else { + return projection2; + } +} + +std::vector PlanarTerrainModel::getHeightProfileAlongLine(const vector3_t& position1InWorld, + const vector3_t& position2InWorld) const { + // Provide end points and one middle point as the height profile. + const auto projection1 = projectPositionInWorldOntoPlaneAlongGravity(position1InWorld, terrainPlane_); + const auto projection2 = projectPositionInWorldOntoPlaneAlongGravity(position2InWorld, terrainPlane_); + return {{0.0, projection1.z()}, {0.5, 0.5 * (projection1.z() + projection2.z())}, {1.0, projection2.z()}}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlaneFitting.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlaneFitting.cpp new file mode 100644 index 000000000..daca4399d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/PlaneFitting.cpp @@ -0,0 +1,44 @@ +// +// Created by rgrandia on 27.11.20. +// + +#include "ocs2_switched_model_interface/terrain/PlaneFitting.h" + +namespace switched_model { + +NormalAndPosition estimatePlane(const std::vector& regressionPoints) { + // Fit a plane that minimizes the normal distance to the provided regression points. Assumes at least 3 points are given. + assert(regressionPoints.size() >= 3); + + // Collect statistics of the points + size_t nPoints = 0; + vector3_t sum = vector3_t::Zero(); + matrix3_t sumSquared = matrix3_t::Zero(); + for (const auto& point : regressionPoints) { + nPoints++; + sum += point; + sumSquared.noalias() += point * point.transpose(); + } + const vector3_t mean = sum / nPoints; + const matrix3_t covarianceMatrix = sumSquared / nPoints - mean * mean.transpose(); + + // Compute Eigenvectors. + // Eigenvalues are ordered small to large. + // Worst case bound for zero eigenvalue from : https://eigen.tuxfamily.org/dox/classEigen_1_1SelfAdjointEigenSolver.html + constexpr double eigenValueZeroTolerance = 1e-8; + Eigen::SelfAdjointEigenSolver solver; + solver.computeDirect(covarianceMatrix, Eigen::DecompositionOptions::ComputeEigenvectors); + if (solver.eigenvalues()(1) > eigenValueZeroTolerance) { + vector3_t unitaryNormalVector = solver.eigenvectors().col(0); + + // Check direction of the normal vector and flip the sign upwards + if (unitaryNormalVector.z() < 0.0) { + unitaryNormalVector = -unitaryNormalVector; + } + return {unitaryNormalVector, mean}; + } else { // If second eigenvalue is zero, the normal is not defined. E.g. all points are on a line. + return {vector3_t::UnitZ(), mean}; + } +} + +} // namespace switched_model \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/TerrainPlane.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/TerrainPlane.cpp new file mode 100644 index 000000000..ef273211d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/terrain/TerrainPlane.cpp @@ -0,0 +1,41 @@ +// +// Created by rgrandia on 21.04.20. +// + +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +#include "ocs2_switched_model_interface/core/Rotations.h" + +#include + +namespace switched_model { + +TerrainPlane loadTerrainPlane(const std::string& filename, bool verbose) { + boost::property_tree::ptree pt; + boost::property_tree::read_info(filename, pt); + + if (verbose) { + std::cerr << "\n #### terrain plane:" << std::endl; + std::cerr << " #### ==================================================" << std::endl; + } + + TerrainPlane plane; + const std::string positionPrefix{"terrainPlane.position."}; + ocs2::loadData::loadPtreeValue(pt, plane.positionInWorld.x(), positionPrefix + "x", verbose); + ocs2::loadData::loadPtreeValue(pt, plane.positionInWorld.y(), positionPrefix + "y", verbose); + ocs2::loadData::loadPtreeValue(pt, plane.positionInWorld.z(), positionPrefix + "z", verbose); + + vector3_t eulerAnglesXYZ(0, 0, 0); + const std::string orientationprefix{"terrainPlane.orientation."}; + ocs2::loadData::loadPtreeValue(pt, eulerAnglesXYZ.x(), orientationprefix + "roll", verbose); + ocs2::loadData::loadPtreeValue(pt, eulerAnglesXYZ.y(), orientationprefix + "pitch", verbose); + ocs2::loadData::loadPtreeValue(pt, eulerAnglesXYZ.z(), orientationprefix + "yaw", verbose); + plane.orientationWorldToTerrain = rotationMatrixOriginToBase(eulerAnglesXYZ); + + if (verbose) { + std::cerr << " #### ==================================================" << std::endl; + } + return plane; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/testConstraints.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/testConstraints.cpp new file mode 100644 index 000000000..a9a92cba5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/src/testConstraints.cpp @@ -0,0 +1,41 @@ + + +#include + +int main(int argc, char** argv) { + using EndEffectorVelocityConstraint_t = switched_model::EndEffectorVelocityConstraint<3, 2>; + + // Set up constraint + switched_model::EndEffectorVelocityConstraintSettings settings; + EndEffectorVelocityConstraint_t EeVelconstraint(settings); + + // Set up (t, x, u, p) + EndEffectorVelocityConstraint_t::scalar_t time; + EndEffectorVelocityConstraint_t::state_vector_t state; + EndEffectorVelocityConstraint_t::input_vector_t input; + time = 0; + state.setOnes(); + input.setOnes(); + settings.desiredEndEffectorVelocity.setConstant(1.5); + + // Evaluate and print + auto constraints = EeVelconstraint.getValue(time, state, input); + auto linearApproximation = EeVelconstraint.getLinearApproximation(time, state, input); + + std::cout << "Constraint values" << std::endl; + for (auto& c : constraints) { + std::cout << c << std::endl; + } + + std::cout << "State Derivatives" << std::endl; + for (auto& dcdx : linearApproximation.derivativeState) { + std::cout << dcdx.transpose() << std::endl; + } + + std::cout << "Input Derivatives" << std::endl; + for (auto& dcdu : linearApproximation.derivativeInput) { + std::cout << dcdu.transpose() << std::endl; + } + + return 0; +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testFrictionConeConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testFrictionConeConstraint.cpp new file mode 100644 index 000000000..61d12e48c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testFrictionConeConstraint.cpp @@ -0,0 +1,113 @@ +// +// Created by rgrandia on 19.09.19. +// + +#include + +#include + +#include "ocs2_switched_model_interface/constraint/FrictionConeConstraint.h" +#include "ocs2_switched_model_interface/core/Rotations.h" + +using namespace switched_model; + +TEST(TestFrictionConeConstraint, finiteDifference) { + friction_cone::Config config; + config.hessianDiagonalShift = 0.0; // no Hessian adaptation in this test + + const scalar_t eps = 1e-4; + const scalar_t tol = 1e-9; + const int N = 10000; + + for (int i = 0; i < N; ++i) { + vector3_t forcesInTerrainFrame = 100.0 * vector3_t::Random(); + + const auto y0 = frictionConeConstraint(config, forcesInTerrainFrame); + auto quadraticApproximation = frictionConeLocalDerivatives(config, forcesInTerrainFrame); + + vector3_t dF = eps * vector3_t::Random(); + const auto y_eps = frictionConeConstraint(config, forcesInTerrainFrame + dF); + const auto y_quadmodel = quadraticApproximation.coneConstraint + quadraticApproximation.dCone_dF.dot(dF) + + 0.5 * dF.dot(quadraticApproximation.d2Cone_dF2 * dF); + + ASSERT_DOUBLE_EQ(y0, quadraticApproximation.coneConstraint); + ASSERT_LT(std::abs(y_eps - y_quadmodel), tol); + } +} + +TEST(TestFrictionConeConstraint, negativeDefinite) { + friction_cone::Config config; + + const scalar_t tol = 1e-12; + const int N = 10000; + + for (int i = 0; i < N; ++i) { + vector3_t forcesInTerrainFrame = 100.0 * vector3_t::Random(); + auto quadraticApproximation = frictionConeLocalDerivatives(config, forcesInTerrainFrame); + ASSERT_LT(ocs2::LinearAlgebra::symmetricEigenvalues(quadraticApproximation.d2Cone_dF2).maxCoeff(), tol); + } +} + +TEST(TestFrictionConeConstraint, finiteDifference_body_frame) { + friction_cone::Config config; + config.hessianDiagonalShift = 0.0; // no Hessian adaptation in this test + + const scalar_t eps = 1e-4; + const scalar_t tol = 1e-5; // Tolerance not very tight because of the Gauss-Newton approximation in the body->terrain nonlinearity + const int N = 10000; + + for (int i = 0; i < N; ++i) { + // Random forces, orientation, and terrain direction + const vector3_t forcesInBodyFrame = 100.0 * vector3_t::Random(); + const vector3_t eulerXYZ = vector3_t::Random(); + const matrix3_t t_R_w = rotationMatrixOriginToBase(vector3_t::Random()); + + // Compute additional inputs consistently + const matrix3_t w_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + const vector3_t forcesInTerrainFrame = t_R_w * w_R_b * forcesInBodyFrame; + + const auto y0 = frictionConeConstraint(config, forcesInTerrainFrame); + auto quadraticApproximation = frictionConeDerivatives(config, forcesInTerrainFrame, t_R_w, w_R_b, eulerXYZ, forcesInBodyFrame); + + // Perturb force in body and body orientation + vector3_t dF = eps * vector3_t::Random(); + vector3_t dEuler = eps * vector3_t::Random(); + + // Compute perturbed inputs consistently + const matrix3_t w_R_b_eps = rotationMatrixBaseToOrigin(eulerXYZ + dEuler); + const vector3_t forcesInTerrainFrame_eps = t_R_w * w_R_b_eps * (forcesInBodyFrame + dF); + + const auto y_eps = frictionConeConstraint(config, forcesInTerrainFrame_eps); + const auto y_quadmodel = quadraticApproximation.coneConstraint + quadraticApproximation.dCone_deuler.dot(dEuler) + + quadraticApproximation.dCone_du.dot(dF) + 0.5 * dEuler.dot(quadraticApproximation.d2Cone_deuler2 * dEuler) + + dF.dot(quadraticApproximation.d2Cone_dudeuler * dEuler) + 0.5 * dF.dot(quadraticApproximation.d2Cone_du2 * dF); + + ASSERT_DOUBLE_EQ(y0, quadraticApproximation.coneConstraint); + ASSERT_LT(std::abs(y_eps - y_quadmodel), tol); + } +} + +TEST(TestFrictionConeConstraint, negativeDefinite_body_frame) { + friction_cone::Config config; + + const scalar_t tol = 1e-12; + const int N = 10000; + + for (int i = 0; i < N; ++i) { + // Random forces, orientation, and terrain direction + const vector3_t forcesInBodyFrame = 100.0 * vector3_t::Random(); + const vector3_t eulerXYZ = vector3_t::Random(); + const matrix3_t t_R_w = rotationMatrixOriginToBase(vector3_t::Random()); + + // Compute additional inputs consistently + const matrix3_t w_R_b = rotationMatrixBaseToOrigin(eulerXYZ); + const vector3_t forcesInTerrainFrame = t_R_w * w_R_b * forcesInBodyFrame; + + auto quadraticApproximation = frictionConeDerivatives(config, forcesInTerrainFrame, t_R_w, w_R_b, eulerXYZ, forcesInBodyFrame); + + matrix_t hessian(6, 6); + hessian << quadraticApproximation.d2Cone_deuler2, quadraticApproximation.d2Cone_dudeuler.transpose(), + quadraticApproximation.d2Cone_dudeuler, quadraticApproximation.d2Cone_du2; + ASSERT_LT(ocs2::LinearAlgebra::symmetricEigenvalues(hessian).maxCoeff(), tol); + } +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testZeroForceConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testZeroForceConstraint.cpp new file mode 100644 index 000000000..eff9beb99 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/constraint/testZeroForceConstraint.cpp @@ -0,0 +1,36 @@ +// +// Created by rgrandia on 19.09.19. +// + +#include + +#include "ocs2_switched_model_interface/constraint/ZeroForceConstraint.h" +#include "ocs2_switched_model_interface/logic/SwitchedModelModeScheduleManager.h" +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/core/MotionPhaseDefinition.h" + +using namespace switched_model; + +TEST(TestZeroForceConstraint, evaluate) { + // Mock the modeScheduleManager + SwitchedModelModeScheduleManager modeScheduleManager(nullptr, nullptr, nullptr); + modeScheduleManager.setModeSchedule({{},{ModeNumber::FLY}}); + + // Mock the precomputation + SwitchedModelPreComputationMockup preComp; + + using TestedConstraint = ZeroForceConstraint; + TestedConstraint zeroForceConstraint(0, modeScheduleManager); + + // evaluation point + double t = 0.0; + input_vector_t u; + state_vector_t x; + u.setZero(); + x.setZero(); + + auto linearApproximation = zeroForceConstraint.getLinearApproximation(t, x, u, preComp); + std::cout << "h: " << linearApproximation.f.transpose() << std::endl; + std::cout << "dhdx: \n" << linearApproximation.dfdx << std::endl; + std::cout << "dhdu: \n" << linearApproximation.dfdu << std::endl; +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/core/testRotation.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/core/testRotation.cpp new file mode 100644 index 000000000..ef684e700 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/core/testRotation.cpp @@ -0,0 +1,92 @@ +// +// Created by rgrandia on 14.07.20. +// + +#include + +#include +#include + +#include "ocs2_switched_model_interface/core/Rotations.h" + +using namespace switched_model; + +template +Eigen::Matrix rotationMatrixBaseToOrigin_check(const Eigen::Matrix& eulerAnglesXYZ) { + // inputs are the intrinsic rotation angles in RADIANTS + SCALAR_T sinAlpha = sin(eulerAnglesXYZ(0)); + SCALAR_T cosAlpha = cos(eulerAnglesXYZ(0)); + SCALAR_T sinBeta = sin(eulerAnglesXYZ(1)); + SCALAR_T cosBeta = cos(eulerAnglesXYZ(1)); + SCALAR_T sinGamma = sin(eulerAnglesXYZ(2)); + SCALAR_T cosGamma = cos(eulerAnglesXYZ(2)); + + Eigen::Matrix Rx, Ry, Rz; + Rx << SCALAR_T(1), SCALAR_T(0), SCALAR_T(0), SCALAR_T(0), cosAlpha, -sinAlpha, SCALAR_T(0), sinAlpha, cosAlpha; + Ry << cosBeta, SCALAR_T(0), sinBeta, SCALAR_T(0), SCALAR_T(1), SCALAR_T(0), -sinBeta, SCALAR_T(0), cosBeta; + Rz << cosGamma, -sinGamma, SCALAR_T(0), sinGamma, cosGamma, SCALAR_T(0), SCALAR_T(0), SCALAR_T(0), SCALAR_T(1); + + return Rx * Ry * Rz; +} + +TEST(testRotations, rotationMatrix) { + for (int i = 0; i < 1000; i++) { + vector3_t eulerAngles = vector3_t::Random(); + + const auto o_R_b_check = rotationMatrixBaseToOrigin_check(eulerAngles); + const auto o_R_b = rotationMatrixBaseToOrigin(eulerAngles); + + ASSERT_NEAR((o_R_b_check - o_R_b).norm(), 0, 1e-12); + } +} + +TEST(testRotations, rotateVector) { + for (int i = 0; i < 1000; i++) { + const vector3_t eulerAngles = vector3_t::Random(); + const vector3_t vector = vector3_t::Random(); + + const vector3_t o_b_check = rotationMatrixBaseToOrigin_check(eulerAngles) * vector; + const vector3_t o_b_vector = rotateVectorBaseToOrigin(vector, eulerAngles); + ASSERT_NEAR((o_b_check - o_b_vector).norm(), 0, 1e-12); + + const vector3_t b_o_check = rotationMatrixBaseToOrigin_check(eulerAngles).transpose() * vector; + const vector3_t b_o_vector = rotateVectorOriginToBase(vector, eulerAngles); + ASSERT_NEAR((b_o_check - b_o_vector).norm(), 0, 1e-12); + } +} + +TEST(testRotations, rotationDerivative) { + using ad_vector_t = ocs2::CppAdInterface::ad_vector_t; + using ad_scalar_t = ocs2::CppAdInterface::ad_scalar_t; + + auto adFunction = [](const ad_vector_t& x, const ad_vector_t& p, ad_vector_t& y) { + vector3_ad_t eulerAngles = x.head<3>(); + vector3_ad_t v_base = p.head<3>(); + y = rotateVectorBaseToOrigin(v_base, eulerAngles); + }; + + ocs2::CppAdInterface adInterface(adFunction, 3, 3, "rotationDerivativeTest"); + adInterface.createModels(); + + for (int i = 0; i < 1000; i++) { + vector3_t eulerAngles = vector3_t::Random(); + vector3_t v_base = vector3_t::Random(); + + matrix3_t jacManual = rotationBaseToOriginJacobian(eulerAngles, v_base); + Eigen::MatrixXd jacAuto = adInterface.getJacobian(eulerAngles, v_base); + ASSERT_NEAR((jacManual - jacAuto).array().abs().sum(), 0, 1e-12); + } + + ASSERT_TRUE(true); +} + +TEST(testRotations, eulerRates) { + for (int i = 0; i < 1000; i++) { + const vector3_t eulerAngles = vector3_t::Random(); + const vector3_t angularVelocityInBase = vector3_t::Random(); + + const vector3_t eulerRate_check = angularVelocitiesToEulerAngleDerivativesMatrix(eulerAngles) * angularVelocityInBase; + const vector3_t eulerRate = angularVelocitiesToEulerAngleDerivatives(angularVelocityInBase, eulerAngles); + ASSERT_NEAR((eulerRate_check - eulerRate).norm(), 0, 1e-12); + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFootplacementCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFootplacementCost.cpp new file mode 100644 index 000000000..44924df13 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFootplacementCost.cpp @@ -0,0 +1,48 @@ +// +// Created by rgrandia on 27.06.20. +// + +#include + +#include "ocs2_switched_model_interface/foot_planner/FootPhase.h" + +using namespace switched_model; + +std::vector createRegularPolygon(const vector2_t& center, double radius, int numberOfVertices) { + assert(numberOfVertices > 2); + std::vector polygon; + double angle = (2. * M_PI) / numberOfVertices; + for (int i = 0; i < numberOfVertices; ++i) { + double phi = i * angle; + double px = radius * std::cos(phi) + center.x(); + double py = radius * std::sin(phi) + center.y(); + // Counter clockwise + polygon.emplace_back(px, py); + } + return polygon; +} + +TEST(TestFootplacementCost, constraintConversion) { + const vector2_t center{1.0, 2.0}; + const scalar_t margin = 0.0; + + ConvexTerrain convexTerrain; + convexTerrain.plane.positionInWorld = vector3_t{center.x(), center.y(), 3.0}; + convexTerrain.plane.orientationWorldToTerrain.setIdentity(); + + const auto emptyConstraints = tangentialConstraintsFromConvexTerrain(convexTerrain, margin); + ASSERT_EQ(emptyConstraints.A.rows(), 0); + ASSERT_EQ(emptyConstraints.b.size(), 0); + + const int numVertices = 16; + double radius = 1.0; + convexTerrain.boundary = createRegularPolygon({0.0, 0.0}, 1.0, numVertices); + const auto linConstraints = tangentialConstraintsFromConvexTerrain(convexTerrain, margin); + ASSERT_EQ(linConstraints.A.rows(), numVertices); + ASSERT_EQ(linConstraints.b.size(), numVertices); + + vector_t h = linConstraints.A * convexTerrain.plane.positionInWorld + linConstraints.b; + vector_t h2 = linConstraints.A * vector3_t{center.x() + 0.99 * radius, center.y(), 0.0} + linConstraints.b; + ASSERT_GT(h.minCoeff(), 0.0); + ASSERT_GT(h2.minCoeff(), 0.0); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFrictionConeCost.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFrictionConeCost.cpp new file mode 100644 index 000000000..0149d21a8 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testFrictionConeCost.cpp @@ -0,0 +1,89 @@ +// +// Created by rgrandia on 27.06.20. +// + +#include + +#include "ocs2_switched_model_interface/core/SwitchedModelPrecomputation.h" +#include "ocs2_switched_model_interface/cost/FrictionConeCost.h" + +#include +#include + +using namespace switched_model; + +TEST(TestFrictionConeCost, evaluate) { + // Mock the modeScheduleManager + SwitchedModelModeScheduleManager modeScheduleManager(nullptr, nullptr, nullptr); + modeScheduleManager.setModeSchedule({{}, {ModeNumber::STANCE}}); + + // Mock the precomputation + SwitchedModelPreComputationMockup preComp; + + // evaluation point + scalar_t t = 0.0; + comkino_state_t x = switched_model::comkino_state_t::Random(); + comkino_input_t u = switched_model::comkino_input_t::Random(); + ocs2::TargetTrajectories targetTrajectories({t}, {x}, {u}); + + std::unique_ptr penalty(new ocs2::RelaxedBarrierPenalty({0.1, 5.0})); + FrictionConeCost frictionConeCost(friction_cone::Config(), modeScheduleManager, std::move(penalty)); + + for (int i = 0; i < NUM_CONTACT_POINTS; ++i) { + preComp.surfaceNormalInOriginFrame(i) = vector3_t::Random(); + preComp.surfaceNormalInOriginFrame(i).normalize(); + } + + const auto cost = frictionConeCost.getValue(t, x, u, targetTrajectories, preComp); + const auto costApproximation = frictionConeCost.getQuadraticApproximation(t, x, u, targetTrajectories, preComp); + + scalar_t tol = 1e-12; + EXPECT_DOUBLE_EQ(cost, costApproximation.f); + ASSERT_GT(ocs2::LinearAlgebra::symmetricEigenvalues(costApproximation.dfduu).minCoeff(), -tol); + ASSERT_GT(ocs2::LinearAlgebra::symmetricEigenvalues(costApproximation.dfdxx).minCoeff(), -tol); +} + +TEST(TestFrictionConeCost, finiteDifference) { + // Mock the modeScheduleManager + SwitchedModelModeScheduleManager modeScheduleManager(nullptr, nullptr, nullptr); + modeScheduleManager.setModeSchedule({{}, {ModeNumber::STANCE}}); + + // Mock the precomputation + SwitchedModelPreComputationMockup preComp; + + // evaluation point + scalar_t t = 0.0; + comkino_state_t x = switched_model::comkino_state_t::Random(); + comkino_input_t u = switched_model::comkino_input_t::Random(); + ocs2::TargetTrajectories targetTrajectories({t}, {x}, {u}); + + std::unique_ptr penalty(new ocs2::RelaxedBarrierPenalty({0.1, 5.0})); + FrictionConeCost frictionConeCost(friction_cone::Config(), modeScheduleManager, std::move(penalty)); + + const scalar_t eps = 1e-4; + const scalar_t tol = 1e-5; + const int N = 10000; + for (int i = 0; i < N; ++i) { + comkino_state_t x = switched_model::comkino_state_t::Random(); + comkino_input_t u = switched_model::comkino_input_t::Random(); + + comkino_state_t dx = eps * switched_model::comkino_state_t::Random(); + comkino_input_t du = eps * switched_model::comkino_input_t::Random(); + + for (int leg = 0; leg< NUM_CONTACT_POINTS; ++leg) { + preComp.surfaceNormalInOriginFrame(leg) = vector3_t::Random(); + preComp.surfaceNormalInOriginFrame(leg).normalize(); + } + + const auto cost = frictionConeCost.getValue(t, x, u, targetTrajectories, preComp); + const auto costApproximation = frictionConeCost.getQuadraticApproximation(t, x, u, targetTrajectories, preComp); + + const auto cost_eps = frictionConeCost.getValue(t, x + dx, u + du, targetTrajectories, preComp); + const auto cost_quadmodel = costApproximation.f + costApproximation.dfdx.dot(dx) + costApproximation.dfdu.dot(du) + + 0.5 * dx.dot(costApproximation.dfdxx * dx) + 0.5 * du.dot(costApproximation.dfduu * du) + + du.dot(costApproximation.dfdux * dx); + + EXPECT_DOUBLE_EQ(cost, costApproximation.f); + ASSERT_LT(std::abs(cost_eps - cost_quadmodel), tol); + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testTorqueLimitsSoftConstraint.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testTorqueLimitsSoftConstraint.cpp new file mode 100644 index 000000000..49dbbc056 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/cost/testTorqueLimitsSoftConstraint.cpp @@ -0,0 +1,71 @@ +// +// Created by rgrandia on 26.07.21. +// + +#include + +#include "ocs2_switched_model_interface/cost/TorqueLimitsSoftConstraint.h" + +using namespace switched_model; + +TEST(TestTorqueLimits, quadraticApproximation) { + joint_coordinate_t torqueLimits = joint_coordinate_t::Constant(80.0); + joint_coordinate_t nominalTorque = joint_coordinate_t::Constant(10.0); + const scalar_t mu = 0.1; + const scalar_t delta = 0.05; + + TorqueLimitsSoftConstraint torqueLimitsSoftConstraint(torqueLimits, {mu, delta}, nominalTorque); + + joint_coordinate_t middleTorque = joint_coordinate_t::Zero(); + ocs2::VectorFunctionLinearApproximation torqueDerivatives = VectorFunctionLinearApproximation::Zero(JOINT_COORDINATE_SIZE, STATE_DIM, INPUT_DIM); + // some random values per joint (with the correct sparsity) + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg){ + const int torqueStartIndex = 3 * leg; + const int forceStartIndex = 3 * leg; + const int jointStartStateIndex = 2 * BASE_COORDINATE_SIZE + 3 * leg; + + torqueDerivatives.dfdx.block<3, 3>(torqueStartIndex, jointStartStateIndex).setRandom(); + torqueDerivatives.dfdu.block<3, 3>(torqueStartIndex, forceStartIndex).setRandom(); + } + + auto value = torqueLimitsSoftConstraint.getValue(middleTorque); + auto quadApprox = torqueLimitsSoftConstraint.getQuadraticApproximation(torqueDerivatives); + + // Gradient is zero in middle of limits + ASSERT_DOUBLE_EQ(quadApprox.dfdx.norm(), 0.0); + ASSERT_DOUBLE_EQ(quadApprox.dfdu.norm(), 0.0); + + // Value is consistent + ASSERT_DOUBLE_EQ(quadApprox.f, value); +} + +TEST(TestTorqueLimits, infiniteLimits) { + joint_coordinate_t torqueLimits = joint_coordinate_t::Constant(1e30); + joint_coordinate_t nominalTorque = joint_coordinate_t::Constant(10.0); + const scalar_t mu = 0.1; + const scalar_t delta = 0.05; + + TorqueLimitsSoftConstraint torqueLimitsSoftConstraint(torqueLimits, {mu, delta}, nominalTorque); + + joint_coordinate_t middleTorque = joint_coordinate_t::Zero(); + ocs2::VectorFunctionLinearApproximation torqueDerivatives = VectorFunctionLinearApproximation::Zero(JOINT_COORDINATE_SIZE, STATE_DIM, INPUT_DIM); + // some random values per joint (with the correct sparsity) + for (int leg = 0; leg < NUM_CONTACT_POINTS; ++leg){ + const int torqueStartIndex = 3 * leg; + const int forceStartIndex = 3 * leg; + const int jointStartStateIndex = 2 * BASE_COORDINATE_SIZE + 3 * leg; + + torqueDerivatives.dfdx.block<3, 3>(torqueStartIndex, jointStartStateIndex).setRandom(); + torqueDerivatives.dfdu.block<3, 3>(torqueStartIndex, forceStartIndex).setRandom(); + } + + + auto quadApprox = torqueLimitsSoftConstraint.getQuadraticApproximation(torqueDerivatives); + + // Gradient and curvature are both almost zero + ASSERT_LT(quadApprox.dfdx.norm(), 1e-30); + ASSERT_LT(quadApprox.dfdu.norm(), 1e-30); + ASSERT_LT(quadApprox.dfdxx.norm(), 1e-30); + ASSERT_LT(quadApprox.dfdux.norm(), 1e-30); + ASSERT_LT(quadApprox.dfduu.norm(), 1e-30); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/foot_planner/testSwingPhase.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/foot_planner/testSwingPhase.cpp new file mode 100644 index 000000000..6a1336cdd --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/foot_planner/testSwingPhase.cpp @@ -0,0 +1,85 @@ +// +// Created by rgrandia on 06.05.20. +// + +#include + +#include "ocs2_switched_model_interface/foot_planner/FootPhase.h" + +using namespace switched_model; + +TEST(TestQuinticSwing, interpolating) { + SwingNode start{0.5, 0.1, 0.2}; + SwingNode mid{0.75, 0.2, -0.3}; + SwingNode end{1.0, -0.4, 0.4}; + QuinticSwing quinticSwing(start, mid, end); + + double tol = 1e-9; + double eps = std::numeric_limits::epsilon(); + EXPECT_LT(std::abs(quinticSwing.position(start.time) - start.position), tol); + EXPECT_LT(std::abs(quinticSwing.velocity(start.time) - start.velocity), tol); + EXPECT_LT(std::abs(quinticSwing.position(mid.time) - mid.position), tol); + EXPECT_LT(std::abs(quinticSwing.velocity(mid.time) - mid.velocity), tol); + EXPECT_LT(std::abs(quinticSwing.position(end.time) - end.position), tol); + EXPECT_LT(std::abs(quinticSwing.velocity(end.time) - end.velocity), tol); + + // Start-end acceleration + EXPECT_LT(std::abs(quinticSwing.acceleration(start.time)), tol); + EXPECT_LT(std::abs(quinticSwing.acceleration(end.time)), tol); + + // Continuity + EXPECT_LT(std::abs(quinticSwing.acceleration(mid.time + eps) - quinticSwing.acceleration(mid.time - eps)), tol); + EXPECT_LT(std::abs(quinticSwing.jerk(mid.time + eps) - quinticSwing.jerk(mid.time - eps)), tol); +} + +TEST(TestQuinticSwing, multipleNodes) { + // Set some random nodes to interpolate + std::vector nodes = {{0.5, 0.1, 0.2}}; + for (int i = 1; i < 10; ++i) { + nodes.push_back({nodes.back().time + i * 0.1, (i - 5) * 0.1, (i - 3) * 0.4}); + } + QuinticSwing quinticSwing(nodes); + + double tol = 1e-9; + double eps = std::numeric_limits::epsilon(); + for (const auto& node : nodes) { + // interpolation + EXPECT_LT(std::abs(quinticSwing.position(node.time) - node.position), tol); + EXPECT_LT(std::abs(quinticSwing.velocity(node.time) - node.velocity), tol); + + // Get pre and post node time (and clamp to interval) + const scalar_t minTime = std::max(node.time - eps, nodes.front().time); + const scalar_t plusTime = std::min(node.time + eps, nodes.back().time); + // Continuity + EXPECT_LT(std::abs(quinticSwing.acceleration(plusTime) - quinticSwing.acceleration(minTime)), tol); + EXPECT_LT(std::abs(quinticSwing.jerk(plusTime) - quinticSwing.jerk(minTime)), tol); + } + + // Start-end acceleration + EXPECT_LT(std::abs(quinticSwing.acceleration(nodes.front().time)), tol); + EXPECT_LT(std::abs(quinticSwing.acceleration(nodes.back().time)), tol); +} + +TEST(TestQuinticSwing3d, interpolating) { + SwingNode3d start{0.5, vector3_t::Random(), vector3_t::Random()}; + SwingNode3d mid{0.75, vector3_t::Random(), vector3_t::Random()}; + SwingNode3d end{1.0, vector3_t::Random(), vector3_t::Random()}; + SwingSpline3d swingNode3D(start, mid, end); + + double tol = 1e-9; + double eps = std::numeric_limits::epsilon(); + EXPECT_LT((swingNode3D.position(start.time) - start.position).norm(), tol); + EXPECT_LT((swingNode3D.velocity(start.time) - start.velocity).norm(), tol); + EXPECT_LT((swingNode3D.position(mid.time) - mid.position).norm(), tol); + EXPECT_LT((swingNode3D.velocity(mid.time) - mid.velocity).norm(), tol); + EXPECT_LT((swingNode3D.position(end.time) - end.position).norm(), tol); + EXPECT_LT((swingNode3D.velocity(end.time) - end.velocity).norm(), tol); + + // Start-end acceleration + EXPECT_LT(swingNode3D.acceleration(start.time).norm(), tol); + EXPECT_LT(swingNode3D.acceleration(end.time).norm(), tol); + + // Continuity + EXPECT_LT((swingNode3D.acceleration(mid.time + eps) - swingNode3D.acceleration(mid.time - eps)).norm(), tol); + EXPECT_LT((swingNode3D.jerk(mid.time + eps) - swingNode3D.jerk(mid.time - eps)).norm(), tol); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testEarlyTouchDown.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testEarlyTouchDown.cpp new file mode 100644 index 000000000..6070ac855 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testEarlyTouchDown.cpp @@ -0,0 +1,93 @@ +/* + * testEarlyTouchDown.cpp + * + * Created on: Jun 4, 2020 + * Author: Marko Bjelonic + */ + +// gtest +#include + +// ocs2 switched model interface +#include +#include +#include + +using namespace switched_model; + +TEST(testEarlyTouchDown, testTrot) { + // Generate gait schedule. + Gait gait; + gait.duration = 0.8; + gait.eventPhases = {0.45, 0.5, 0.95}; + gait.modeSequence = {ModeNumber::LF_RH, ModeNumber::STANCE, ModeNumber::RF_LH, ModeNumber::STANCE}; + GaitSchedule gaitSchedule(0.0, gait); + gaitSchedule.setGaitAfterTime(gait, gaitSchedule.getCurrentTime() + 0.99 * gait.duration); + + // Early touch down gait adaptation RF and LH should be in touch down. + feet_array_t earlyTouchDownPerLeg{true, true, true, true}; + auto earlyTouchDownGaitAdaptor = earlyTouchDownAdaptation(earlyTouchDownPerLeg); + gaitSchedule.adaptCurrentGait(earlyTouchDownGaitAdaptor); + + // Check. + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[2] == ModeNumber::RF_LH); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[3] == ModeNumber::STANCE); + + // Early touch down gait adaptation LF and RH should be in touch down. + gaitSchedule.advanceToTime(gait.duration * gait.eventPhases[1]); + gaitSchedule.adaptCurrentGait(earlyTouchDownGaitAdaptor); + + // Check. + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[2] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[3] == ModeNumber::STANCE); + + // Check that the next gait was not adapted. + gaitSchedule.advanceToTime(gait.duration); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::LF_RH); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[2] == ModeNumber::RF_LH); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[3] == ModeNumber::STANCE); +} + +TEST(testEarlyTouchDown, testOverhangingSwingPhases) { + // Generate gait schedule. + Gait gait; + gait.duration = 1.0; + gait.eventPhases = {0.5}; + gait.modeSequence = {ModeNumber::RF_LH_RH, ModeNumber::LH_RH}; + GaitSchedule gaitSchedule(0.0, gait); + Gait nextGait; + nextGait.duration = 0.5; + nextGait.eventPhases = {0.5}; + nextGait.modeSequence = {ModeNumber::LH_RH, ModeNumber::LF_LH_RH}; + gaitSchedule.setGaitAfterTime(nextGait, gaitSchedule.getCurrentTime() + 0.99 * gait.duration); + + // Early touch down gait adaptation LF should be in touch down. + feet_array_t earlyTouchDownPerLeg{true, true, false, false}; + auto earlyTouchDownGaitAdaptor = earlyTouchDownAdaptation(earlyTouchDownPerLeg); + gaitSchedule.adaptCurrentGait(earlyTouchDownGaitAdaptor); + + // Check. + const auto modeSchedule = gaitSchedule.getModeSchedule(gait.duration + nextGait.duration); + ASSERT_TRUE(modeSchedule.modeSequence[0] == ModeNumber::STANCE); + ASSERT_TRUE(modeSchedule.modeSequence[1] == ModeNumber::LF_LH_RH); + ASSERT_EQ(modeSchedule.modeSequence.size(), 2); + + // Early touch down gait adaptation RF should be in touch down. + gaitSchedule.advanceToTime(gait.eventPhases[0] * gait.duration); + gaitSchedule.adaptCurrentGait(earlyTouchDownGaitAdaptor); + + // Check. + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::STANCE); + gaitSchedule.advanceToTime(gait.duration); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::STANCE); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::STANCE); + gaitSchedule.advanceToTime(gait.duration + nextGait.duration); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[0] == ModeNumber::LH_RH); + ASSERT_TRUE(gaitSchedule.getCurrentGait().modeSequence[1] == ModeNumber::LF_LH_RH); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testExtractContractTimings.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testExtractContractTimings.cpp new file mode 100644 index 000000000..b264fc922 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testExtractContractTimings.cpp @@ -0,0 +1,90 @@ +// +// Created by rgrandia on 17.03.20. +// + +#include + +#include "ocs2_switched_model_interface/logic/SingleLegLogic.h" + +using namespace switched_model; + +TEST(TestFootPlanner, extractPhases_SinglePhase) { + std::vector eventTimes = {}; + std::vector contactFlags; + + // Single stance phase + contactFlags = {true}; + auto contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_TRUE(std::isnan(contactPhases.front().start)); + ASSERT_TRUE(std::isnan(contactPhases.front().end)); + + // Single swing phase + contactFlags = {false}; + contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_TRUE(contactPhases.empty()); +} + +TEST(TestFootPlanner, extractPhases_MergePhases) { + std::vector eventTimes = {0.5}; + std::vector contactFlags; + + // Single stance phase + contactFlags = {true, true}; + auto contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_TRUE(std::isnan(contactPhases.front().start)); + ASSERT_TRUE(std::isnan(contactPhases.front().end)); + + // Single swing phase + contactFlags = {false, false}; + contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_TRUE(contactPhases.empty()); +} + +TEST(TestFootPlanner, extractPhases_singleSwitch) { + std::vector eventTimes; + std::vector contactFlags; + + // Switched phase + eventTimes = {0.5}; + contactFlags = {false, true}; + auto contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_EQ(contactPhases.size(), 1); + ASSERT_DOUBLE_EQ(contactPhases.front().start, eventTimes.front()); + ASSERT_TRUE(std::isnan(contactPhases.front().end)); + + // change switching direction + contactFlags = {true, false}; + contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_EQ(contactPhases.size(), 1); + ASSERT_TRUE(std::isnan(contactPhases.front().start)); + ASSERT_DOUBLE_EQ(contactPhases.front().end, eventTimes.front()); +} + +TEST(TestFootPlanner, extractPhases_multiSwitch_startContact) { + std::vector eventTimes; + std::vector contactFlags; + + eventTimes = {1.0, 2.0, 3.0, 4.0}; + contactFlags = {true, true, false, false, true}; + auto contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_EQ(contactPhases.size(), 2); + // contact phase 1 + ASSERT_TRUE(std::isnan(contactPhases[0].start)); + ASSERT_DOUBLE_EQ(contactPhases[0].end, eventTimes[1]); + // contact phase 2 + ASSERT_DOUBLE_EQ(contactPhases[1].start, eventTimes[3]); + ASSERT_TRUE(std::isnan(contactPhases[1].end)); +} + +TEST(TestFootPlanner, extractPhases_multiSwitch_startSwing) { + std::vector eventTimes; + std::vector contactFlags; + + eventTimes = {1.0, 2.0, 3.0, 4.0}; + contactFlags = {false, false, true, true, false}; + auto contactPhases = extractContactTimings(eventTimes, contactFlags); + ASSERT_EQ(contactPhases.size(), 1); + // contact phase 1 + ASSERT_DOUBLE_EQ(contactPhases[0].start, eventTimes[1]); + ASSERT_DOUBLE_EQ(contactPhases[0].end, eventTimes[3]); +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGait.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGait.cpp new file mode 100644 index 000000000..899960557 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGait.cpp @@ -0,0 +1,96 @@ +// +// Created by rgrandia on 15.03.20. +// + +#include + +#include "ocs2_switched_model_interface/logic/Gait.h" + +using namespace switched_model; + +const Gait singleModeGait = [] { + Gait gait; + gait.duration = 0.8; + gait.eventPhases = {}; + gait.modeSequence = {1}; + return gait; +}(); + +const Gait multiModeGait = [] { + Gait gait; + gait.duration = 0.6; + gait.eventPhases = {0.33, 0.66}; + gait.modeSequence = {0, 1, 2}; + return gait; +}(); + +TEST(TestGait, validGait) { + ASSERT_TRUE(isValidGait(singleModeGait)); + ASSERT_TRUE(isValidGait(multiModeGait)); + + // Negative duration + ASSERT_FALSE(isValidGait({-0.1, {}, {0}})); + // Event <= 0 + ASSERT_FALSE(isValidGait({0.1, {-0.1}, {0, 1}})); + ASSERT_FALSE(isValidGait({0.1, {0}, {0, 1}})); + // Event >= 1 + ASSERT_FALSE(isValidGait({0.1, {1}, {0, 1}})); + ASSERT_FALSE(isValidGait({0.1, {1.1}, {0, 1}})); + // Events not sorted + ASSERT_FALSE(isValidGait({0.1, {0.6, 0.3}, {0, 1, 2}})); + // Wrong number of mode + ASSERT_FALSE(isValidGait({0.1, {}, {}})); + ASSERT_FALSE(isValidGait({0.1, {0.1, 0.2}, {0}})); +} + +TEST(TestPhase, isValidPhase) { + ASSERT_FALSE(isValidPhase(-std::numeric_limits::epsilon())); + ASSERT_TRUE(isValidPhase(0.0)); + ASSERT_TRUE(isValidPhase(0.5)); + ASSERT_TRUE(isValidPhase(1.0 - std::numeric_limits::epsilon())); + ASSERT_FALSE(isValidPhase(1.0)); + ASSERT_FALSE(isValidPhase(1.0 + std::numeric_limits::epsilon())); +} + +TEST(TestPhaseWrap, wrapPhase) { + // Wrap around edges + ASSERT_DOUBLE_EQ(wrapPhase(0.0), 0.0); + ASSERT_DOUBLE_EQ(wrapPhase(1.0), 0.0); + ASSERT_DOUBLE_EQ(wrapPhase(1.0 - std::numeric_limits::epsilon()), 1.0 - std::numeric_limits::epsilon()); + ASSERT_DOUBLE_EQ(wrapPhase(1.0), 0.0); + ASSERT_DOUBLE_EQ(wrapPhase(1.0 + std::numeric_limits::epsilon()), std::numeric_limits::epsilon()); + ASSERT_DOUBLE_EQ(wrapPhase(1.8), 0.8); + ASSERT_DOUBLE_EQ(wrapPhase(-0.2), 0.8); +} + +TEST(TestSingleModeGait, getModeFromPhase) { + ASSERT_EQ(getModeFromPhase(0.0, singleModeGait), 1); + ASSERT_EQ(getModeFromPhase(0.33, singleModeGait), 1); + ASSERT_EQ(getModeFromPhase(1.0 - std::numeric_limits::epsilon(), singleModeGait), 1); +} + +TEST(TestMultiModeGait, getModeFromPhase) { + ASSERT_EQ(getModeFromPhase(0.0, multiModeGait), 0); + ASSERT_EQ(getModeFromPhase(0.1, multiModeGait), 0); + ASSERT_EQ(getModeFromPhase(0.33, multiModeGait), 1); + ASSERT_EQ(getModeFromPhase(0.42, multiModeGait), 1); + ASSERT_EQ(getModeFromPhase(0.66, multiModeGait), 2); + ASSERT_EQ(getModeFromPhase(1.0 - std::numeric_limits::epsilon(), multiModeGait), 2); +} + +TEST(TestMultiModeGait, timeLeft) { + ASSERT_DOUBLE_EQ(timeLeftInMode(0.0, multiModeGait), 0.33 * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(0.1, multiModeGait), (0.33 - 0.1) * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(0.33 - std::numeric_limits::epsilon(), multiModeGait), + std::numeric_limits::epsilon() * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(0.33, multiModeGait), (0.66 - 0.33) * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(0.42, multiModeGait), (0.66 - 0.42) * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(0.66, multiModeGait), (1.0 - 0.66) * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInMode(1.0 - std::numeric_limits::epsilon(), multiModeGait), + std::numeric_limits::epsilon() * multiModeGait.duration); + + ASSERT_DOUBLE_EQ(timeLeftInGait(0.0, multiModeGait), 1.0 * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInGait(0.5, multiModeGait), 0.5 * multiModeGait.duration); + ASSERT_DOUBLE_EQ(timeLeftInGait(1.0 - std::numeric_limits::epsilon(), multiModeGait), + std::numeric_limits::epsilon() * multiModeGait.duration); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSchedule.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSchedule.cpp new file mode 100644 index 000000000..cfe64756d --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSchedule.cpp @@ -0,0 +1,171 @@ +// +// Created by rgrandia on 15.03.20. +// + +#include + +#include "ocs2_switched_model_interface/logic/GaitSchedule.h" +#include "ocs2_switched_model_interface/logic/GaitSwitching.h" + +using namespace switched_model; + +TEST(TestGaitSchedule, advanceSingleGait) { + const double t0 = 11.0; + GaitSchedule gaitSchedule(t0, {1.0, {}, {42}}); + ASSERT_EQ(gaitSchedule.getCurrentMode(), 42); + ASSERT_DOUBLE_EQ(gaitSchedule.getCurrentPhase(), 0.0); + + gaitSchedule.advanceToTime(t0 + 100.0); + ASSERT_EQ(gaitSchedule.getCurrentMode(), 42); + + gaitSchedule.advanceToTime(t0 + 110.0); + ASSERT_EQ(gaitSchedule.getCurrentMode(), 42); +} + +TEST(TestGaitSchedule, advanceTwoGaits) { + const double t0 = 11.0; + GaitSchedule gaitSchedule(t0, {1.0, {}, {42}}); + gaitSchedule.setNextGait({1.0, {}, {21}}); + + ASSERT_EQ(gaitSchedule.getCurrentMode(), 42); + + gaitSchedule.advanceToTime(t0 + 0.5); + ASSERT_EQ(gaitSchedule.getCurrentMode(), 42); + + gaitSchedule.advanceToTime(t0 + 1.0); + ASSERT_EQ(gaitSchedule.getCurrentMode(), 21); +} + +TEST(TestGaitSchedule, setNextGaitSchedule) { + const double t0 = 11.0; + const double timeHorizon = 5.0; + const std::deque gaitSequence = {Gait{1.0, {}, {42}}, Gait{1.0, {}, {21}}, Gait{0.5, {0.66}, {0, 1}}}; + + // Add the gait schedule in two parts + GaitSchedule gaitSchedule(t0, gaitSequence[0]); + gaitSchedule.setGaitSequenceAfterCurrentGait({gaitSequence[1], gaitSequence[2]}); + + // Check that the resulting mode schedule is equal + auto checkModeSchedule = getModeSchedule(gaitSchedule.getCurrentPhase(), t0, timeHorizon, gaitSequence.begin(), gaitSequence.end()); + auto modeSchedule = gaitSchedule.getModeSchedule(timeHorizon); + ASSERT_EQ(modeSchedule.eventTimes, checkModeSchedule.eventTimes); + ASSERT_EQ(modeSchedule.modeSequence, checkModeSchedule.modeSequence); +} + +TEST(TestGaitSchedule, setGaitScheduleAtTime) { + const double t0 = 1.0; + const double tInsert = 9.5; + + // Start with multi mode gait + GaitSchedule gaitSchedule(t0, Gait{1.0, {0.5}, {0, 1}}); + + // Set a new gait way pass the end of the current schedule + gaitSchedule.setGaitAtTime(Gait{1.5, {}, {21}}, tInsert); + auto modeSchedule = gaitSchedule.getModeSchedule((tInsert - t0) + 1.5); + + // Last gait was shrunk in duration + ASSERT_DOUBLE_EQ(*(modeSchedule.eventTimes.end() - 2), tInsert - 0.25); + ASSERT_DOUBLE_EQ(*(modeSchedule.eventTimes.end() - 3), tInsert - 0.5); + + // New gait inserted at the correct time + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes.back(), tInsert); + ASSERT_EQ(modeSchedule.modeSequence.back(), 21); +} + +TEST(TestGaitSchedule, setGaitScheduleAtTime_twice_current_gait) { + const double t0 = 1.0; + const double tGaitDuration = 1.0; + const double tInsert = t0 + 2.0 * tGaitDuration; + + // Start with multi mode gait + GaitSchedule gaitSchedule(t0, Gait{tGaitDuration, {0.5}, {0, 1}}); + + // Set a new gait at twice the current gait + gaitSchedule.setGaitAtTime(Gait{1.5, {}, {21}}, tInsert); + auto modeSchedule = gaitSchedule.getModeSchedule((tInsert - t0) + 1.5); + + // Check expected mode schedule + ASSERT_EQ(modeSchedule.modeSequence[0], 0); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[0], t0 + 0.5); + ASSERT_EQ(modeSchedule.modeSequence[1], 1); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[1], t0 + 1.0); + ASSERT_EQ(modeSchedule.modeSequence[2], 0); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[2], t0 + 1.5); + ASSERT_EQ(modeSchedule.modeSequence[3], 1); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[3], t0 + 2.0); + ASSERT_EQ(modeSchedule.modeSequence[4], 21); +} + +TEST(TestGaitSchedule, setGaitScheduleAtTime_currentTime) { + const double t0 = 1.0; + const double tInsert = 1.0; + + // Start with multi mode gait + GaitSchedule gaitSchedule(t0, Gait{1.0, {0.5}, {0, 1}}); + + // Set a new gait at t0 + gaitSchedule.setGaitAtTime(Gait{1.5, {}, {21}}, tInsert); + auto modeSchedule = gaitSchedule.getModeSchedule((tInsert - t0) + 1.5); + + // New gait is all that is left + ASSERT_TRUE(modeSchedule.eventTimes.empty()); + ASSERT_EQ(modeSchedule.modeSequence.front(), 21); +} + +TEST(TestGaitSchedule, setGaitScheduleAtTime_shortenCurrentGait) { + const double T = 1.0; // Gait repeats at t = 0.0, 1.0, 2.0 + const double Tinsert = 0.5; // period of inserted gait + const double tcurr = 0.7; + const double tInsert = 0.9; // insert before the current gait ends + + // Start with multi mode gait + GaitSchedule gaitSchedule(0.0, Gait{T, {0.5}, {0, 1}}); + + // Advance to get a non-zero current phase + gaitSchedule.advanceToTime(tcurr); + + // Set a new gait by interrupting the current gait + gaitSchedule.setGaitAtTime(Gait{Tinsert, {}, {21}}, tInsert); + auto modeSchedule = gaitSchedule.getModeSchedule(Tinsert); + + // Change happens at requested time + ASSERT_DOUBLE_EQ(gaitSchedule.timeLeftInCurrentGait(), tInsert - tcurr); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes.front(), tInsert); +} + +TEST(TestGaitSchedule, setGaitScheduleAfterTime) { + const double t0 = 18.6; + const double tInsert = 20.5 + 1.0; + + // Start with multi mode gait + GaitSchedule gaitSchedule(t0, Gait{2.0, {}, {0}}); + + // Set a new gait way pass the end of the current schedule + gaitSchedule.setGaitAfterTime(Gait{1.0, {}, {1}}, tInsert); + auto modeSchedule = gaitSchedule.getModeSchedule((tInsert - t0) + 1.5); + + // New gait inserted at the correct time + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes.back(), 22.6); +} + +TEST(TestGaitSchedule, setGaitScheduleAfterTimeWithNonzeroPhase) { + const double t0 = 0.0; + const double tadvance = 1.4; + const double tInsert = 2.4; + + // Start with multi mode gait + GaitSchedule gaitSchedule(t0, Gait{1.0, {}, {0}}); + + // Advance + gaitSchedule.advanceToTime(tadvance); + + // Set a new gait way pass the end of the current schedule + gaitSchedule.setGaitAfterTime(Gait{1.0, {}, {1}}, tInsert); + + auto modeSchedule = gaitSchedule.getModeSchedule(2.0); + + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes.size(), 1); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes.front(), 3.0); // First insert opportunity + ASSERT_EQ(modeSchedule.modeSequence.front(), 0); + ASSERT_EQ(modeSchedule.modeSequence.back(), 1); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSwitching.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSwitching.cpp new file mode 100644 index 000000000..987e1dc44 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testGaitSwitching.cpp @@ -0,0 +1,142 @@ +// +// Created by rgrandia on 15.03.20. +// + +#include + +#include "ocs2_switched_model_interface/logic/GaitSwitching.h" + +using namespace switched_model; + +const Gait singleModeGait = [] { + Gait gait; + gait.duration = 0.8; + gait.eventPhases = {}; + gait.modeSequence = {1}; + return gait; +}(); + +const Gait multiModeGait = [] { + Gait gait; + gait.duration = 0.6; + gait.eventPhases = {0.33, 0.66}; + gait.modeSequence = {0, 1, 2}; + return gait; +}(); + +TEST(TestAdvance, withinSameGait) { + std::vector gaitSchedule = {singleModeGait}; + + const double dt = 0.1; + const double phase = 0.1; + double advancedPhase; + std::vector::iterator nextGaitIt; + std::tie(advancedPhase, nextGaitIt) = advancePhase(phase, dt, gaitSchedule.begin(), gaitSchedule.end()); + + ASSERT_DOUBLE_EQ(advancedPhase, phase + dt / singleModeGait.duration); + ASSERT_EQ(nextGaitIt, gaitSchedule.begin()); + + // Looping the gait + std::tie(advancedPhase, nextGaitIt) = advancePhase(phase, dt + 3 * singleModeGait.duration, gaitSchedule.begin(), gaitSchedule.end()); + + // We loose some precision while recursing over the gaits. + ASSERT_NEAR(advancedPhase, phase + dt / singleModeGait.duration, 1e-12); + ASSERT_EQ(nextGaitIt, gaitSchedule.begin()); +} + +TEST(TestAdvance, advanceExactlyOneGaitcycle) { + std::vector gaitSchedule = {singleModeGait}; + + const double dt = singleModeGait.duration; + const double phase = 0.0; + double advancedPhase; + std::vector::iterator nextGaitIt; + std::tie(advancedPhase, nextGaitIt) = advancePhase(phase, dt, gaitSchedule.begin(), gaitSchedule.end()); + ASSERT_DOUBLE_EQ(advancedPhase, 0.0); +} + +TEST(TestAdvance, transitionGait) { + std::vector gaitSchedule = {singleModeGait, multiModeGait}; + + const double dt = 0.1; + const double phase = 0.9; + double advancedPhase; + std::vector::iterator nextGaitIt; + std::tie(advancedPhase, nextGaitIt) = advancePhase(phase, dt, gaitSchedule.begin(), gaitSchedule.end()); + + ASSERT_DOUBLE_EQ((1.0 - phase) * singleModeGait.duration + advancedPhase * multiModeGait.duration, dt); + ASSERT_EQ(nextGaitIt, gaitSchedule.end() - 1); + + // The same but, while looping the last gait + std::tie(advancedPhase, nextGaitIt) = advancePhase(phase, dt + 3 * multiModeGait.duration, gaitSchedule.begin(), gaitSchedule.end()); + + // We loose some precision while recursing over the gaits. + ASSERT_NEAR((1.0 - phase) * singleModeGait.duration + advancedPhase * multiModeGait.duration, dt, 1e-12); + ASSERT_EQ(nextGaitIt, gaitSchedule.end() - 1); +} + +TEST(TestGetModeSchedule, singleModeLooping) { + std::vector gaitSchedule = {singleModeGait}; + + auto modeSchedule = getModeSchedule(0.1, 123.0, 2.5, gaitSchedule.begin(), gaitSchedule.end()); + + // No mode switches -> no event times + ASSERT_EQ(modeSchedule.eventTimes.size(), 0); + ASSERT_EQ(modeSchedule.modeSequence.front(), singleModeGait.modeSequence.front()); +} + +TEST(TestGetModeSchedule, gaitTransition) { + std::vector gaitSchedule = {singleModeGait, multiModeGait}; + + double t0 = 0.1; + auto modeSchedule = + getModeSchedule(0.0, t0, singleModeGait.duration + multiModeGait.duration / 2, gaitSchedule.begin(), gaitSchedule.end()); + ASSERT_EQ(modeSchedule.eventTimes.size(), 2); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[0], singleModeGait.duration + t0); + ASSERT_DOUBLE_EQ(modeSchedule.eventTimes[1], multiModeGait.eventPhases[0] * multiModeGait.duration + singleModeGait.duration + t0); + ASSERT_EQ(modeSchedule.modeSequence[0], 1); + ASSERT_EQ(modeSchedule.modeSequence[1], 0); + ASSERT_EQ(modeSchedule.modeSequence[2], 1); +} + +TEST(TestGetModeSchedule, doubleGaitTransition) { + std::vector gaitSchedule = {multiModeGait, singleModeGait, multiModeGait}; + + double t0 = 0.1; + // Progress to half the last gait and loop it once + const double timeHorizon = multiModeGait.duration + singleModeGait.duration + 1.5 * multiModeGait.duration; + auto modeSchedule = getModeSchedule(0.0, t0, timeHorizon, gaitSchedule.begin(), gaitSchedule.end()); + // The switch to single mode and back has two event times. Halve the multiMode as also two event times + ASSERT_EQ(modeSchedule.eventTimes.size(), multiModeGait.eventPhases.size() + 2 + multiModeGait.eventPhases.size() + 2); + ASSERT_EQ(modeSchedule.modeSequence.back(), 1); +} + +TEST(TestGetModeSchedule, mergePhases) { + std::vector gaitSchedule = {singleModeGait, singleModeGait, multiModeGait}; + + double t0 = 0.1; + // Progress to half the last gait and loop it once + const double timeHorizon = 2.0 * singleModeGait.duration + multiModeGait.duration; + auto modeSchedule = getModeSchedule(0.0, t0, timeHorizon, gaitSchedule.begin(), gaitSchedule.end()); + // The switch to between the two single modes is merged to 1. + ASSERT_EQ(modeSchedule.eventTimes.size(), 1 + multiModeGait.eventPhases.size()); + ASSERT_EQ(modeSchedule.modeSequence[0], 1); + ASSERT_EQ(modeSchedule.modeSequence[1], 0); + ASSERT_EQ(modeSchedule.modeSequence[2], 1); + ASSERT_EQ(modeSchedule.modeSequence[3], 2); +} + +TEST(TestGetModeSchedule, finalPhaseNotFullyInHorizon) { + std::vector gaitSchedule = {singleModeGait, multiModeGait}; + + double t0 = 0.0; + // Progress to half the last gait and loop it once + const double timeHorizon = singleModeGait.duration + 0.999 * multiModeGait.duration; + auto modeSchedule = getModeSchedule(0.0, t0, timeHorizon, gaitSchedule.begin(), gaitSchedule.end()); + // The switch to between the two single modes is merged to 1. + ASSERT_EQ(modeSchedule.eventTimes.size(), 1 + multiModeGait.eventPhases.size()); + ASSERT_EQ(modeSchedule.modeSequence[0], 1); + ASSERT_EQ(modeSchedule.modeSequence[1], 0); + ASSERT_EQ(modeSchedule.modeSequence[2], 1); + ASSERT_EQ(modeSchedule.modeSequence[3], 2); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testSingleLegLogic.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testSingleLegLogic.cpp new file mode 100644 index 000000000..bc5e084aa --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/logic/testSingleLegLogic.cpp @@ -0,0 +1,62 @@ +// +// Created by rgrandia on 29.04.20. +// + +#include + +#include "ocs2_switched_model_interface/logic/SingleLegLogic.h" + +using namespace switched_model; + +TEST(TestContactTiming, stanceOnly) { + ContactTiming stanceOnly{timingNaN(), timingNaN()}; + std::vector stanceOnlyVector = {stanceOnly}; + + ASSERT_FALSE(hasStartTime(stanceOnly)); + ASSERT_FALSE(hasEndTime(stanceOnly)); + ASSERT_FALSE(startsWithSwingPhase(stanceOnlyVector)); + ASSERT_TRUE(startsWithStancePhase(stanceOnlyVector)); + ASSERT_FALSE(endsWithSwingPhase(stanceOnlyVector)); + ASSERT_TRUE(endsWithStancePhase(stanceOnlyVector)); + ASSERT_FALSE(touchesDownAtLeastOnce(stanceOnlyVector)); + ASSERT_FALSE(liftsOffAtLeastOnce(stanceOnlyVector)); +} + +TEST(TestContactTiming, SwingOnly) { + std::vector swingOnlyVector = {}; + + ASSERT_TRUE(startsWithSwingPhase(swingOnlyVector)); + ASSERT_FALSE(startsWithStancePhase(swingOnlyVector)); + ASSERT_TRUE(endsWithSwingPhase(swingOnlyVector)); + ASSERT_FALSE(endsWithStancePhase(swingOnlyVector)); + ASSERT_FALSE(touchesDownAtLeastOnce(swingOnlyVector)); + ASSERT_FALSE(liftsOffAtLeastOnce(swingOnlyVector)); +} + +TEST(TestContactTiming, SwingToStance) { + ContactTiming stance{0.0, timingNaN()}; + std::vector swingToStanceVector = {stance}; + + ASSERT_TRUE(hasStartTime(stance)); + ASSERT_FALSE(hasEndTime(stance)); + ASSERT_TRUE(startsWithSwingPhase(swingToStanceVector)); + ASSERT_FALSE(startsWithStancePhase(swingToStanceVector)); + ASSERT_FALSE(endsWithSwingPhase(swingToStanceVector)); + ASSERT_TRUE(endsWithStancePhase(swingToStanceVector)); + ASSERT_TRUE(touchesDownAtLeastOnce(swingToStanceVector)); + ASSERT_FALSE(liftsOffAtLeastOnce(swingToStanceVector)); +} + +TEST(TestContactTiming, StanceToSwing) { + ContactTiming stance{timingNaN(), 0.0}; + std::vector stanceToSwingVector = {stance}; + + ASSERT_FALSE(hasStartTime(stance)); + ASSERT_TRUE(hasEndTime(stance)); + ASSERT_FALSE(startsWithSwingPhase(stanceToSwingVector)); + ASSERT_TRUE(startsWithStancePhase(stanceToSwingVector)); + ASSERT_TRUE(endsWithSwingPhase(stanceToSwingVector)); + ASSERT_FALSE(endsWithStancePhase(stanceToSwingVector)); + ASSERT_FALSE(touchesDownAtLeastOnce(stanceToSwingVector)); + ASSERT_TRUE(liftsOffAtLeastOnce(stanceToSwingVector)); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testConvexTerrain.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testConvexTerrain.cpp new file mode 100644 index 000000000..e02b4180a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testConvexTerrain.cpp @@ -0,0 +1,110 @@ +// +// Created by rgrandia on 29.04.20. +// + +#include + +#include "ocs2_switched_model_interface/core/Rotations.h" +#include "ocs2_switched_model_interface/terrain/ConvexTerrain.h" + +using namespace switched_model; + +TerrainPlane getRandomTerrain() { + vector3_t eulerXYZ = vector3_t::Random(); + return {vector3_t::Random(), rotationMatrixBaseToOrigin(eulerXYZ)}; +} + +std::vector getRandomboundary(size_t N) { + std::vector boundary(N); + for (auto& b : boundary) { + b.setRandom(); + } + return boundary; +} + +TEST(TestConvexTerrain, projectToConvex2dPolygonBoundary_signTest) { + constexpr size_t N = 3; + const auto boundary = getRandomboundary(N); + + for (size_t numTests = 0; numTests < 3; numTests++) { + // a point inside + const auto insidePoint = [&]() -> vector2_t { + vector_t lambda = 0.5 * vector_t::Random(N) + 0.5 * vector_t::Ones(N); // positive numbers in [0, 1] + lambda /= lambda.sum(); + + vector2_t p = vector2_t::Zero(); + for (size_t i = 0; i < boundary.size(); i++) { + p += lambda(i) * boundary[i]; + } + return p; + }(); + + // a point outside + const auto outsidePoint = [&]() -> vector2_t { + const vector_t lambda = vector_t::Random(N) + 2.0 * vector_t::Ones(N); // numbers in [1, 3] + + vector2_t p = vector2_t::Zero(); + for (size_t i = 0; i < boundary.size(); i++) { + p += lambda(i) * boundary[i]; + } + return p; + }(); + + // a point on the polygon boundary + const auto onPoint = [&]() -> vector2_t { + vector_t lambda = 0.5 * vector_t::Random(2) + 0.5 * vector_t::Ones(2); // positive numbers in [0, 1] + lambda /= lambda.sum(); + return lambda(0) * boundary[0] + lambda(1) * boundary[1]; + }(); + + EXPECT_NEAR(projectToConvex2dPolygonBoundary(boundary, onPoint).first, 0.0, 1e-9); + EXPECT_LT(projectToConvex2dPolygonBoundary(boundary, insidePoint).first, 0.0); + EXPECT_GT(projectToConvex2dPolygonBoundary(boundary, outsidePoint).first, 0.0); + } +} + +TEST(TestConvexTerrain, projectToConvex2dPolygonBoundary_valueTest) { + const std::vector boundary{vector2_t(-1.0, -1.0), vector2_t(-1.0, 1.0), vector2_t(1.0, 1.0), vector2_t(1.0, -1.0)}; + + for (size_t numTests = 0; numTests < 3; numTests++) { + // a point inside + const vector2_t insidePoint = vector2_t::Random(); + + const scalar_array_t insidePointDists{-std::abs(insidePoint.x() - 1.0), -std::abs(insidePoint.x() + 1.0), + -std::abs(insidePoint.y() - 1.0), -std::abs(insidePoint.y() + 1.0)}; + const auto minDist = std::max_element(insidePointDists.cbegin(), insidePointDists.cend()); + + const auto distance2ImagePair = projectToConvex2dPolygonBoundary(boundary, insidePoint); + const auto computedDist = (distance2ImagePair.first > 0.0) ? std::sqrt(distance2ImagePair.first) : -std::sqrt(-distance2ImagePair.first); + + EXPECT_NEAR(computedDist, *minDist, 1e-9); + } +} + +TEST(TestConvexTerrain, projectToConvexPolygon) { + ConvexTerrain convexTerrain; + convexTerrain.plane = getRandomTerrain(); + convexTerrain.boundary = {vector2_t(-0.5, -0.5), vector2_t(-0.5, 0.5), vector2_t(0.5, 0.5), vector2_t(0.5, -0.5)}; + + // plane center point + { + const vector3_t point = convexTerrain.plane.positionInWorld; + const vector3_t image = projectToConvex3dPolygon(convexTerrain, point); + const vector3_t local_image = positionInTerrainFrameFromPositionInWorld(image, convexTerrain.plane); + + EXPECT_NEAR(local_image.x(), 0.0, 1e-9); + EXPECT_NEAR(local_image.y(), 0.0, 1e-9); + EXPECT_NEAR(local_image.z(), 0.0, 1e-9); + } + + // random point + { + const vector3_t point = vector3_t::Random(); + const vector3_t image = projectToConvex3dPolygon(convexTerrain, point); + const vector3_t local_image = positionInTerrainFrameFromPositionInWorld(image, convexTerrain.plane); + + EXPECT_LT(std::abs(local_image.x()), 0.5 + 1e-9); + EXPECT_LT(std::abs(local_image.y()), 0.5 + 1e-9); + EXPECT_NEAR(local_image.z(), 0.0, 1e-9); + } +} diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testTerrainPlane.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testTerrainPlane.cpp new file mode 100644 index 000000000..1902e678c --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_interface/test/terrain/testTerrainPlane.cpp @@ -0,0 +1,148 @@ +// +// Created by rgrandia on 29.04.20. +// + +#include + +#include "ocs2_switched_model_interface/terrain/TerrainPlane.h" + +#include "ocs2_switched_model_interface/core/Rotations.h" + +using namespace switched_model; + +TerrainPlane getRandomTerrain() { + vector3_t eulerXYZ = vector3_t::Random(); + return {vector3_t::Random(), rotationMatrixBaseToOrigin(eulerXYZ)}; +} + +TEST(TestTerrainPlane, surfaceNormal) { + TerrainPlane canonicalPlane{vector3_t::Zero(), matrix3_t::Identity()}; + + ASSERT_TRUE(surfaceNormalInWorld(canonicalPlane).isApprox(vector3_t{0.0, 0.0, 1.0})); + + vector3_t eulerXYZ{0.0, 0.0, 0.3}; + const auto yawRotation = rotationMatrixBaseToOrigin(eulerXYZ); + + TerrainPlane yawRotatedPlane{vector3_t::Zero(), yawRotation * matrix3_t::Identity()}; + + ASSERT_TRUE(surfaceNormalInWorld(yawRotatedPlane).isApprox(vector3_t{0.0, 0.0, 1.0})); +} + +TEST(TestTerrainPlane, tangentialBasisFromSurfaceNormal) { + const auto randomPlane = getRandomTerrain(); + const auto surfaceNormal = surfaceNormalInWorld(randomPlane); + + const auto tangentialBasis = tangentialBasisFromSurfaceNormal(surfaceNormal); + + // Normalized + ASSERT_DOUBLE_EQ(tangentialBasis.row(0).norm(), 1.0); + ASSERT_DOUBLE_EQ(tangentialBasis.row(1).norm(), 1.0); + + // Orthogonal + const double tol = 1e-9; + ASSERT_LT(std::abs(tangentialBasis.row(0).dot(surfaceNormal)), tol); + ASSERT_LT(std::abs(tangentialBasis.row(1).dot(surfaceNormal)), tol); + ASSERT_LT(std::abs(tangentialBasis.row(0).dot(tangentialBasis.row(1))), tol); +} + +TEST(TestTerrainPlane, tangentialBasisFromSurfaceNormalUnitX) { + const auto surfaceNormal = vector3_t::UnitX(); + const auto tangentialBasis = tangentialBasisFromSurfaceNormal(surfaceNormal); + + // Normalized + ASSERT_DOUBLE_EQ(tangentialBasis.row(0).norm(), 1.0); + ASSERT_DOUBLE_EQ(tangentialBasis.row(1).norm(), 1.0); + + // Orthogonal + const double tol = 1e-9; + ASSERT_LT(std::abs(tangentialBasis.row(0).dot(surfaceNormal)), tol); + ASSERT_LT(std::abs(tangentialBasis.row(1).dot(surfaceNormal)), tol); + ASSERT_LT(std::abs(tangentialBasis.row(0).dot(tangentialBasis.row(1))), tol); + + // Y is still unit y + ASSERT_TRUE(tangentialBasis.row(1).transpose().isApprox(vector3_t::UnitY())); +} + +TEST(TestTerrainPlane, orientationWorldToTerrainFromSurfaceNormalInWorld) { + const vector3_t surfaceNormal = vector3_t::Random().normalized(); + + // Extract + const matrix3_t R_WtoT = orientationWorldToTerrainFromSurfaceNormalInWorld(surfaceNormal); + const vector3_t xAxisInWorld = R_WtoT.row(0).transpose(); + const vector3_t yAxisInWorld = R_WtoT.row(1).transpose(); + const vector3_t zAxisInWorld = R_WtoT.row(2).transpose(); + + const double tol = 1e-9; + ASSERT_LT(std::abs(R_WtoT.determinant() - 1.0), tol); + + // z-axis is the surface normal + ASSERT_TRUE(zAxisInWorld.isApprox(surfaceNormal)); + + // Right hand coordinate system + ASSERT_TRUE(zAxisInWorld.cross(xAxisInWorld).isApprox(yAxisInWorld)); + + // Ortogonal + ASSERT_LT(std::abs(xAxisInWorld.dot(yAxisInWorld)), tol); + ASSERT_LT(std::abs(xAxisInWorld.dot(zAxisInWorld)), tol); + ASSERT_LT(std::abs(yAxisInWorld.dot(zAxisInWorld)), tol); +} + +TEST(TestTerrainPlane, orientationWorldToTerrainFromSurfaceNormalInWorld_identity) { + // If the normal is in z direction in world. We want to retrieve the identity rotation. (local and world frame are aligned) + const matrix3_t R_WtoT = orientationWorldToTerrainFromSurfaceNormalInWorld(vector3_t::UnitZ()); + ASSERT_TRUE(R_WtoT.isApprox(matrix3_t::Identity())); +} + +TEST(TestTerrainPlane, projectPositionInWorldOntoPlane) { + const auto randomPlane = getRandomTerrain(); + + // Origin of plane is projected to itself + ASSERT_TRUE(projectPositionInWorldOntoPlane(randomPlane.positionInWorld, randomPlane).isApprox(randomPlane.positionInWorld)); + + // Random point projected + const auto projectedPosition = projectPositionInWorldOntoPlane(vector3_t::Random(), randomPlane); + + // Distance to plane + const double tol = 1e-9; + ASSERT_LT(std::abs(terrainSignedDistanceFromPositionInWorld(projectedPosition, randomPlane)), tol); + + // Double projection + ASSERT_TRUE(projectPositionInWorldOntoPlane(projectedPosition, randomPlane).isApprox(projectedPosition)); +} + +TEST(TestTerrainPlane, projectPositionInWorldOntoPlaneAlongGravity_flatTerrain) { + vector3_t eulerXYZ(0, 0, 0.3); + TerrainPlane flatTerrain = {vector3_t::Random(), rotationMatrixOriginToBase(eulerXYZ)}; + + // Origin of plane is projected to itself + ASSERT_TRUE(projectPositionInWorldOntoPlaneAlongGravity(flatTerrain.positionInWorld, flatTerrain).isApprox(flatTerrain.positionInWorld)); + + // Any point in the horizontal plane should stay point projected + const vector3_t queryPosition = {1.0, 1.0, 0.0}; + const auto projectedPosition = projectPositionInWorldOntoPlaneAlongGravity(queryPosition, flatTerrain); + + ASSERT_TRUE(queryPosition.head(2).isApprox(projectedPosition.head(2))); + ASSERT_DOUBLE_EQ(projectedPosition.z(), flatTerrain.positionInWorld.z()); +} + +TEST(TestTerrainPlane, projectPositionInWorldOntoPlaneAlongGravity_randomTerrain) { + const auto randomPlane = getRandomTerrain(); + + // Origin of plane is projected to itself + ASSERT_TRUE(projectPositionInWorldOntoPlaneAlongGravity(randomPlane.positionInWorld, randomPlane).isApprox(randomPlane.positionInWorld)); + + // Random point projected + const vector3_t queryPosition = vector3_t::Random(); + const auto projectedPosition = projectPositionInWorldOntoPlaneAlongGravity(queryPosition, randomPlane); + + // x, y position remained to same + ASSERT_DOUBLE_EQ(projectedPosition.x(), queryPosition.x()); + ASSERT_DOUBLE_EQ(projectedPosition.y(), queryPosition.y()); + + // Distance to plane + const double tol = 1e-9; + ASSERT_LT(std::abs(terrainSignedDistanceFromPositionInWorld(projectedPosition, randomPlane)), tol); + + // Double projection + ASSERT_TRUE(projectPositionInWorldOntoPlane(projectedPosition, randomPlane).isApprox(projectedPosition)); +} \ No newline at end of file diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/CMakeLists.txt new file mode 100644 index 000000000..ae4bd5689 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.0.0) +project(ocs2_switched_model_msgs) + +set(CATKIN_PACKAGE_DEPENDENCIES + std_msgs + ocs2_msgs +) + +find_package(catkin REQUIRED COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} + message_generation +) + +# Declare the message files to be built +add_message_files(DIRECTORY msg FILES + gait.msg + gait_sequence.msg + scheduled_gait_sequence.msg +) + +# Declare the service files to be built +add_service_files(DIRECTORY srv FILES + trajectory_request.srv +) + +# Actually generate the language-specific message and service files +generate_messages(DEPENDENCIES + ${CATKIN_PACKAGE_DEPENDENCIES} +) + +# Declare that this catkin package's runtime dependencies +catkin_package(CATKIN_DEPENDS + ${CATKIN_PACKAGE_DEPENDENCIES} + message_runtime +) diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait.msg b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait.msg new file mode 100644 index 000000000..38db64176 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait.msg @@ -0,0 +1,5 @@ +# Gait message + +float32[] eventPhases # event phases: length equal to modesequence's - 1. Values within [0,1] +int8[] modeSequence # mode sequence: e.g., for a quadrupedal robot, it is in the set {0, 1,..., 15} +float32 duration diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait_sequence.msg b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait_sequence.msg new file mode 100644 index 000000000..a52dbf80e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/gait_sequence.msg @@ -0,0 +1,3 @@ +# Sequence of gaits + +gait[] gaits diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/scheduled_gait_sequence.msg b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/scheduled_gait_sequence.msg new file mode 100644 index 000000000..7bf2458ba --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/msg/scheduled_gait_sequence.msg @@ -0,0 +1,4 @@ +# Scheduled list of gaits + +float32 startTime +gait_sequence gaitSequence diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/package.xml new file mode 100644 index 000000000..85bdd0121 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/package.xml @@ -0,0 +1,19 @@ + + ocs2_switched_model_msgs + 0.0.1 + Provides ocs2_switched_model_msgs + + Marko Bjelonic + Ruben Grandia + Oliver Harley + Oliver Harley + + TODO + + catkin + message_generation + std_msgs + ocs2_msgs + message_runtime + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/srv/trajectory_request.srv b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/srv/trajectory_request.srv new file mode 100644 index 000000000..cb311f595 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/ocs2_switched_model_msgs/srv/trajectory_request.srv @@ -0,0 +1,6 @@ +# Trajectory request service + +ocs2_msgs/mpc_target_trajectories trajectory # The trajectory to track +gait_sequence gaitSequence # The gait +--- +bool success # 1 if successful 0 if trajectory couldn't be started. diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/CMakeLists.txt b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/CMakeLists.txt new file mode 100644 index 000000000..6a5454e26 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/CMakeLists.txt @@ -0,0 +1,76 @@ +cmake_minimum_required(VERSION 3.10) +project(segmented_planes_terrain_model) + +# Catkin dependencies +set(CATKIN_PACKAGE_DEPENDENCIES + convex_plane_decomposition + convex_plane_decomposition_msgs + convex_plane_decomposition_ros + grid_map_filters_rsl + grid_map_ros + grid_map_sdf + ocs2_ros_interfaces + ocs2_switched_model_interface + roscpp + sensor_msgs + visualization_msgs +) + +find_package(catkin REQUIRED COMPONENTS + ${CATKIN_PACKAGE_DEPENDENCIES} +) + +# Cpp standard version +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS ${CATKIN_PACKAGE_DEPENDENCIES} + DEPENDS +) + +########### +## Build ## +########### + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/SegmentedPlanesTerrainModel.cpp + src/SegmentedPlanesTerrainModelRos.cpp + src/SegmentedPlanesTerrainVisualization.cpp + ) +add_dependencies(${PROJECT_NAME} + ${catkin_EXPORTED_TARGETS} + ) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + ) +target_compile_options(${PROJECT_NAME} + PUBLIC -DCGAL_HAS_THREADS + ) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + ) + +############# +## Testing ## +############# diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesSignedDistanceField.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesSignedDistanceField.h new file mode 100644 index 000000000..254d786fc --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesSignedDistanceField.h @@ -0,0 +1,47 @@ +// +// Created by rgrandia on 17.03.22. +// + +#pragma once + +#include + +#include + +namespace switched_model { + +/** + * Simple wrapper class to implement the switched_model::SignedDistanceField interface. + * See the forwarded function for documentation. + */ +class SegmentedPlanesSignedDistanceField : public SignedDistanceField { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + SegmentedPlanesSignedDistanceField(const grid_map::GridMap& gridMap, const std::string& elevationLayer, double minHeight, + double maxHeight) + : sdf_(gridMap, elevationLayer, minHeight, maxHeight) {} + + ~SegmentedPlanesSignedDistanceField() override = default; + SegmentedPlanesSignedDistanceField* clone() const override { return new SegmentedPlanesSignedDistanceField(*this); }; + + switched_model::scalar_t value(const switched_model::vector3_t& position) const override { return sdf_.value(position); } + + switched_model::vector3_t derivative(const switched_model::vector3_t& position) const override { return sdf_.derivative(position); } + + std::pair valueAndDerivative( + const switched_model::vector3_t& position) const override { + return sdf_.valueAndDerivative(position); + } + + grid_map::SignedDistanceField& asGridmapSdf() { return sdf_; } + const grid_map::SignedDistanceField& asGridmapSdf() const { return sdf_; } + + protected: + SegmentedPlanesSignedDistanceField(const SegmentedPlanesSignedDistanceField& other) : sdf_(other.sdf_){}; + + private: + grid_map::SignedDistanceField sdf_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModel.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModel.h new file mode 100644 index 000000000..3574dec1a --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModel.h @@ -0,0 +1,42 @@ +// +// Created by rgrandia on 23.06.20. +// + +#pragma once + +#include + +#include + +#include "segmented_planes_terrain_model/SegmentedPlanesSignedDistanceField.h" + +namespace switched_model { + +class SegmentedPlanesTerrainModel : public switched_model::TerrainModel { + public: + SegmentedPlanesTerrainModel(convex_plane_decomposition::PlanarTerrain planarTerrain); + + TerrainPlane getLocalTerrainAtPositionInWorldAlongGravity(const vector3_t& positionInWorld, + std::function penaltyFunction) const override; + + using switched_model::TerrainModel::getConvexTerrainAtPositionInWorld; + ConvexTerrain getConvexTerrainAtPositionInWorld(const vector3_t& positionInWorld, + std::function penaltyFunction) const override; + + void createSignedDistanceBetween(const Eigen::Vector3d& minCoordinates, const Eigen::Vector3d& maxCoordinates); + + const SegmentedPlanesSignedDistanceField* getSignedDistanceField() const override { return signedDistanceField_.get(); } + + vector3_t getHighestObstacleAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const override; + + std::vector getHeightProfileAlongLine(const vector3_t& position1InWorld, const vector3_t& position2InWorld) const override; + + const convex_plane_decomposition::PlanarTerrain& planarTerrain() const { return planarTerrain_; } + + private: + const convex_plane_decomposition::PlanarTerrain planarTerrain_; + std::unique_ptr signedDistanceField_; + const grid_map::Matrix* const elevationData_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModelRos.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModelRos.h new file mode 100644 index 000000000..e3c75cea5 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainModelRos.h @@ -0,0 +1,57 @@ +// +// Created by rgrandia on 24.06.20. +// + +#pragma once + +#include + +#include + +#include + +#include + +#include + +#include "SegmentedPlanesTerrainModel.h" + +namespace switched_model { + +class SegmentedPlanesTerrainModelRos { + public: + SegmentedPlanesTerrainModelRos(ros::NodeHandle& nodehandle); + + ~SegmentedPlanesTerrainModelRos(); + + /// Extract the latest terrain model. Resets internal model to a nullptr + std::unique_ptr getTerrainModel(); + + void createSignedDistanceBetween(const Eigen::Vector3d& minCoordinates, const Eigen::Vector3d& maxCoordinates); + + void publish(); + + private: + void callback(const convex_plane_decomposition_msgs::PlanarTerrain::ConstPtr& msg); + + std::pair getSignedDistanceRange(const grid_map::GridMap& gridMap, const std::string& elevationLayer); + + ros::Subscriber terrainSubscriber_; + ros::Publisher distanceFieldPublisher_; + + std::mutex updateMutex_; + std::atomic_bool terrainUpdated_; + std::unique_ptr terrainPtr_; + + std::mutex updateCoordinatesMutex_; + Eigen::Vector3d minCoordinates_; + Eigen::Vector3d maxCoordinates_; + bool externalCoordinatesGiven_; + + std::mutex pointCloudMutex_; + std::unique_ptr pointCloud2MsgPtr_; + + ocs2::benchmark::RepeatedTimer callbackTimer_; +}; + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainVisualization.h b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainVisualization.h new file mode 100644 index 000000000..6c8acf6b4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/include/segmented_planes_terrain_model/SegmentedPlanesTerrainVisualization.h @@ -0,0 +1,18 @@ +// +// Created by rgrandia on 24.06.20. +// + +#pragma once + +#include +#include + +#include +#include + +namespace switched_model { + +visualization_msgs::MarkerArray getConvexTerrainMarkers(const ConvexTerrain& convexTerrain, ocs2::Color color, double linewidth, + double normalLength); + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/package.xml b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/package.xml new file mode 100644 index 000000000..c9b7fb7c4 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/package.xml @@ -0,0 +1,24 @@ + + + segmented_planes_terrain_model + 0.0.0 + The segmented_planes_terrain_model package + + Ruben Grandia + + TODO + + catkin + convex_plane_decomposition + convex_plane_decomposition_msgs + convex_plane_decomposition_ros + grid_map_filters_rsl + grid_map_ros + grid_map_sdf + ocs2_ros_interfaces + ocs2_switched_model_interface + roscpp + sensor_msgs + visualization_msgs + + diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModel.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModel.cpp new file mode 100644 index 000000000..dfaef97ef --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModel.cpp @@ -0,0 +1,127 @@ +// +// Created by rgrandia on 23.06.20. +// + +#include "segmented_planes_terrain_model/SegmentedPlanesTerrainModel.h" + +#include + +#include +#include + +#include + +namespace switched_model { + +namespace { +const std::string elevationLayerName = "elevation"; +} // namespace + +SegmentedPlanesTerrainModel::SegmentedPlanesTerrainModel(convex_plane_decomposition::PlanarTerrain planarTerrain) + : planarTerrain_(std::move(planarTerrain)), + signedDistanceField_(nullptr), + elevationData_(&planarTerrain_.gridMap.get(elevationLayerName)) {} + +TerrainPlane SegmentedPlanesTerrainModel::getLocalTerrainAtPositionInWorldAlongGravity( + const vector3_t& positionInWorld, std::function penaltyFunction) const { + const auto projection = getBestPlanarRegionAtPositionInWorld(positionInWorld, planarTerrain_.planarRegions, std::move(penaltyFunction)); + if (projection.regionPtr == nullptr) { + throw std::runtime_error("[SegmentedPlanesTerrainModel] no region found"); + } + + return TerrainPlane{projection.positionInWorld, projection.regionPtr->transformPlaneToWorld.linear().transpose()}; +} + +ConvexTerrain SegmentedPlanesTerrainModel::getConvexTerrainAtPositionInWorld( + const vector3_t& positionInWorld, std::function penaltyFunction) const { + const auto projection = getBestPlanarRegionAtPositionInWorld(positionInWorld, planarTerrain_.planarRegions, std::move(penaltyFunction)); + if (projection.regionPtr == nullptr) { + throw std::runtime_error("[SegmentedPlanesTerrainModel] no region found"); + } + + // Convert boundary and projection to terrain frame + const int numberOfVertices = 16; // Multiple of 4 is nice for symmetry. + const double growthFactor = 1.05; + const auto convexRegion = convex_plane_decomposition::growConvexPolygonInsideShape( + projection.regionPtr->boundaryWithInset.boundary, projection.positionInTerrainFrame, numberOfVertices, growthFactor); + + // Return convex region with origin at the projection + ConvexTerrain convexTerrain; + convexTerrain.plane = {projection.positionInWorld, + projection.regionPtr->transformPlaneToWorld.linear().transpose()}; // Origin is at the projection + convexTerrain.boundary.reserve(convexRegion.size()); + for (const auto& point : convexRegion) { + convexTerrain.boundary.emplace_back(point.x() - projection.positionInTerrainFrame.x(), + point.y() - projection.positionInTerrainFrame.y()); // Shift points to new origin + } + return convexTerrain; +} + +void SegmentedPlanesTerrainModel::createSignedDistanceBetween(const Eigen::Vector3d& minCoordinates, + const Eigen::Vector3d& maxCoordinates) { + // Compute coordinates of submap + const auto minXY = + grid_map::lookup::projectToMapWithMargin(planarTerrain_.gridMap, grid_map::Position(minCoordinates.x(), minCoordinates.y())); + const auto maxXY = + grid_map::lookup::projectToMapWithMargin(planarTerrain_.gridMap, grid_map::Position(maxCoordinates.x(), maxCoordinates.y())); + const auto centerXY = 0.5 * (minXY + maxXY); + const auto lengths = maxXY - minXY; + + bool success = true; + grid_map::GridMap subMap = planarTerrain_.gridMap.getSubmap(centerXY, lengths, success); + if (success) { + signedDistanceField_ = + std::make_unique(subMap, elevationLayerName, minCoordinates.z(), maxCoordinates.z()); + } else { + std::cerr << "[SegmentedPlanesTerrainModel] Failed to get subMap" << std::endl; + } +} + +vector3_t SegmentedPlanesTerrainModel::getHighestObstacleAlongLine(const vector3_t& position1InWorld, + const vector3_t& position2InWorld) const { + const auto result = grid_map::lookup::maxValueBetweenLocations( + {position1InWorld.x(), position1InWorld.y()}, {position2InWorld.x(), position2InWorld.y()}, planarTerrain_.gridMap, *elevationData_); + if (result.isValid) { + return {result.position.x(), result.position.y(), result.value}; + } else { + // return highest query point if the map didn't work. + if (position1InWorld.z() > position2InWorld.z()) { + return position1InWorld; + } else { + return position2InWorld; + } + } +} + +std::vector SegmentedPlanesTerrainModel::getHeightProfileAlongLine(const vector3_t& position1InWorld, + const vector3_t& position2InWorld) const { + const vector2_t diff2d = position2InWorld.head<2>() - position1InWorld.head<2>(); + const scalar_t diffSquareNorm = diff2d.squaredNorm(); + const auto resolution = planarTerrain_.gridMap.getResolution(); + + if (diffSquareNorm > (resolution * resolution)) { // norm(p2-p1)_XY > resolution + const auto pointsOnLine = + grid_map::lookup::valuesBetweenLocations({position1InWorld.x(), position1InWorld.y()}, {position2InWorld.x(), position2InWorld.y()}, + planarTerrain_.gridMap, *elevationData_); + + std::vector heightProfile; + heightProfile.reserve(pointsOnLine.size()); + + for (const auto& point : pointsOnLine) { + const vector2_t pointDiff = point.head<2>() - position1InWorld.head<2>(); + const scalar_t lineProgress = pointDiff.dot(diff2d) / diffSquareNorm; + if (lineProgress >= 0.0 && lineProgress <= 1.0) { + heightProfile.push_back({lineProgress, point.z()}); + } + } + + return heightProfile; + } else { + grid_map::Index index; + planarTerrain_.gridMap.getIndex({position1InWorld.x(), position1InWorld.y()}, index); + scalar_t heightData = (*elevationData_)(index(0), index(1)); + return {{0.0, heightData}, {1.0, heightData}}; + } +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModelRos.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModelRos.cpp new file mode 100644 index 000000000..fa83f1da1 --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainModelRos.cpp @@ -0,0 +1,123 @@ +// +// Created by rgrandia on 24.06.20. +// + +#include "segmented_planes_terrain_model/SegmentedPlanesTerrainModelRos.h" + +#include + +#include + +#include + +namespace switched_model { + +SegmentedPlanesTerrainModelRos::SegmentedPlanesTerrainModelRos(ros::NodeHandle& nodehandle) + : terrainUpdated_(false), + minCoordinates_(Eigen::Vector3d::Zero()), + maxCoordinates_(Eigen::Vector3d::Zero()), + externalCoordinatesGiven_(false) { + terrainSubscriber_ = + nodehandle.subscribe("/convex_plane_decomposition_ros/planar_terrain", 1, &SegmentedPlanesTerrainModelRos::callback, this); + distanceFieldPublisher_ = + nodehandle.advertise("/convex_plane_decomposition_ros/signed_distance_field", 1, true); +} + +SegmentedPlanesTerrainModelRos::~SegmentedPlanesTerrainModelRos() { + if (callbackTimer_.getNumTimedIntervals() > 0) { + std::cout << "[SegmentedPlanesTerrainModelRos] Benchmarking terrain Callback\n" + << "\tStatistics computed over " << callbackTimer_.getNumTimedIntervals() << " iterations. \n" + << "\tAverage time [ms] " << callbackTimer_.getAverageInMilliseconds() << "\n" + << "\tMaximum time [ms] " << callbackTimer_.getMaxIntervalInMilliseconds() << std::endl; + } +} + +std::unique_ptr SegmentedPlanesTerrainModelRos::getTerrainModel() { + std::lock_guard lock(updateMutex_); + return std::move(terrainPtr_); +} + +void SegmentedPlanesTerrainModelRos::createSignedDistanceBetween(const Eigen::Vector3d& minCoordinates, + const Eigen::Vector3d& maxCoordinates) { + std::lock_guard lock(updateCoordinatesMutex_); + minCoordinates_ = minCoordinates; + maxCoordinates_ = maxCoordinates; + externalCoordinatesGiven_ = true; +} + +void SegmentedPlanesTerrainModelRos::publish() { + // Extract point cloud. + std::unique_ptr pointCloud2MsgPtr; + { + std::lock_guard lock(pointCloudMutex_); + pointCloud2MsgPtr.swap(pointCloud2MsgPtr_); + } + + // Publish. + if (pointCloud2MsgPtr != nullptr) { + distanceFieldPublisher_.publish(*pointCloud2MsgPtr); + } +} + +void SegmentedPlanesTerrainModelRos::callback(const convex_plane_decomposition_msgs::PlanarTerrain::ConstPtr& msg) { + callbackTimer_.startTimer(); + + // Read terrain + auto terrainPtr = std::make_unique(convex_plane_decomposition::fromMessage(*msg)); + + // Create SDF + const std::string elevationLayer = "elevation"; + if (terrainPtr->planarTerrain().gridMap.exists(elevationLayer)) { + const auto sdfRange = getSignedDistanceRange(terrainPtr->planarTerrain().gridMap, elevationLayer); + terrainPtr->createSignedDistanceBetween(sdfRange.first, sdfRange.second); + } + + // Create pointcloud for visualization + const auto* sdfPtr = terrainPtr->getSignedDistanceField(); + if (sdfPtr != nullptr) { + const auto& sdf = sdfPtr->asGridmapSdf(); + std::unique_ptr pointCloud2MsgPtr(new sensor_msgs::PointCloud2()); + grid_map::GridMapRosConverter::toPointCloud(sdf, *pointCloud2MsgPtr, 1, [](float val) { return -0.05F <= val && val <= 0.0F; }); + std::lock_guard lock(pointCloudMutex_); + pointCloud2MsgPtr_.swap(pointCloud2MsgPtr); + } + + { // Move to storage under the lock + std::lock_guard lock(updateMutex_); + terrainPtr_.swap(terrainPtr); + } + + callbackTimer_.endTimer(); +} + +std::pair SegmentedPlanesTerrainModelRos::getSignedDistanceRange(const grid_map::GridMap& gridMap, + const std::string& elevationLayer) { + // Extract coordinates for signed distance field + Eigen::Vector3d minCoordinates; + Eigen::Vector3d maxCoordinates; + bool externalRangeGiven; + { + std::lock_guard lock(updateCoordinatesMutex_); + minCoordinates = minCoordinates_; + maxCoordinates = maxCoordinates_; + externalRangeGiven = externalCoordinatesGiven_; + } + + if (!externalRangeGiven) { + // Read min-max from elevation map + const float heightMargin = 0.1; + const auto& elevationData = gridMap.get(elevationLayer); + const float minValue = elevationData.minCoeffOfFinites() - heightMargin; + const float maxValue = elevationData.maxCoeffOfFinites() + heightMargin; + auto minXY = grid_map::lookup::projectToMapWithMargin( + gridMap, grid_map::Position(std::numeric_limits::lowest(), std::numeric_limits::lowest())); + auto maxXY = grid_map::lookup::projectToMapWithMargin( + gridMap, grid_map::Position(std::numeric_limits::max(), std::numeric_limits::max())); + minCoordinates = {minXY.x(), minXY.y(), minValue}; + maxCoordinates = {maxXY.x(), maxXY.y(), maxValue}; + }; + + return {minCoordinates, maxCoordinates}; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainVisualization.cpp b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainVisualization.cpp new file mode 100644 index 000000000..1f20ffd0e --- /dev/null +++ b/ocs2_robotic_examples/ocs2_perceptive_anymal/segmented_planes_terrain_model/src/SegmentedPlanesTerrainVisualization.cpp @@ -0,0 +1,39 @@ +// +// Created by rgrandia on 24.06.20. +// + +#include "segmented_planes_terrain_model/SegmentedPlanesTerrainVisualization.h" + +#include + +namespace switched_model { + +visualization_msgs::MarkerArray getConvexTerrainMarkers(const ConvexTerrain& convexTerrain, ocs2::Color color, double linewidth, + double normalLength) { + visualization_msgs::MarkerArray markerArray; + markerArray.markers.reserve(2); + + // Mark the surface normal + const vector3_t surfaceNormal = normalLength * surfaceNormalInWorld(convexTerrain.plane); + markerArray.markers.emplace_back(ocs2::getArrowAtPointMsg(surfaceNormal, convexTerrain.plane.positionInWorld, color)); + + // Polygon message + if (!convexTerrain.boundary.empty()) { + std::vector boundary; + boundary.reserve(convexTerrain.boundary.size() + 1); + for (const auto& point : convexTerrain.boundary) { + const auto& pointInWorldFrame = positionInWorldFrameFromPositionInTerrain({point.x(), point.y(), 0.0}, convexTerrain.plane); + boundary.emplace_back(ocs2::getPointMsg(pointInWorldFrame)); + } + // Close the polygon + const auto& pointInWorldFrame = positionInWorldFrameFromPositionInTerrain( + {convexTerrain.boundary.front().x(), convexTerrain.boundary.front().y(), 0.0}, convexTerrain.plane); + boundary.emplace_back(ocs2::getPointMsg(pointInWorldFrame)); + + markerArray.markers.emplace_back(ocs2::getLineMsg(std::move(boundary), color, linewidth)); + } + + return markerArray; +} + +} // namespace switched_model diff --git a/ocs2_robotic_examples/ocs2_robotic_examples/package.xml b/ocs2_robotic_examples/ocs2_robotic_examples/package.xml index 8aa431308..27cc79f14 100644 --- a/ocs2_robotic_examples/ocs2_robotic_examples/package.xml +++ b/ocs2_robotic_examples/ocs2_robotic_examples/package.xml @@ -22,6 +22,7 @@ ocs2_quadrotor_ros ocs2_mobile_manipulator ocs2_mobile_manipulator_ros + ocs2_anymal ocs2_legged_robot ocs2_legged_robot_ros xacro diff --git a/ocs2_sqp/ocs2_sqp/CMakeLists.txt b/ocs2_sqp/ocs2_sqp/CMakeLists.txt index 9bd34a16e..fae6f1ddf 100644 --- a/ocs2_sqp/ocs2_sqp/CMakeLists.txt +++ b/ocs2_sqp/ocs2_sqp/CMakeLists.txt @@ -50,6 +50,7 @@ include_directories( # Multiple shooting solver library add_library(${PROJECT_NAME} + src/SqpLogging.cpp src/SqpSettings.cpp src/SqpSolver.cpp ) diff --git a/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpLogging.h b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpLogging.h new file mode 100644 index 000000000..468a3592e --- /dev/null +++ b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpLogging.h @@ -0,0 +1,147 @@ +/****************************************************************************** +Copyright (c) 2020, Farbod Farshidian. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +******************************************************************************/ + +#pragma once + +#include +#include + +#include + +#include + +#include "ocs2_sqp/SqpSolverStatus.h" + +namespace ocs2 { +namespace sqp { + +struct LogEntry { + // Problem info + size_t problemNumber = 0; + scalar_t time = 0.0; // horizon start time for the currently solved problem + + // Iteration info + size_t iteration = 0; + + // Computation time + scalar_t linearQuadraticApproximationTime = 0.0; + scalar_t solveQpTime = 0.0; + scalar_t linesearchTime = 0.0; + + // Line search + PerformanceIndex baselinePerformanceIndex; // before taking the step + scalar_t totalConstraintViolationBaseline; // constraint metric used in the line search + StepInfo stepInfo; + + // Convergence + Convergence convergence = Convergence::FALSE; +}; + +std::ostream& operator<<(std::ostream& stream, const LogEntry& logEntry); + +std::string logHeader(); + +template +class Logger { + public: + explicit Logger(size_t numberOfEntries); + + T& currentEntry(); + + void advance(); + + void write(std::ostream& stream) const; + + private: + using const_iterator = typename std::vector::const_iterator; + using iterator = typename std::vector::iterator; + + bool full_; + const_iterator front_; + iterator back_; + std::vector data_; +}; + +template +Logger::Logger(size_t numberOfEntries) + : full_(false), + data_(numberOfEntries + 1, T()) // +1 so we have space for a new element to write to when full. +{ + front_ = data_.begin(); + back_ = data_.begin(); +} + +template +T& Logger::currentEntry() { + return *back_; +} + +template +void Logger::advance() { + // move current entry iterator + ++back_; + + // Wrap back pointer + if (back_ == data_.end()) { + back_ = data_.begin(); + full_ = true; + } + + // Move (+wrap) front point + if (full_) { + ++front_; + if (front_ == data_.end()) { + front_ = data_.begin(); + } + } +} + +template +void Logger::write(std::ostream& stream) const { + const_iterator writeIt = front_; + + if (writeIt > back_) { + // write front -> end + while (writeIt != data_.end()) { + stream << *writeIt; + ++writeIt; + } + // wrap around + writeIt = data_.cbegin(); + } + + // write front -> back + while (writeIt < back_) { + stream << *writeIt; + ++writeIt; + } +} + +} // namespace sqp +} // namespace ocs2 \ No newline at end of file diff --git a/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSettings.h b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSettings.h index b6f84e6c7..a9570edf6 100644 --- a/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSettings.h +++ b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSettings.h @@ -76,6 +76,11 @@ struct Settings { bool printSolverStatistics = false; // Print benchmarking of the multiple shooting method bool printLinesearch = false; // Print linesearch information + // Logging + bool enableLogging = true; + size_t logSize = 1000; // the of the last N iterations will be stored + std::string logFilePath = "/tmp/ocs2/sqp_log/"; // Folder the log will be written to + // Threading size_t nThreads = 4; int threadPriority = 50; diff --git a/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSolver.h b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSolver.h index 0247a5473..b2f8b269b 100644 --- a/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSolver.h +++ b/ocs2_sqp/ocs2_sqp/include/ocs2_sqp/SqpSolver.h @@ -42,6 +42,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include +#include "ocs2_sqp/SqpLogging.h" #include "ocs2_sqp/SqpSettings.h" #include "ocs2_sqp/SqpSolverStatus.h" @@ -185,7 +186,9 @@ class SqpSolver : public SolverBase { ProblemMetrics problemMetrics_; // Benchmarking + size_t numProblems_{0}; size_t totalNumIterations_{0}; + sqp::Logger logger_; benchmark::RepeatedTimer initializationTimer_; benchmark::RepeatedTimer linearQuadraticApproximationTimer_; benchmark::RepeatedTimer solveQpTimer_; diff --git a/ocs2_sqp/ocs2_sqp/logging/.gitignore b/ocs2_sqp/ocs2_sqp/logging/.gitignore new file mode 100644 index 000000000..ac95f4ecc --- /dev/null +++ b/ocs2_sqp/ocs2_sqp/logging/.gitignore @@ -0,0 +1,4 @@ +.idea/ + +# virtualenv +venv/ \ No newline at end of file diff --git a/ocs2_sqp/ocs2_sqp/logging/ReadSqpLog.py b/ocs2_sqp/ocs2_sqp/logging/ReadSqpLog.py new file mode 100644 index 000000000..d3d9632b9 --- /dev/null +++ b/ocs2_sqp/ocs2_sqp/logging/ReadSqpLog.py @@ -0,0 +1,152 @@ +import pandas as pd +import numpy as np +import matplotlib.pyplot as plt +from matplotlib import rc +import itertools + +if __name__ == "__main__": + # ===== Settings ======= + fileName = "/tmp/ocs2/sqp_log/log_Wed_Jan_19_10:02:29_2022.txt" + + lineWidth = 1.0 + # ====================== + rc('text', usetex=True) + plt.rcParams['text.latex.preamble'].join([ + r'\usepackage{tgheros}', # helvetica font + r'\usepackage{sansmath}', # math-font matching helvetica + r'\sansmath' # actually tell tex to use it! + r'\usepackage{siunitx}', # micro symbols + r'\sisetup{detect-all}', # force siunitx to use the fonts + ]) + + # Read the log + data = pd.read_csv(fileName, sep=r'\s*,\s*',) + data['global_iteration'] = data.index + firstIterations = data.groupby('problemNumber').first().reset_index() + lastIterations = data.groupby('problemNumber').last().reset_index() + + # Detect if we have multiple iterations per problem + multiIterationPlots = len(data) > len(firstIterations) + + # plot iterations + if multiIterationPlots: + fig1, ax1 = plt.subplots() + ax1.plot(lastIterations['problemNumber'], 1 + lastIterations['iteration'], linewidth=lineWidth) + plt.ylabel('Number of iterations') + plt.xlabel('Problem number') + + # plot constraint satisfaction per problem + fig1, ax1 = plt.subplots() + ax1.semilogy(firstIterations['problemNumber'], firstIterations['totalConstraintViolationBaseline'], linewidth=lineWidth, label='initialization') + ax1.semilogy(lastIterations['problemNumber'], lastIterations['totalConstraintViolationAfterStep'], linewidth=lineWidth, label='optimized') + plt.ylabel('Constraint violation norm') + plt.xlabel('Problem number') + ax1.legend() + + if multiIterationPlots: + # plot constraint satisfaction per iteration + fig1, ax1 = plt.subplots() + ax1.semilogy(data['global_iteration'], data['totalConstraintViolationAfterStep'], linewidth=lineWidth, label='after iteration') + ax1.scatter(firstIterations['global_iteration'], firstIterations['totalConstraintViolationBaseline'], marker='.', label='initialization') + ax1.scatter(lastIterations['global_iteration'], lastIterations['totalConstraintViolationAfterStep'], marker='.', label='optimized') + plt.ylabel('Constraint violation norm') + plt.xlabel('Iteration') + ax1.legend() + + # plot Merit satisfaction per problem + fig1, ax1 = plt.subplots() + ax1.plot(firstIterations['problemNumber'], firstIterations['baselinePerformanceIndex/merit'], linewidth=lineWidth, label='initialization') + ax1.plot(lastIterations['problemNumber'], lastIterations['performanceAfterStep/merit'], linewidth=lineWidth, label='optimized') + plt.ylabel('Merit value') + plt.xlabel('Problem number') + ax1.legend() + + if multiIterationPlots: + # plot Merit satisfaction per iteration + fig1, ax1 = plt.subplots() + ax1.plot(data['global_iteration'], data['performanceAfterStep/merit'], linewidth=lineWidth, label='after iteration') + ax1.scatter(firstIterations['global_iteration'], firstIterations['baselinePerformanceIndex/merit'], marker='.', label='initialization') + ax1.scatter(lastIterations['global_iteration'], lastIterations['performanceAfterStep/merit'], marker='.', label='optimized') + plt.ylabel('Merit value') + plt.xlabel('Iteration') + ax1.legend() + + # plot primal update + fig1, ax1 = plt.subplots() + ax1.semilogy(data['global_iteration'], data['dxNorm'], linewidth=lineWidth, label='|dx(t)|') + ax1.semilogy(data['global_iteration'], data['duNorm'], linewidth=lineWidth, label='|du(t)|') + if multiIterationPlots: + ax1.scatter(firstIterations['global_iteration'], firstIterations['dxNorm'], marker='.', label='|dx(t)| (first iter)') + ax1.scatter(firstIterations['global_iteration'], firstIterations['duNorm'], marker='.', label='|du(t)| (first iter)') + plt.ylabel('Primal update norm') + plt.xlabel('Iteration') + ax1.legend() + + # plot step size and type + fig1, ax1 = plt.subplots() + marker = itertools.cycle(('.', 'v', 'p', 'x', '*')) + # ax1.plot(data['global_iteration'], data['stepSize'], linewidth=lineWidth, label='step size') + for name, group in data.groupby('stepType'): + ax1.scatter(group['global_iteration'], group['stepSize'], marker=next(marker), label=name) + plt.ylabel('Step size') + plt.xlabel('Iteration') + ax1.legend() + + # Termination condition + if multiIterationPlots: + fig1, ax1 = plt.subplots() + ax1.plot(lastIterations['problemNumber'], lastIterations['convergence'], linewidth=lineWidth) + plt.title('Convergence condition') + plt.xlabel('Problem number') + + # Computation times + fig1, ax1 = plt.subplots() + ax1.plot(data['global_iteration'], data['linearQuadraticApproximationTime'], linewidth=lineWidth, label='LQ approximation') + ax1.plot(data['global_iteration'], data['solveQpTime'], linewidth=lineWidth, label='QP solve') + ax1.plot(data['global_iteration'], data['linesearchTime'], linewidth=lineWidth, label='Linesearch') + ax1.plot(data['global_iteration'], data['linearQuadraticApproximationTime'] + data['solveQpTime'] + data['linesearchTime'], linewidth=lineWidth, label='Total') + plt.ylabel('CPU time [ms]') + plt.xlabel('Problem number') + ax1.legend() + + # Problem init time + fig1, ax1 = plt.subplots() + ax1.plot(firstIterations['global_iteration'], firstIterations['time'], linewidth=lineWidth, marker='.', label='t0') + plt.ylabel('t0 [s]') + plt.xlabel('Problem number') + ax1.legend() + + # Cost - constraints - stepsize when using realtime iteration + if not multiIterationPlots: + fig, (ax1, ax2, ax3) = plt.subplots(3, 1, sharex=True) + + ax1.plot(lastIterations['time'], lastIterations['performanceAfterStep/merit'], linewidth=lineWidth) + ax1.set_ylabel('Cost') + ax1.grid(linestyle=':') + + ax2.semilogy(lastIterations['time'], lastIterations['totalConstraintViolationAfterStep'], linewidth=lineWidth) + ax2.set_ylabel('Constraint violation') + ax2.set_yticks(np.logspace(-6, 0, num=4)) + ax2.grid(linestyle=':') + + marker = itertools.cycle(('v', '^', 'x', '*')) + offset = itertools.cycle((0.05, -0.05, 0.0, 0.0)) + # ax1.plot(data['global_iteration'], data['stepSize'], linewidth=lineWidth, label='step size') + for name, group in data.groupby('stepType'): + ax3.scatter(group['time'], group['stepSize'] + next(offset), marker=next(marker), label=name, alpha=0.7) + ax3.set_ylim(0.0, 1.15) + ax3.set_ylabel('Step size') + ax3.set_xlabel('time [s]') + ax3.set_yticks([0.0, 0.25, 0.5, 1.0]) + ax3.legend() + ax3.grid(linestyle=':') + + fig.align_ylabels() + + plt.show() + + + + + + diff --git a/ocs2_sqp/ocs2_sqp/src/SqpLogging.cpp b/ocs2_sqp/ocs2_sqp/src/SqpLogging.cpp new file mode 100644 index 000000000..d3fc79863 --- /dev/null +++ b/ocs2_sqp/ocs2_sqp/src/SqpLogging.cpp @@ -0,0 +1,94 @@ +/****************************************************************************** +Copyright (c) 2020, Farbod Farshidian. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +******************************************************************************/ + +#include "ocs2_sqp/SqpLogging.h" + +#include + +namespace ocs2 { +namespace sqp { + +std::ostream& operator<<(std::ostream& stream, const LogEntry& logEntry) { + const std::string delim = ", "; + const std::string lineEnd = "\n"; + // clang-format off + stream << std::setprecision(16) // print decimals up to machine epsilon of double (~10^-16) + << logEntry.problemNumber << delim + << logEntry.time << delim + << logEntry.iteration << delim + << logEntry.linearQuadraticApproximationTime << delim + << logEntry.solveQpTime << delim + << logEntry.linesearchTime << delim + << logEntry.baselinePerformanceIndex.merit << delim + << logEntry.baselinePerformanceIndex.dynamicsViolationSSE << delim + << logEntry.baselinePerformanceIndex.equalityConstraintsSSE << delim + << logEntry.totalConstraintViolationBaseline << delim + << logEntry.stepInfo.stepSize << delim + << toString(logEntry.stepInfo.stepType) << delim + << logEntry.stepInfo.dx_norm << delim + << logEntry.stepInfo.du_norm << delim + << logEntry.stepInfo.performanceAfterStep.merit << delim + << logEntry.stepInfo.performanceAfterStep.dynamicsViolationSSE << delim + << logEntry.stepInfo.performanceAfterStep.equalityConstraintsSSE << delim + << logEntry.stepInfo.totalConstraintViolationAfterStep << delim + << toString(logEntry.convergence) << lineEnd; + // clang-format on + return stream; +} + +std::string logHeader() { + const std::string delim = ", "; + const std::string lineEnd = "\n"; + std::stringstream stream; + // clang-format off + stream << "problemNumber" << delim + << "time" << delim + << "iteration" << delim + << "linearQuadraticApproximationTime" << delim + << "solveQpTime" << delim + << "linesearchTime" << delim + << "baselinePerformanceIndex/merit" << delim + << "baselinePerformanceIndex/dynamicsViolationSSE" << delim + << "baselinePerformanceIndex/equalityConstraintsSSE" << delim + << "totalConstraintViolationBaseline" << delim + << "stepSize" << delim + << "stepType" << delim + << "dxNorm" << delim + << "duNorm" << delim + << "performanceAfterStep/merit" << delim + << "performanceAfterStep/dynamicsViolationSSE" << delim + << "performanceAfterStep/equalityConstraintsSSE" << delim + << "totalConstraintViolationAfterStep" << delim + << "convergence" << lineEnd; + // clang-format on + return stream.str(); +} + +} // namespace sqp +} // namespace ocs2 diff --git a/ocs2_sqp/ocs2_sqp/src/SqpSettings.cpp b/ocs2_sqp/ocs2_sqp/src/SqpSettings.cpp index 0160c921b..e19de6ad9 100644 --- a/ocs2_sqp/ocs2_sqp/src/SqpSettings.cpp +++ b/ocs2_sqp/ocs2_sqp/src/SqpSettings.cpp @@ -70,6 +70,9 @@ Settings loadSettings(const std::string& filename, const std::string& fieldName, loadData::loadPtreeValue(pt, settings.printSolverStatus, fieldName + ".printSolverStatus", verbose); loadData::loadPtreeValue(pt, settings.printSolverStatistics, fieldName + ".printSolverStatistics", verbose); loadData::loadPtreeValue(pt, settings.printLinesearch, fieldName + ".printLinesearch", verbose); + loadData::loadPtreeValue(pt, settings.enableLogging, fieldName + ".enableLogging", verbose); + loadData::loadPtreeValue(pt, settings.logSize, fieldName + ".logSize", verbose); + loadData::loadPtreeValue(pt, settings.logFilePath, fieldName + ".logFilePath", verbose); loadData::loadPtreeValue(pt, settings.nThreads, fieldName + ".nThreads", verbose); loadData::loadPtreeValue(pt, settings.threadPriority, fieldName + ".threadPriority", verbose); diff --git a/ocs2_sqp/ocs2_sqp/src/SqpSolver.cpp b/ocs2_sqp/ocs2_sqp/src/SqpSolver.cpp index 5e0e38379..26f3fd1f4 100644 --- a/ocs2_sqp/ocs2_sqp/src/SqpSolver.cpp +++ b/ocs2_sqp/ocs2_sqp/src/SqpSolver.cpp @@ -33,6 +33,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include + #include #include #include @@ -56,7 +58,8 @@ sqp::Settings rectifySettings(const OptimalControlProblem& ocp, sqp::Settings&& SqpSolver::SqpSolver(sqp::Settings settings, const OptimalControlProblem& optimalControlProblem, const Initializer& initializer) : settings_(rectifySettings(optimalControlProblem, std::move(settings))), hpipmInterface_(OcpSize(), settings_.hpipmSettings), - threadPool_(std::max(settings_.nThreads, size_t(1)) - 1, settings_.threadPriority) { + threadPool_(std::max(settings_.nThreads, size_t(1)) - 1, settings_.threadPriority), + logger_(settings_.logSize) { Eigen::setNbThreads(1); // No multithreading within Eigen. Eigen::initParallel(); @@ -83,6 +86,27 @@ SqpSolver::~SqpSolver() { if (settings_.printSolverStatistics) { std::cerr << getBenchmarkingInformation() << std::endl; } + + if (settings_.enableLogging) { + // Create the folder + boost::filesystem::create_directories(settings_.logFilePath); + + // Get current time + const auto t = std::chrono::high_resolution_clock::to_time_t(std::chrono::high_resolution_clock::now()); + std::string timeStamp = std::ctime(&t); + std::replace(timeStamp.begin(), timeStamp.end(), ' ', '_'); + timeStamp.erase(std::remove(timeStamp.begin(), timeStamp.end(), '\n'), timeStamp.end()); + + // Write to file + const std::string logFileName = settings_.logFilePath + "log_" + timeStamp + ".txt"; + if (std::ofstream logfile{logFileName}) { + logfile << sqp::logHeader(); + logger_.write(logfile); + std::cerr << "[SqpSolver] Log written to '" << logFileName << "'\n"; + } else { + std::cerr << "[SqpSolver] Unable to open '" << logFileName << "'\n"; + } + } } void SqpSolver::reset() { @@ -92,7 +116,9 @@ void SqpSolver::reset() { performanceIndeces_.clear(); // reset timers + numProblems_ = 0; totalNumIterations_ = 0; + logger_ = sqp::Logger(settings_.logSize); linearQuadraticApproximationTimer_.reset(); solveQpTimer_.reset(); linesearchTimer_.reset(); @@ -211,11 +237,29 @@ void SqpSolver::runImpl(scalar_t initTime, const vector_t& initState, scalar_t f // Check convergence convergence = checkConvergence(iter, baselinePerformance, stepInfo); + // Logging + if (settings_.enableLogging) { + auto& logEntry = logger_.currentEntry(); + logEntry.problemNumber = numProblems_; + logEntry.time = initTime; + logEntry.iteration = iter; + logEntry.linearQuadraticApproximationTime = linearQuadraticApproximationTimer_.getLastIntervalInMilliseconds(); + logEntry.solveQpTime = solveQpTimer_.getLastIntervalInMilliseconds(); + logEntry.linesearchTime = linesearchTimer_.getLastIntervalInMilliseconds(); + logEntry.baselinePerformanceIndex = baselinePerformance; + logEntry.totalConstraintViolationBaseline = FilterLinesearch::totalConstraintViolation(baselinePerformance); + logEntry.stepInfo = stepInfo; + logEntry.convergence = convergence; + logger_.advance(); + } + // Next iteration ++iter; ++totalNumIterations_; } + ++numProblems_; + computeControllerTimer_.startTimer(); primalSolution_ = toPrimalSolution(timeDiscretization, std::move(x), std::move(u)); problemMetrics_ = multiple_shooting::toProblemMetrics(timeDiscretization, std::move(metrics)); diff --git a/ocs2_sqp/ocs2_sqp/test/testLogging.cpp b/ocs2_sqp/ocs2_sqp/test/testLogging.cpp new file mode 100644 index 000000000..84f41922e --- /dev/null +++ b/ocs2_sqp/ocs2_sqp/test/testLogging.cpp @@ -0,0 +1,50 @@ +/****************************************************************************** +Copyright (c) 2020, Farbod Farshidian. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +******************************************************************************/ + +#include + +#include "ocs2_sqp/SqpLogging.h" + +using namespace ocs2; + +TEST(test_logging, wrap_around) { + const int Ntest = 3; + sqp::Logger logger(Ntest); + + std::stringstream stream; + + for (int i = 0; i < (2 * Ntest + 1); ++i) { + logger.write(stream); + + logger.currentEntry() = i; + logger.advance(); + } + + ASSERT_EQ(stream.str(), std::string("0") + "01" + "012" + "123" + "234" + "345"); +}