diff --git a/clik/clik.py b/clik/clik.py index 38a3b7e9de5266c0791ecd722131ba0108f788e2..6daff4a7d877228e1de5ef9ea84e8cceb644b836 100644 --- a/clik/clik.py +++ b/clik/clik.py @@ -66,7 +66,7 @@ Mtool = data.oMi[JOINT_ID] print("pos", Mtool) #SEerror = pin.SE3(np.zeros((3,3)), np.array([0.0, 0.0, 0.1]) Mgoal = copy.deepcopy(Mtool) -Mgoal.translation = Mgoal.translation + np.array([-0.1, 0.0, 0.0]) +Mgoal.translation = Mgoal.translation + np.array([0.0, 0.0, -0.1]) print("goal", Mgoal) eps = 1e-3 IT_MAX = 100000 @@ -81,6 +81,7 @@ rtde_io.setSpeedSlider(0.5) # if you just stop it normally, it will continue running # the last speedj lmao +# there's also an actual stop command def handler(signum, frame): print('sending 100 speedjs full of zeros') for i in range(100): diff --git a/dmp/my_sol/drawing_gen/cliking_the_path.py b/dmp/my_sol/drawing_gen/cliking_the_path.py index d0b4e926c5fdf68bc9192f64b4bcdbd1d16197e3..01d274b30f9533af1b309d49d0cbb2b952261a1b 100644 --- a/dmp/my_sol/drawing_gen/cliking_the_path.py +++ b/dmp/my_sol/drawing_gen/cliking_the_path.py @@ -62,9 +62,17 @@ path[:,1] = -1 * path[:,1] + board_height #R = np.array([[ 1. , 0. , 0.1496001 ], # [ 0. , -0.71010996, 0.68801429], # [ 0. , -0.68801429, -0.71010996]]) -R = np.array([[1., 0., 0.03236534], -[ 0., -0.82404727, 0.56559577], -[ 0. , -0.56559577, -0.82404727]]) +#R = np.array([[1., 0., 0.03236534], +#[ 0., -0.82404727, 0.56559577], +#[ 0. , -0.56559577, -0.82404727]]) +#R = np.array([[1., 0. , 0.02588808], +#[ 0., -0.82340404 , 0.56686471], +#[ 0. , -0.56686471 ,-0.82340404]]) + +R = np.array([[1. , 0. , 0.02562061], +[ 0. , -0.82215985 , 0.56867984], +[ 0. , -0.56867984 ,-0.82215985]]) + print(R) @@ -74,7 +82,8 @@ transf_body_to_board = pin.SE3(R, p) # offset in z # very close #path = path + np.array([0.0, 0.0, -0.0238]) -path = path + np.array([0.0, 0.0, -0.1038]) +path = path + np.array([0.0, 0.0, -0.0938]) +#path = path + np.array([0.0, 0.0, -0.1248]) #path = path + np.array([0.0, 0.2, -0.1438]) for i in range(len(path)): @@ -96,7 +105,8 @@ eps = 10**-2 dt = 0.01 # skip inital pos tho #q = np.array([-2.256,-1.408,0.955,-1.721,-1.405,-0.31, 0.0, 0.0]) -q = np.array([-2.014, -1.469, 1.248, -1.97, -1.366, -0.327, 0.0, 0.0]) +#q = np.array([-2.014, -1.469, 1.248, -1.97, -1.366, -0.327, 0.0, 0.0]) +q = np.array([1.584, -1.859, -0.953, -1.309, 1.578, -0.006, 0.0, 0.0]) INIT_ITER = 10000 n_iter = INIT_ITER RUNNING_ITER = 1000 diff --git a/dmp/my_sol/drawing_gen/path_in_pixels.csv b/dmp/my_sol/drawing_gen/path_in_pixels.csv index 2b2f9c6b30775c93e4fc2ebcbeb5d170893eb005..50cb59133242c933a0765c8083781b061eaf0076 100644 --- a/dmp/my_sol/drawing_gen/path_in_pixels.csv +++ b/dmp/my_sol/drawing_gen/path_in_pixels.csv @@ -1,62 +1,327 @@ -0.14553,0.49903 -0.14763,0.49903 -0.14973,0.49903 -0.15183,0.49903 -0.16024,0.49903 -0.16654,0.49903 -0.17495,0.49903 -0.19176,0.49903 -0.19807,0.49903 -0.22118,0.49903 -0.22328,0.49903 -0.22749,0.49903 -0.24010,0.49903 -0.24850,0.49903 -0.25271,0.49903 -0.27372,0.49903 -0.27582,0.49903 -0.29894,0.49903 -0.30524,0.49903 -0.30945,0.49903 -0.31785,0.49903 -0.33677,0.49903 -0.34097,0.49903 -0.35568,0.49903 -0.37459,0.49903 -0.38090,0.49903 -0.41032,0.49903 -0.41662,0.49903 -0.42293,0.49903 -0.42713,0.49903 -0.45025,0.49903 -0.45655,0.49903 -0.47967,0.49903 -0.48387,0.49903 -0.49228,0.49903 -0.49648,0.49903 -0.50699,0.50202 -0.51960,0.50202 -0.54271,0.50202 -0.54902,0.50202 -0.56793,0.50202 -0.60156,0.50649 -0.60786,0.50649 -0.63518,0.50649 -0.64989,0.51097 -0.67090,0.51097 -0.71714,0.51545 -0.73185,0.51993 -0.76547,0.51993 -0.79489,0.52441 -0.80330,0.52441 -0.80960,0.52441 -0.83272,0.52739 -0.84113,0.52739 -0.84533,0.52739 -0.86634,0.52739 -0.86845,0.52739 -0.87685,0.53038 -0.88105,0.53038 -0.89577,0.53038 -0.90207,0.53038 -0.90207,0.53038 +0.30482,0.61994 +0.30334,0.61994 +0.30186,0.62144 +0.29891,0.62442 +0.29595,0.62890 +0.29299,0.63189 +0.28263,0.64383 +0.27227,0.65278 +0.26635,0.65726 +0.26191,0.66174 +0.25747,0.66323 +0.25155,0.66920 +0.24711,0.67368 +0.24416,0.67518 +0.23972,0.68115 +0.23824,0.68264 +0.23676,0.68562 +0.23528,0.69309 +0.23380,0.69757 +0.23380,0.70503 +0.23380,0.71249 +0.23380,0.71697 +0.23528,0.72444 +0.24120,0.74534 +0.24711,0.75429 +0.25747,0.76773 +0.26339,0.77370 +0.26783,0.77967 +0.27967,0.78713 +0.28559,0.79460 +0.29003,0.79758 +0.30038,0.80803 +0.30926,0.81549 +0.32998,0.82594 +0.33886,0.82893 +0.34478,0.83042 +0.35661,0.83341 +0.36253,0.83341 +0.36993,0.83341 +0.38325,0.83341 +0.39657,0.83192 +0.40249,0.83042 +0.41432,0.82744 +0.41728,0.82594 +0.42172,0.82445 +0.42912,0.81997 +0.43060,0.81848 +0.43356,0.81549 +0.44244,0.80803 +0.44984,0.79609 +0.45280,0.78863 +0.45576,0.77668 +0.45872,0.76773 +0.46168,0.75877 +0.46463,0.74683 +0.46759,0.72891 +0.46907,0.72444 +0.46907,0.72145 +0.46907,0.71548 +0.46907,0.71249 +0.46907,0.70652 +0.46907,0.70354 +0.46907,0.69906 +0.46907,0.69757 +0.46907,0.69607 +0.46907,0.69458 +0.46759,0.69607 +0.46463,0.70354 +0.46315,0.70951 +0.46020,0.72294 +0.46315,0.73936 +0.47647,0.75877 +0.47647,0.76026 +0.47795,0.76176 +0.47795,0.76325 +0.47943,0.76474 +0.52826,0.78116 +0.55934,0.78713 +0.57561,0.79161 +0.58005,0.79310 +0.58153,0.79310 +0.58301,0.79310 +0.58597,0.79310 +0.62149,0.78713 +0.65108,0.78265 +0.65552,0.78265 +0.66440,0.77818 +0.67624,0.77370 +0.69843,0.76474 +0.71027,0.75877 +0.72359,0.75280 +0.72951,0.75131 +0.73247,0.74832 +0.74134,0.74235 +0.74726,0.73787 +0.75318,0.73041 +0.76354,0.70951 +0.76798,0.69607 +0.76946,0.68712 +0.76946,0.66920 +0.76798,0.66174 +0.76502,0.65129 +0.76058,0.63338 +0.75910,0.63189 +0.75910,0.63039 +0.75614,0.62741 +0.75022,0.62293 +0.74282,0.61994 +0.73542,0.61696 +0.71767,0.61248 +0.70879,0.61099 +0.69991,0.60949 +0.69695,0.60949 +0.69103,0.60949 +0.68511,0.60800 +0.67180,0.60502 +0.66736,0.60502 +0.65996,0.60502 +0.65700,0.60502 +0.65108,0.60502 +0.64516,0.60651 +0.63776,0.60800 +0.62001,0.61397 +0.61557,0.61397 +0.60965,0.61397 +0.60817,0.61397 +0.60521,0.61397 +0.60373,0.61397 +0.60817,0.61248 +0.61853,0.60949 +0.63332,0.60352 +0.64516,0.60054 +0.65700,0.59606 +0.67032,0.59009 +0.69251,0.58113 +0.70731,0.57217 +0.71767,0.56770 +0.73690,0.55874 +0.74578,0.55426 +0.75910,0.54680 +0.76502,0.54232 +0.77538,0.53486 +0.78130,0.53187 +0.79165,0.51993 +0.79609,0.50948 +0.80201,0.49455 +0.80497,0.48559 +0.80793,0.47067 +0.80793,0.46619 +0.80793,0.46320 +0.80793,0.45574 +0.80793,0.45425 +0.80497,0.45126 +0.80053,0.44380 +0.78130,0.42439 +0.76946,0.41693 +0.74726,0.40648 +0.73986,0.40349 +0.72951,0.40200 +0.72211,0.40200 +0.70583,0.40349 +0.69695,0.40648 +0.68067,0.40946 +0.67476,0.41245 +0.66440,0.41544 +0.66144,0.41693 +0.65700,0.41842 +0.65108,0.42141 +0.63924,0.42887 +0.63332,0.43186 +0.62001,0.43633 +0.60669,0.44230 +0.60225,0.44529 +0.59189,0.45126 +0.58893,0.45275 +0.57709,0.46470 +0.57265,0.46917 +0.56674,0.47664 +0.56230,0.48410 +0.54898,0.50351 +0.54750,0.50948 +0.54454,0.51844 +0.54454,0.51993 +0.54306,0.52590 +0.54306,0.53038 +0.54158,0.53933 +0.54158,0.54232 +0.54158,0.54381 +0.54158,0.54232 +0.54306,0.54083 +0.54602,0.53336 +0.56082,0.50202 +0.56378,0.48410 +0.56526,0.47664 +0.56674,0.46470 +0.56674,0.45425 +0.56082,0.42439 +0.55786,0.41096 +0.55046,0.39454 +0.54750,0.39006 +0.54158,0.38409 +0.53270,0.37364 +0.53122,0.37065 +0.52234,0.36170 +0.51790,0.35572 +0.51495,0.35572 +0.50163,0.34826 +0.49127,0.34528 +0.47055,0.34229 +0.46168,0.34229 +0.44984,0.34229 +0.44392,0.34378 +0.42764,0.34677 +0.42024,0.34826 +0.41284,0.35125 +0.39805,0.35423 +0.39213,0.35572 +0.38473,0.35722 +0.37881,0.36020 +0.37585,0.36170 +0.37141,0.36468 +0.36253,0.37364 +0.35513,0.38259 +0.34626,0.40648 +0.34626,0.41245 +0.34626,0.42141 +0.34922,0.43484 +0.35218,0.44230 +0.35365,0.45275 +0.35661,0.46022 +0.35957,0.47365 +0.36549,0.48709 +0.36993,0.49455 +0.37141,0.50052 +0.37289,0.50351 +0.37437,0.50649 +0.37585,0.50799 +0.37585,0.50500 +0.37141,0.48858 +0.36549,0.47067 +0.35809,0.45873 +0.34626,0.44380 +0.33590,0.43335 +0.31518,0.41693 +0.30926,0.41245 +0.29003,0.39752 +0.27967,0.39304 +0.26191,0.38707 +0.25303,0.38558 +0.23676,0.38409 +0.22788,0.38409 +0.20568,0.38409 +0.19384,0.38409 +0.17609,0.38558 +0.16869,0.38707 +0.16129,0.39006 +0.14797,0.39603 +0.13909,0.40200 +0.12430,0.41096 +0.11098,0.41842 +0.10358,0.42290 +0.09618,0.42887 +0.09174,0.43186 +0.08730,0.43783 +0.08139,0.44828 +0.07695,0.46320 +0.07547,0.46917 +0.07399,0.48559 +0.07399,0.49306 +0.07399,0.50202 +0.07547,0.50799 +0.07547,0.51097 +0.07843,0.51993 +0.08286,0.53038 +0.08730,0.53933 +0.09174,0.54978 +0.09322,0.55277 +0.09470,0.55426 +0.09766,0.55725 +0.09914,0.55874 +0.10210,0.56173 +0.10950,0.56620 +0.11542,0.57068 +0.12726,0.57964 +0.13318,0.58412 +0.13466,0.58561 +0.14205,0.59158 +0.14501,0.59457 +0.15685,0.60203 +0.16425,0.60800 +0.17165,0.61248 +0.17905,0.61546 +0.18201,0.61696 +0.18497,0.61845 +0.19384,0.62144 +0.19680,0.62293 +0.20124,0.62293 +0.20716,0.62293 +0.21012,0.62293 +0.21752,0.62293 +0.22196,0.62144 +0.22788,0.62144 +0.23232,0.62144 +0.23676,0.61994 +0.23972,0.61994 +0.25599,0.61994 +0.26191,0.61845 +0.26635,0.61845 +0.27523,0.61845 +0.27819,0.61696 +0.28263,0.61696 +0.28559,0.61696 +0.28707,0.61546 +0.29151,0.61546 +0.29447,0.61546 +0.29595,0.61397 +0.30038,0.61248 +0.30334,0.61248 +0.30482,0.61248 +0.30926,0.61099 +0.31074,0.60949 +0.31666,0.60800 +0.31814,0.60651 +0.31962,0.60651 +0.32110,0.60651 +0.32110,0.60502 +0.32110,0.60502 diff --git a/dmp/my_sol/new_traj.csv b/dmp/my_sol/new_traj.csv index e237258e2a55eeca04e27c386bc7e1b7826d8054..e66abd4e00f286573e1ae4449e41fffe9bde449d 100644 --- a/dmp/my_sol/new_traj.csv +++ b/dmp/my_sol/new_traj.csv @@ -1,241 +1,1086 @@ -0.00000,-2.21506,-1.66639,1.51913,-1.93538,-1.22877,-0.54469 -0.04167,-2.21583,-1.66605,1.51881,-1.93518,-1.22840,-0.54540 -0.08333,-2.21834,-1.66492,1.51777,-1.93453,-1.22719,-0.54768 -0.12500,-2.22061,-1.66389,1.51680,-1.93392,-1.22609,-0.54977 -0.16667,-2.22269,-1.66295,1.51590,-1.93335,-1.22509,-0.55168 -0.20833,-2.22458,-1.66210,1.51507,-1.93282,-1.22418,-0.55342 -0.25000,-2.22634,-1.66130,1.51429,-1.93231,-1.22333,-0.55504 -0.29167,-2.22825,-1.66042,1.51343,-1.93176,-1.22241,-0.55680 -0.33333,-2.23000,-1.65962,1.51263,-1.93124,-1.22157,-0.55841 -0.37500,-2.23046,-1.65941,1.51243,-1.93110,-1.22134,-0.55884 -0.41667,-2.23328,-1.65809,1.51114,-1.93029,-1.21999,-0.56144 -0.45833,-2.23584,-1.65688,1.50995,-1.92953,-1.21876,-0.56381 -0.50000,-2.23817,-1.65578,1.50885,-1.92882,-1.21764,-0.56597 -0.54167,-2.24030,-1.65477,1.50784,-1.92815,-1.21661,-0.56795 -0.58333,-2.24223,-1.65385,1.50690,-1.92754,-1.21568,-0.56975 -0.62500,-2.24400,-1.65301,1.50603,-1.92696,-1.21483,-0.57139 -0.66667,-2.24467,-1.65269,1.50569,-1.92673,-1.21451,-0.57202 -0.70833,-2.24603,-1.65203,1.50501,-1.92628,-1.21385,-0.57329 -0.75000,-2.24780,-1.65117,1.50413,-1.92570,-1.21301,-0.57494 -0.79167,-2.24869,-1.65074,1.50367,-1.92540,-1.21258,-0.57577 -0.83333,-2.25090,-1.64965,1.50256,-1.92469,-1.21152,-0.57783 -0.87500,-2.25291,-1.64865,1.50154,-1.92402,-1.21056,-0.57971 -0.91667,-2.25473,-1.64774,1.50059,-1.92340,-1.20968,-0.58143 -0.95833,-2.25645,-1.64688,1.49969,-1.92281,-1.20886,-0.58303 -1.00000,-2.25841,-1.64589,1.49866,-1.92215,-1.20792,-0.58487 -1.04167,-2.26020,-1.64498,1.49771,-1.92153,-1.20707,-0.58655 -1.08333,-2.26153,-1.64430,1.49699,-1.92106,-1.20643,-0.58781 -1.12500,-2.26326,-1.64341,1.49605,-1.92045,-1.20561,-0.58943 -1.16667,-2.26418,-1.64293,1.49555,-1.92013,-1.20517,-0.59030 -1.20833,-2.26679,-1.64156,1.49415,-1.91927,-1.20393,-0.59274 -1.25000,-2.26915,-1.64030,1.49286,-1.91847,-1.20281,-0.59496 -1.29167,-2.27131,-1.63915,1.49167,-1.91772,-1.20179,-0.59699 -1.33333,-2.27327,-1.63809,1.49056,-1.91702,-1.20086,-0.59884 -1.37500,-2.27506,-1.63713,1.48954,-1.91637,-1.20001,-0.60053 -1.41667,-2.27669,-1.63625,1.48859,-1.91576,-1.19924,-0.60208 -1.45833,-2.27794,-1.63556,1.48786,-1.91531,-1.19864,-0.60327 -1.50000,-2.28062,-1.63407,1.48634,-1.91439,-1.19739,-0.60579 -1.54167,-2.28305,-1.63270,1.48492,-1.91354,-1.19624,-0.60808 -1.58333,-2.28527,-1.63145,1.48362,-1.91274,-1.19520,-0.61018 -1.62500,-2.28728,-1.63031,1.48241,-1.91199,-1.19426,-0.61209 -1.66667,-2.28911,-1.62927,1.48129,-1.91130,-1.19339,-0.61383 -1.70833,-2.29078,-1.62831,1.48026,-1.91065,-1.19261,-0.61542 -1.75000,-2.29144,-1.62793,1.47985,-1.91040,-1.19230,-0.61605 -1.79167,-2.29322,-1.62690,1.47874,-1.90971,-1.19146,-0.61774 -1.83333,-2.29484,-1.62595,1.47772,-1.90908,-1.19070,-0.61929 -1.87500,-2.29517,-1.62576,1.47751,-1.90895,-1.19055,-0.61960 -1.91667,-2.29683,-1.62479,1.47645,-1.90830,-1.18977,-0.62119 -1.95833,-2.29765,-1.62430,1.47593,-1.90798,-1.18939,-0.62197 -2.00000,-2.29951,-1.62319,1.47475,-1.90727,-1.18852,-0.62374 -2.04167,-2.30121,-1.62217,1.47366,-1.90661,-1.18773,-0.62536 -2.08333,-2.30255,-1.62136,1.47278,-1.90608,-1.18710,-0.62665 -2.12500,-2.30492,-1.61991,1.47127,-1.90521,-1.18600,-0.62891 -2.16667,-2.30708,-1.61858,1.46987,-1.90439,-1.18500,-0.63096 -2.20833,-2.30904,-1.61736,1.46857,-1.90363,-1.18409,-0.63284 -2.25000,-2.31083,-1.61624,1.46738,-1.90292,-1.18327,-0.63455 -2.29167,-2.31245,-1.61522,1.46627,-1.90226,-1.18251,-0.63611 -2.33333,-2.31323,-1.61473,1.46573,-1.90194,-1.18215,-0.63686 -2.37500,-2.31484,-1.61371,1.46462,-1.90128,-1.18140,-0.63841 -2.41667,-2.31567,-1.61318,1.46405,-1.90094,-1.18102,-0.63921 -2.45833,-2.31779,-1.61182,1.46261,-1.90012,-1.18005,-0.64124 -2.50000,-2.31972,-1.61056,1.46127,-1.89936,-1.17916,-0.64309 -2.54167,-2.32148,-1.60942,1.46004,-1.89864,-1.17835,-0.64478 -2.58333,-2.32308,-1.60837,1.45889,-1.89797,-1.17762,-0.64632 -2.62500,-2.32392,-1.60782,1.45829,-1.89763,-1.17723,-0.64713 -2.66667,-2.32621,-1.60629,1.45668,-1.89673,-1.17618,-0.64933 -2.70833,-2.32830,-1.60488,1.45519,-1.89589,-1.17523,-0.65134 -2.75000,-2.33020,-1.60360,1.45381,-1.89511,-1.17436,-0.65317 -2.79167,-2.33193,-1.60242,1.45253,-1.89439,-1.17357,-0.65484 -2.83333,-2.33350,-1.60135,1.45135,-1.89371,-1.17285,-0.65636 -2.87500,-2.33427,-1.60082,1.45077,-1.89338,-1.17250,-0.65710 -2.91667,-2.33593,-1.59967,1.44952,-1.89267,-1.17174,-0.65871 -2.95833,-2.33744,-1.59862,1.44836,-1.89200,-1.17105,-0.66018 -3.00000,-2.33788,-1.59832,1.44804,-1.89183,-1.17086,-0.66060 -3.04167,-2.34062,-1.59638,1.44602,-1.89075,-1.16962,-0.66324 -3.08333,-2.34311,-1.59460,1.44415,-1.88975,-1.16850,-0.66564 -3.12500,-2.34537,-1.59298,1.44241,-1.88881,-1.16748,-0.66783 -3.16667,-2.34743,-1.59149,1.44080,-1.88794,-1.16655,-0.66982 -3.20833,-2.34929,-1.59013,1.43932,-1.88712,-1.16571,-0.67164 -3.25000,-2.35099,-1.58888,1.43794,-1.88636,-1.16494,-0.67329 -3.29167,-2.35254,-1.58774,1.43667,-1.88565,-1.16424,-0.67480 -3.33333,-2.35343,-1.58708,1.43593,-1.88523,-1.16384,-0.67567 -3.37500,-2.35504,-1.58587,1.43460,-1.88450,-1.16311,-0.67725 -3.41667,-2.35652,-1.58477,1.43336,-1.88381,-1.16245,-0.67869 -3.45833,-2.35682,-1.58453,1.43311,-1.88367,-1.16231,-0.67899 -3.50000,-2.35843,-1.58332,1.43177,-1.88294,-1.16159,-0.68055 -3.54167,-2.35988,-1.58221,1.43053,-1.88225,-1.16094,-0.68198 -3.58333,-2.36018,-1.58198,1.43027,-1.88212,-1.16081,-0.68227 -3.62500,-2.36167,-1.58084,1.42900,-1.88142,-1.16014,-0.68373 -3.66667,-2.36248,-1.58021,1.42832,-1.88105,-1.15978,-0.68452 -3.70833,-2.36483,-1.57839,1.42637,-1.88005,-1.15874,-0.68680 -3.75000,-2.36696,-1.57672,1.42457,-1.87912,-1.15779,-0.68888 -3.79167,-2.36889,-1.57519,1.42291,-1.87824,-1.15693,-0.69077 -3.83333,-2.37065,-1.57379,1.42137,-1.87743,-1.15615,-0.69250 -3.87500,-2.37225,-1.57251,1.41994,-1.87667,-1.15544,-0.69407 -3.91667,-2.37371,-1.57134,1.41862,-1.87596,-1.15480,-0.69550 -3.95833,-2.37428,-1.57088,1.41810,-1.87568,-1.15454,-0.69606 -4.00000,-2.37583,-1.56961,1.41669,-1.87493,-1.15386,-0.69759 -4.04167,-2.37725,-1.56846,1.41539,-1.87423,-1.15323,-0.69898 -4.08333,-2.37762,-1.56815,1.41506,-1.87406,-1.15307,-0.69935 -4.12500,-2.37991,-1.56627,1.41303,-1.87304,-1.15206,-0.70159 -4.16667,-2.38198,-1.56454,1.41115,-1.87209,-1.15115,-0.70363 -4.20833,-2.38387,-1.56296,1.40941,-1.87119,-1.15033,-0.70548 -4.25000,-2.38558,-1.56151,1.40780,-1.87036,-1.14958,-0.70717 -4.29167,-2.38714,-1.56019,1.40631,-1.86959,-1.14889,-0.70871 -4.33333,-2.38855,-1.55897,1.40494,-1.86886,-1.14827,-0.71011 -4.37500,-2.38910,-1.55850,1.40440,-1.86858,-1.14803,-0.71065 -4.41667,-2.39052,-1.55727,1.40301,-1.86785,-1.14741,-0.71206 -4.45833,-2.39122,-1.55667,1.40232,-1.86749,-1.14710,-0.71275 -4.50000,-2.39282,-1.55528,1.40077,-1.86670,-1.14641,-0.71433 -4.54167,-2.39427,-1.55400,1.39933,-1.86595,-1.14578,-0.71577 -4.58333,-2.39535,-1.55305,1.39824,-1.86539,-1.14530,-0.71684 -4.62500,-2.39676,-1.55180,1.39683,-1.86466,-1.14469,-0.71824 -4.66667,-2.39744,-1.55116,1.39609,-1.86429,-1.14439,-0.71892 -4.70833,-2.39898,-1.54949,1.39413,-1.86339,-1.14372,-0.72044 -4.75000,-2.40038,-1.54796,1.39231,-1.86254,-1.14312,-0.72183 -4.79167,-2.40165,-1.54656,1.39063,-1.86175,-1.14256,-0.72310 -4.83333,-2.40230,-1.54585,1.38978,-1.86136,-1.14228,-0.72374 -4.87500,-2.40394,-1.54414,1.38780,-1.86043,-1.14158,-0.72537 -4.91667,-2.40542,-1.54257,1.38596,-1.85957,-1.14094,-0.72684 -4.95833,-2.40677,-1.54113,1.38426,-1.85876,-1.14035,-0.72819 -5.00000,-2.40810,-1.53973,1.38260,-1.85797,-1.13978,-0.72951 -5.04167,-2.41019,-1.53763,1.38024,-1.85687,-1.13889,-0.73157 -5.08333,-2.41208,-1.53570,1.37805,-1.85584,-1.13808,-0.73345 -5.12500,-2.41380,-1.53394,1.37602,-1.85488,-1.13735,-0.73516 -5.16667,-2.41536,-1.53233,1.37415,-1.85399,-1.13668,-0.73672 -5.20833,-2.41677,-1.53085,1.37241,-1.85315,-1.13607,-0.73813 -5.25000,-2.41806,-1.52949,1.37080,-1.85237,-1.13553,-0.73942 -5.29167,-2.41857,-1.52896,1.37017,-1.85206,-1.13531,-0.73993 -5.33333,-2.41995,-1.52751,1.36848,-1.85124,-1.13472,-0.74132 -5.37500,-2.42121,-1.52618,1.36691,-1.85048,-1.13418,-0.74258 -5.41667,-2.42153,-1.52585,1.36653,-1.85030,-1.13405,-0.74290 -5.45833,-2.42342,-1.52391,1.36433,-1.84926,-1.13324,-0.74479 -5.50000,-2.42514,-1.52213,1.36229,-1.84830,-1.13252,-0.74650 -5.54167,-2.42670,-1.52050,1.36040,-1.84740,-1.13185,-0.74807 -5.58333,-2.42812,-1.51900,1.35865,-1.84655,-1.13125,-0.74949 -5.62500,-2.42941,-1.51764,1.35704,-1.84577,-1.13071,-0.75079 -5.66667,-2.43013,-1.51682,1.35608,-1.84532,-1.13041,-0.75151 -5.70833,-2.43242,-1.51400,1.35277,-1.84390,-1.12945,-0.75379 -5.75000,-2.43448,-1.51141,1.34969,-1.84257,-1.12858,-0.75586 -5.79167,-2.43636,-1.50903,1.34684,-1.84132,-1.12780,-0.75774 -5.83333,-2.43805,-1.50685,1.34421,-1.84016,-1.12708,-0.75944 -5.87500,-2.43959,-1.50485,1.34176,-1.83907,-1.12644,-0.76099 -5.91667,-2.44099,-1.50301,1.33950,-1.83805,-1.12585,-0.76241 -5.95833,-2.44226,-1.50133,1.33741,-1.83710,-1.12532,-0.76369 -6.00000,-2.44340,-1.49979,1.33548,-1.83621,-1.12484,-0.76486 -6.04167,-2.44407,-1.49890,1.33436,-1.83570,-1.12456,-0.76553 -6.08333,-2.44530,-1.49730,1.33237,-1.83479,-1.12405,-0.76678 -6.12500,-2.44642,-1.49583,1.33054,-1.83394,-1.12358,-0.76792 -6.16667,-2.44674,-1.49543,1.33007,-1.83373,-1.12345,-0.76824 -6.20833,-2.44880,-1.49298,1.32720,-1.83245,-1.12260,-0.77031 -6.25000,-2.45067,-1.49072,1.32454,-1.83125,-1.12183,-0.77220 -6.29167,-2.45236,-1.48866,1.32207,-1.83013,-1.12113,-0.77391 -6.33333,-2.45390,-1.48676,1.31979,-1.82909,-1.12049,-0.77546 -6.37500,-2.45529,-1.48502,1.31767,-1.82811,-1.11992,-0.77688 -6.41667,-2.45655,-1.48343,1.31571,-1.82719,-1.11940,-0.77816 -6.45833,-2.45770,-1.48197,1.31390,-1.82634,-1.11892,-0.77933 -6.50000,-2.45806,-1.48146,1.31326,-1.82606,-1.11878,-0.77970 -6.54167,-2.45944,-1.47926,1.31049,-1.82488,-1.11821,-0.78111 -6.58333,-2.46069,-1.47725,1.30791,-1.82378,-1.11769,-0.78238 -6.62500,-2.46183,-1.47540,1.30553,-1.82275,-1.11722,-0.78354 -6.66667,-2.46286,-1.47371,1.30333,-1.82179,-1.11680,-0.78460 -6.70833,-2.46369,-1.47236,1.30159,-1.82102,-1.11646,-0.78545 -6.75000,-2.46535,-1.47001,1.29870,-1.81978,-1.11578,-0.78713 -6.79167,-2.46685,-1.46785,1.29603,-1.81861,-1.11517,-0.78866 -6.83333,-2.46820,-1.46588,1.29356,-1.81752,-1.11462,-0.79004 -6.87500,-2.46943,-1.46406,1.29126,-1.81650,-1.11412,-0.79130 -6.91667,-2.47055,-1.46239,1.28914,-1.81555,-1.11366,-0.79245 -6.95833,-2.47172,-1.46063,1.28690,-1.81456,-1.11319,-0.79365 -7.00000,-2.47416,-1.45696,1.28243,-1.81271,-1.11220,-0.79611 -7.04167,-2.47637,-1.45358,1.27827,-1.81098,-1.11132,-0.79835 -7.08333,-2.47836,-1.45049,1.27441,-1.80936,-1.11052,-0.80038 -7.12500,-2.48016,-1.44764,1.27083,-1.80784,-1.10979,-0.80222 -7.16667,-2.48179,-1.44502,1.26751,-1.80641,-1.10914,-0.80389 -7.20833,-2.48327,-1.44262,1.26443,-1.80508,-1.10854,-0.80541 -7.25000,-2.48461,-1.44041,1.26158,-1.80383,-1.10801,-0.80679 -7.29167,-2.48582,-1.43839,1.25893,-1.80266,-1.10752,-0.80804 -7.33333,-2.48692,-1.43653,1.25648,-1.80156,-1.10708,-0.80918 -7.37500,-2.48791,-1.43482,1.25420,-1.80054,-1.10668,-0.81021 -7.41667,-2.48868,-1.43345,1.25238,-1.79973,-1.10637,-0.81100 -7.45833,-2.48985,-1.43107,1.24919,-1.79840,-1.10590,-0.81221 -7.50000,-2.49090,-1.42888,1.24624,-1.79716,-1.10548,-0.81331 -7.54167,-2.49186,-1.42687,1.24350,-1.79599,-1.10510,-0.81430 -7.58333,-2.49273,-1.42502,1.24096,-1.79491,-1.10475,-0.81521 -7.62500,-2.49356,-1.42333,1.23866,-1.79392,-1.10442,-0.81608 -7.66667,-2.49546,-1.42024,1.23478,-1.79228,-1.10367,-0.81802 -7.70833,-2.49718,-1.41740,1.23117,-1.79075,-1.10299,-0.81979 -7.75000,-2.49874,-1.41479,1.22782,-1.78931,-1.10238,-0.82139 -7.79167,-2.50014,-1.41239,1.22471,-1.78796,-1.10182,-0.82284 -7.83333,-2.50142,-1.41018,1.22183,-1.78669,-1.10132,-0.82416 -7.87500,-2.50257,-1.40816,1.21915,-1.78551,-1.10087,-0.82536 -7.91667,-2.50361,-1.40629,1.21667,-1.78440,-1.10046,-0.82645 -7.95833,-2.50456,-1.40458,1.21436,-1.78337,-1.10009,-0.82744 -8.00000,-2.50517,-1.40345,1.21285,-1.78270,-1.09985,-0.82808 -8.04167,-2.50680,-1.40034,1.20880,-1.78102,-1.09921,-0.82975 -8.08333,-2.50827,-1.39749,1.20503,-1.77944,-1.09864,-0.83127 -8.12500,-2.50960,-1.39486,1.20153,-1.77797,-1.09812,-0.83265 -8.16667,-2.51080,-1.39244,1.19828,-1.77658,-1.09765,-0.83391 -8.20833,-2.51189,-1.39022,1.19527,-1.77528,-1.09722,-0.83504 -8.25000,-2.51288,-1.38818,1.19247,-1.77406,-1.09684,-0.83608 -8.29167,-2.51377,-1.38629,1.18987,-1.77293,-1.09649,-0.83701 -8.33333,-2.51458,-1.38456,1.18746,-1.77186,-1.09617,-0.83787 -8.37500,-2.51468,-1.38436,1.18719,-1.77174,-1.09613,-0.83798 -8.41667,-2.51569,-1.38239,1.18452,-1.77057,-1.09574,-0.83903 -8.45833,-2.51660,-1.38057,1.18204,-1.76947,-1.09539,-0.83998 -8.50000,-2.51737,-1.37903,1.17993,-1.76853,-1.09509,-0.84079 -8.54167,-2.51833,-1.37719,1.17744,-1.76743,-1.09472,-0.84180 -8.58333,-2.51920,-1.37549,1.17512,-1.76640,-1.09438,-0.84272 -8.62500,-2.51943,-1.37504,1.17452,-1.76614,-1.09429,-0.84296 -8.66667,-2.52085,-1.37225,1.17082,-1.76459,-1.09375,-0.84443 -8.70833,-2.52212,-1.36968,1.16739,-1.76314,-1.09326,-0.84575 -8.75000,-2.52328,-1.36731,1.16420,-1.76177,-1.09282,-0.84696 -8.79167,-2.52433,-1.36513,1.16123,-1.76049,-1.09241,-0.84806 -8.83333,-2.52527,-1.36313,1.15847,-1.75929,-1.09205,-0.84905 -8.87500,-2.52613,-1.36128,1.15591,-1.75817,-1.09172,-0.84996 -8.91667,-2.52678,-1.35987,1.15395,-1.75730,-1.09147,-0.85065 -8.95833,-2.52777,-1.35788,1.15124,-1.75611,-1.09109,-0.85169 -9.00000,-2.52867,-1.35604,1.14873,-1.75500,-1.09075,-0.85263 -9.04167,-2.52941,-1.35450,1.14659,-1.75405,-1.09047,-0.85342 -9.08333,-2.53029,-1.35273,1.14417,-1.75297,-1.09013,-0.85434 -9.12500,-2.53085,-1.35163,1.14267,-1.75231,-1.08992,-0.85493 -9.16667,-2.53227,-1.34907,1.13934,-1.75087,-1.08938,-0.85641 -9.20833,-2.53355,-1.34672,1.13623,-1.74952,-1.08890,-0.85775 -9.25000,-2.53471,-1.34455,1.13334,-1.74825,-1.08846,-0.85897 -9.29167,-2.53577,-1.34255,1.13065,-1.74706,-1.08806,-0.86007 -9.33333,-2.53672,-1.34071,1.12816,-1.74594,-1.08770,-0.86108 -9.37500,-2.53758,-1.33901,1.12583,-1.74489,-1.08737,-0.86199 -9.41667,-2.53775,-1.33868,1.12537,-1.74468,-1.08731,-0.86217 -9.45833,-2.53844,-1.33730,1.12348,-1.74383,-1.08705,-0.86290 -9.50000,-2.53935,-1.33519,1.12054,-1.74258,-1.08670,-0.86386 -9.54167,-2.54017,-1.33324,1.11781,-1.74139,-1.08639,-0.86473 -9.58333,-2.54092,-1.33145,1.11527,-1.74029,-1.08611,-0.86552 -9.62500,-2.54100,-1.33126,1.11501,-1.74017,-1.08608,-0.86561 -9.66667,-2.54180,-1.32941,1.11242,-1.73904,-1.08578,-0.86646 -9.70833,-2.54229,-1.32830,1.11087,-1.73836,-1.08559,-0.86698 -9.75000,-2.54343,-1.32596,1.10771,-1.73700,-1.08517,-0.86817 -9.79167,-2.54446,-1.32381,1.10476,-1.73572,-1.08478,-0.86926 -9.83333,-2.54539,-1.32182,1.10203,-1.73452,-1.08443,-0.87024 -9.87500,-2.54624,-1.31999,1.09948,-1.73339,-1.08412,-0.87114 -9.91667,-2.54680,-1.31876,1.09776,-1.73263,-1.08391,-0.87173 -9.95833,-2.54770,-1.31685,1.09514,-1.73147,-1.08357,-0.87269 -10.00000,-2.54852,-1.31510,1.09269,-1.73038,-1.08326,-0.87356 +0.00000,1.41594,-1.64387,-1.33067,-1.13806,1.65243,-0.12670 +0.00922,1.41755,-1.64484,-1.32855,-1.13909,1.65153,-0.12539 +0.01843,1.41901,-1.64574,-1.32659,-1.14004,1.65072,-0.12420 +0.02765,1.41949,-1.64603,-1.32595,-1.14035,1.65045,-0.12380 +0.03687,1.42150,-1.64716,-1.32344,-1.14159,1.64933,-0.12217 +0.04608,1.42332,-1.64820,-1.32113,-1.14274,1.64832,-0.12068 +0.05530,1.42497,-1.64916,-1.31898,-1.14381,1.64739,-0.11933 +0.06452,1.42647,-1.65005,-1.31701,-1.14480,1.64655,-0.11810 +0.07373,1.42735,-1.65057,-1.31586,-1.14538,1.64606,-0.11739 +0.08295,1.42904,-1.65150,-1.31376,-1.14645,1.64512,-0.11601 +0.09217,1.43057,-1.65235,-1.31182,-1.14743,1.64426,-0.11475 +0.10138,1.43146,-1.65286,-1.31069,-1.14801,1.64376,-0.11403 +0.11060,1.43308,-1.65380,-1.30858,-1.14908,1.64285,-0.11270 +0.11982,1.43456,-1.65467,-1.30663,-1.15007,1.64202,-0.11149 +0.12903,1.43514,-1.65499,-1.30589,-1.15046,1.64169,-0.11101 +0.13825,1.43671,-1.65576,-1.30409,-1.15140,1.64081,-0.10972 +0.14747,1.43749,-1.65614,-1.30319,-1.15188,1.64037,-0.10909 +0.15668,1.43926,-1.65707,-1.30106,-1.15298,1.63937,-0.10764 +0.16590,1.44087,-1.65793,-1.29908,-1.15401,1.63847,-0.10632 +0.17512,1.44237,-1.65875,-1.29722,-1.15498,1.63762,-0.10509 +0.18433,1.44401,-1.65967,-1.29513,-1.15606,1.63670,-0.10375 +0.19355,1.44550,-1.66053,-1.29320,-1.15706,1.63586,-0.10253 +0.20276,1.44607,-1.66086,-1.29246,-1.15745,1.63553,-0.10206 +0.21198,1.44756,-1.66165,-1.29063,-1.15841,1.63469,-0.10084 +0.22120,1.44788,-1.66184,-1.29022,-1.15862,1.63452,-0.10058 +0.23041,1.44953,-1.66285,-1.28797,-1.15977,1.63359,-0.09923 +0.23963,1.45102,-1.66380,-1.28589,-1.16083,1.63274,-0.09800 +0.24885,1.45213,-1.66450,-1.28433,-1.16163,1.63211,-0.09710 +0.25806,1.45324,-1.66523,-1.28273,-1.16245,1.63149,-0.09619 +0.26728,1.45462,-1.66623,-1.28060,-1.16353,1.63071,-0.09506 +0.27650,1.45502,-1.66656,-1.27990,-1.16387,1.63048,-0.09473 +0.28571,1.45639,-1.66794,-1.27713,-1.16520,1.62971,-0.09361 +0.29493,1.45763,-1.66921,-1.27457,-1.16644,1.62901,-0.09260 +0.30415,1.45855,-1.67018,-1.27260,-1.16738,1.62848,-0.09185 +0.31336,1.45972,-1.67155,-1.26988,-1.16868,1.62782,-0.09089 +0.32258,1.46068,-1.67275,-1.26752,-1.16980,1.62728,-0.09011 +0.33180,1.46171,-1.67444,-1.26429,-1.17129,1.62669,-0.08927 +0.34101,1.46264,-1.67600,-1.26130,-1.17267,1.62616,-0.08851 +0.35023,1.46341,-1.67736,-1.25871,-1.17386,1.62573,-0.08788 +0.35945,1.46425,-1.67921,-1.25525,-1.17543,1.62525,-0.08720 +0.36866,1.46500,-1.68092,-1.25204,-1.17689,1.62482,-0.08659 +0.37788,1.46569,-1.68254,-1.24902,-1.17827,1.62443,-0.08604 +0.38710,1.46634,-1.68431,-1.24573,-1.17975,1.62406,-0.08551 +0.39631,1.46687,-1.68584,-1.24289,-1.18103,1.62376,-0.08508 +0.40553,1.46738,-1.68791,-1.23912,-1.18270,1.62347,-0.08467 +0.41475,1.46784,-1.68983,-1.23563,-1.18425,1.62321,-0.08430 +0.42396,1.46825,-1.69159,-1.23240,-1.18570,1.62297,-0.08397 +0.43318,1.46827,-1.69193,-1.23181,-1.18594,1.62296,-0.08395 +0.44240,1.46846,-1.69514,-1.22617,-1.18834,1.62285,-0.08381 +0.45161,1.46863,-1.69811,-1.22094,-1.19057,1.62276,-0.08369 +0.46083,1.46877,-1.70085,-1.21609,-1.19266,1.62267,-0.08359 +0.47005,1.46889,-1.70338,-1.21160,-1.19461,1.62260,-0.08350 +0.47926,1.46900,-1.70571,-1.20743,-1.19643,1.62254,-0.08343 +0.48848,1.46909,-1.70787,-1.20357,-1.19813,1.62249,-0.08336 +0.49770,1.46916,-1.70986,-1.20000,-1.19971,1.62245,-0.08331 +0.50691,1.46918,-1.71107,-1.19785,-1.20066,1.62244,-0.08331 +0.51613,1.46896,-1.71359,-1.19343,-1.20255,1.62256,-0.08350 +0.52535,1.46876,-1.71592,-1.18934,-1.20431,1.62267,-0.08367 +0.53456,1.46858,-1.71808,-1.18554,-1.20596,1.62278,-0.08384 +0.54378,1.46840,-1.72007,-1.18202,-1.20750,1.62288,-0.08399 +0.55300,1.46832,-1.72057,-1.18115,-1.20787,1.62293,-0.08407 +0.56221,1.46767,-1.72357,-1.17601,-1.21002,1.62329,-0.08461 +0.57143,1.46707,-1.72635,-1.17124,-1.21203,1.62363,-0.08512 +0.58065,1.46653,-1.72891,-1.16681,-1.21391,1.62394,-0.08558 +0.58986,1.46602,-1.73128,-1.16270,-1.21567,1.62422,-0.08601 +0.59908,1.46556,-1.73347,-1.15888,-1.21731,1.62448,-0.08640 +0.60829,1.46514,-1.73550,-1.15534,-1.21885,1.62473,-0.08676 +0.61751,1.46502,-1.73595,-1.15457,-1.21918,1.62479,-0.08686 +0.62673,1.46435,-1.73836,-1.15043,-1.22093,1.62517,-0.08743 +0.63594,1.46373,-1.74058,-1.14659,-1.22258,1.62552,-0.08795 +0.64516,1.46317,-1.74264,-1.14302,-1.22411,1.62584,-0.08842 +0.65438,1.46288,-1.74367,-1.14124,-1.22488,1.62601,-0.08867 +0.66359,1.46218,-1.74603,-1.13718,-1.22660,1.62640,-0.08926 +0.67281,1.46154,-1.74822,-1.13341,-1.22821,1.62677,-0.08980 +0.68203,1.46096,-1.75024,-1.12991,-1.22972,1.62710,-0.09029 +0.69124,1.46078,-1.75071,-1.12911,-1.23006,1.62720,-0.09044 +0.70046,1.45965,-1.75337,-1.12465,-1.23190,1.62784,-0.09139 +0.70968,1.45861,-1.75583,-1.12050,-1.23363,1.62843,-0.09225 +0.71889,1.45767,-1.75811,-1.11664,-1.23525,1.62897,-0.09305 +0.72811,1.45680,-1.76022,-1.11306,-1.23677,1.62946,-0.09377 +0.73733,1.45598,-1.76224,-1.10961,-1.23824,1.62992,-0.09446 +0.74654,1.45499,-1.76472,-1.10540,-1.24000,1.63049,-0.09529 +0.75576,1.45409,-1.76702,-1.10148,-1.24165,1.63100,-0.09605 +0.76498,1.45327,-1.76915,-1.09784,-1.24321,1.63147,-0.09674 +0.77419,1.45249,-1.77116,-1.09440,-1.24468,1.63192,-0.09740 +0.78341,1.45158,-1.77331,-1.09074,-1.24623,1.63243,-0.09816 +0.79263,1.45074,-1.77530,-1.08735,-1.24768,1.63291,-0.09886 +0.80184,1.45053,-1.77578,-1.08652,-1.24802,1.63303,-0.09904 +0.81106,1.44931,-1.77861,-1.08178,-1.24999,1.63372,-0.10007 +0.82028,1.44818,-1.78122,-1.07736,-1.25184,1.63436,-0.10101 +0.82949,1.44716,-1.78365,-1.07324,-1.25358,1.63494,-0.10187 +0.83871,1.44623,-1.78589,-1.06941,-1.25521,1.63548,-0.10266 +0.84793,1.44537,-1.78797,-1.06585,-1.25674,1.63596,-0.10338 +0.85714,1.44477,-1.78942,-1.06337,-1.25781,1.63630,-0.10388 +0.86636,1.44362,-1.79201,-1.05899,-1.25964,1.63696,-0.10485 +0.87558,1.44257,-1.79441,-1.05491,-1.26137,1.63756,-0.10573 +0.88479,1.44161,-1.79664,-1.05111,-1.26299,1.63811,-0.10654 +0.89401,1.44073,-1.79870,-1.04757,-1.26452,1.63861,-0.10728 +0.90323,1.44005,-1.80019,-1.04503,-1.26560,1.63899,-0.10785 +0.91244,1.43826,-1.80329,-1.03993,-1.26768,1.64000,-0.10934 +0.92166,1.43663,-1.80616,-1.03517,-1.26964,1.64093,-0.11070 +0.93088,1.43515,-1.80883,-1.03073,-1.27149,1.64177,-0.11194 +0.94009,1.43379,-1.81131,-1.02659,-1.27323,1.64253,-0.11307 +0.94931,1.43256,-1.81360,-1.02272,-1.27487,1.64324,-0.11411 +0.95853,1.43143,-1.81574,-1.01912,-1.27641,1.64388,-0.11505 +0.96774,1.43041,-1.81772,-1.01575,-1.27786,1.64446,-0.11592 +0.97696,1.42988,-1.81870,-1.01408,-1.27858,1.64476,-0.11636 +0.98618,1.42853,-1.82092,-1.01039,-1.28013,1.64553,-0.11749 +0.99539,1.42730,-1.82298,-1.00694,-1.28159,1.64623,-0.11852 +1.00461,1.42618,-1.82489,-1.00373,-1.28297,1.64686,-0.11946 +1.01382,1.42563,-1.82582,-1.00216,-1.28364,1.64718,-0.11992 +1.02304,1.42435,-1.82780,-0.99888,-1.28502,1.64791,-0.12099 +1.03226,1.42318,-1.82963,-0.99582,-1.28633,1.64857,-0.12197 +1.04147,1.42279,-1.83021,-0.99486,-1.28673,1.64879,-0.12230 +1.05069,1.42115,-1.83241,-0.99130,-1.28819,1.64972,-0.12367 +1.05991,1.41965,-1.83445,-0.98797,-1.28958,1.65057,-0.12492 +1.06912,1.41829,-1.83635,-0.98486,-1.29088,1.65134,-0.12605 +1.07834,1.41705,-1.83811,-0.98195,-1.29211,1.65204,-0.12709 +1.08756,1.41678,-1.83846,-0.98137,-1.29235,1.65220,-0.12732 +1.09677,1.41536,-1.84023,-0.97851,-1.29354,1.65301,-0.12851 +1.10599,1.41401,-1.84190,-0.97581,-1.29467,1.65377,-0.12963 +1.11521,1.41243,-1.84363,-0.97307,-1.29579,1.65466,-0.13095 +1.12442,1.41099,-1.84524,-0.97051,-1.29685,1.65548,-0.13215 +1.13364,1.41025,-1.84603,-0.96924,-1.29736,1.65590,-0.13277 +1.14286,1.40829,-1.84784,-0.96650,-1.29844,1.65701,-0.13440 +1.15207,1.40650,-1.84951,-0.96393,-1.29946,1.65801,-0.13589 +1.16129,1.40487,-1.85107,-0.96153,-1.30043,1.65893,-0.13725 +1.17051,1.40339,-1.85252,-0.95927,-1.30134,1.65977,-0.13848 +1.17972,1.40304,-1.85282,-0.95882,-1.30152,1.65997,-0.13878 +1.18894,1.40099,-1.85441,-0.95650,-1.30240,1.66113,-0.14048 +1.19816,1.39913,-1.85588,-0.95433,-1.30324,1.66218,-0.14203 +1.20737,1.39743,-1.85725,-0.95229,-1.30403,1.66314,-0.14344 +1.21659,1.39589,-1.85853,-0.95038,-1.30479,1.66401,-0.14473 +1.22581,1.39571,-1.85866,-0.95020,-1.30486,1.66411,-0.14488 +1.23502,1.39398,-1.85989,-0.94843,-1.30553,1.66509,-0.14632 +1.24424,1.39235,-1.86105,-0.94677,-1.30617,1.66601,-0.14768 +1.25346,1.39026,-1.86223,-0.94521,-1.30671,1.66719,-0.14942 +1.26267,1.38836,-1.86333,-0.94375,-1.30722,1.66826,-0.15100 +1.27189,1.38663,-1.86436,-0.94237,-1.30772,1.66923,-0.15244 +1.28111,1.38550,-1.86503,-0.94147,-1.30805,1.66987,-0.15338 +1.29032,1.38383,-1.86591,-0.94034,-1.30844,1.67082,-0.15477 +1.29954,1.38208,-1.86675,-0.93932,-1.30877,1.67181,-0.15623 +1.30876,1.38106,-1.86721,-0.93877,-1.30894,1.67238,-0.15708 +1.31797,1.37911,-1.86784,-0.93819,-1.30906,1.67348,-0.15870 +1.32719,1.37733,-1.86843,-0.93764,-1.30918,1.67448,-0.16018 +1.33641,1.37634,-1.86876,-0.93734,-1.30925,1.67504,-0.16101 +1.34562,1.37532,-1.86902,-0.93716,-1.30926,1.67561,-0.16185 +1.35484,1.37360,-1.86933,-0.93711,-1.30916,1.67659,-0.16328 +1.36406,1.37305,-1.86939,-0.93717,-1.30910,1.67689,-0.16374 +1.37327,1.37096,-1.86938,-0.93780,-1.30866,1.67807,-0.16547 +1.38249,1.36907,-1.86938,-0.93839,-1.30826,1.67913,-0.16705 +1.39171,1.36734,-1.86938,-0.93892,-1.30789,1.68011,-0.16848 +1.40092,1.36648,-1.86931,-0.93931,-1.30766,1.68059,-0.16920 +1.41014,1.36443,-1.86867,-0.94112,-1.30670,1.68174,-0.17089 +1.41935,1.36257,-1.86806,-0.94280,-1.30582,1.68279,-0.17243 +1.42857,1.36088,-1.86751,-0.94436,-1.30499,1.68374,-0.17383 +1.43779,1.35935,-1.86699,-0.94580,-1.30423,1.68460,-0.17511 +1.44700,1.35903,-1.86684,-0.94617,-1.30404,1.68478,-0.17537 +1.45622,1.35740,-1.86592,-0.94838,-1.30293,1.68570,-0.17672 +1.46544,1.35592,-1.86506,-0.95043,-1.30189,1.68653,-0.17795 +1.47465,1.35480,-1.86433,-0.95212,-1.30105,1.68716,-0.17888 +1.48387,1.35324,-1.86281,-0.95540,-1.29947,1.68804,-0.18017 +1.49309,1.35181,-1.86140,-0.95845,-1.29799,1.68884,-0.18135 +1.50230,1.35052,-1.86008,-0.96128,-1.29661,1.68957,-0.18242 +1.51152,1.34935,-1.85887,-0.96392,-1.29533,1.69023,-0.18339 +1.52074,1.34899,-1.85846,-0.96478,-1.29491,1.69043,-0.18369 +1.52995,1.34767,-1.85680,-0.96825,-1.29324,1.69117,-0.18478 +1.53917,1.34648,-1.85526,-0.97148,-1.29168,1.69185,-0.18577 +1.54839,1.34539,-1.85384,-0.97448,-1.29023,1.69246,-0.18666 +1.55760,1.34457,-1.85271,-0.97684,-1.28909,1.69292,-0.18734 +1.56682,1.34337,-1.85092,-0.98054,-1.28732,1.69359,-0.18833 +1.57604,1.34229,-1.84925,-0.98398,-1.28567,1.69420,-0.18922 +1.58525,1.34130,-1.84771,-0.98717,-1.28413,1.69475,-0.19003 +1.59447,1.34046,-1.84633,-0.99000,-1.28276,1.69522,-0.19073 +1.60369,1.33932,-1.84424,-0.99423,-1.28075,1.69587,-0.19167 +1.61290,1.33828,-1.84230,-0.99816,-1.27888,1.69645,-0.19252 +1.62212,1.33734,-1.84050,-1.00181,-1.27714,1.69697,-0.19330 +1.63134,1.33648,-1.83883,-1.00520,-1.27551,1.69745,-0.19400 +1.64055,1.33574,-1.83731,-1.00828,-1.27403,1.69787,-0.19461 +1.64977,1.33461,-1.83471,-1.01343,-1.27162,1.69850,-0.19553 +1.65899,1.33359,-1.83229,-1.01822,-1.26937,1.69907,-0.19637 +1.66820,1.33266,-1.83005,-1.02266,-1.26728,1.69959,-0.19713 +1.67742,1.33182,-1.82798,-1.02678,-1.26532,1.70006,-0.19782 +1.68664,1.33106,-1.82606,-1.03061,-1.26349,1.70048,-0.19844 +1.69585,1.33037,-1.82428,-1.03416,-1.26179,1.70086,-0.19900 +1.70507,1.32980,-1.82276,-1.03719,-1.26034,1.70119,-0.19947 +1.71429,1.32909,-1.82096,-1.04078,-1.25861,1.70158,-0.20005 +1.72350,1.32844,-1.81929,-1.04412,-1.25701,1.70194,-0.20058 +1.73272,1.32831,-1.81895,-1.04480,-1.25668,1.70201,-0.20068 +1.74194,1.32770,-1.81722,-1.04823,-1.25504,1.70236,-0.20118 +1.75115,1.32746,-1.81652,-1.04961,-1.25438,1.70249,-0.20138 +1.76037,1.32683,-1.81456,-1.05346,-1.25257,1.70284,-0.20189 +1.76959,1.32626,-1.81274,-1.05703,-1.25088,1.70315,-0.20235 +1.77880,1.32590,-1.81152,-1.05941,-1.24974,1.70336,-0.20265 +1.78802,1.32538,-1.80972,-1.06293,-1.24808,1.70365,-0.20307 +1.79724,1.32512,-1.80883,-1.06467,-1.24725,1.70379,-0.20327 +1.80645,1.32458,-1.80682,-1.06857,-1.24543,1.70409,-0.20371 +1.81567,1.32410,-1.80495,-1.07218,-1.24373,1.70436,-0.20410 +1.82488,1.32378,-1.80371,-1.07459,-1.24259,1.70454,-0.20436 +1.83410,1.32333,-1.80188,-1.07814,-1.24092,1.70479,-0.20472 +1.84332,1.32311,-1.80098,-1.07988,-1.24010,1.70491,-0.20490 +1.85253,1.32265,-1.79904,-1.08361,-1.23836,1.70516,-0.20527 +1.86175,1.32224,-1.79725,-1.08707,-1.23674,1.70539,-0.20560 +1.87097,1.32220,-1.79706,-1.08742,-1.23657,1.70541,-0.20563 +1.88018,1.32188,-1.79565,-1.09015,-1.23529,1.70559,-0.20588 +1.88940,1.32161,-1.79440,-1.09254,-1.23417,1.70574,-0.20610 +1.89862,1.32137,-1.79347,-1.09439,-1.23326,1.70587,-0.20630 +1.90783,1.32164,-1.79641,-1.08929,-1.23530,1.70572,-0.20608 +1.91705,1.32188,-1.79913,-1.08453,-1.23721,1.70559,-0.20590 +1.92627,1.32209,-1.80165,-1.08011,-1.23902,1.70548,-0.20573 +1.93548,1.32227,-1.80398,-1.07600,-1.24071,1.70538,-0.20559 +1.94470,1.32243,-1.80615,-1.07218,-1.24230,1.70529,-0.20547 +1.95392,1.32257,-1.80815,-1.06862,-1.24379,1.70522,-0.20536 +1.96313,1.32259,-1.80835,-1.06826,-1.24394,1.70521,-0.20535 +1.97235,1.32270,-1.80993,-1.06544,-1.24514,1.70515,-0.20527 +1.98157,1.32276,-1.81154,-1.06258,-1.24635,1.70512,-0.20522 +1.99078,1.32283,-1.81314,-1.05972,-1.24757,1.70508,-0.20518 +2.00000,1.32261,-1.81523,-1.05610,-1.24910,1.70521,-0.20537 +2.00922,1.32031,-1.81981,-1.04882,-1.25196,1.70647,-0.20730 +2.01843,1.31822,-1.82406,-1.04203,-1.25467,1.70763,-0.20905 +2.02765,1.31632,-1.82800,-1.03569,-1.25723,1.70868,-0.21065 +2.03687,1.31458,-1.83165,-1.02977,-1.25965,1.70964,-0.21211 +2.04608,1.31301,-1.83504,-1.02424,-1.26193,1.71052,-0.21344 +2.05530,1.31157,-1.83819,-1.01907,-1.26408,1.71132,-0.21465 +2.06452,1.31026,-1.84110,-1.01425,-1.26611,1.71205,-0.21577 +2.07373,1.30907,-1.84381,-1.00975,-1.26803,1.71271,-0.21678 +2.08295,1.30798,-1.84632,-1.00555,-1.26984,1.71332,-0.21771 +2.09217,1.30699,-1.84866,-1.00162,-1.27154,1.71388,-0.21856 +2.10138,1.30608,-1.85082,-0.99796,-1.27314,1.71439,-0.21933 +2.11060,1.30525,-1.85283,-0.99454,-1.27464,1.71486,-0.22004 +2.11982,1.30501,-1.85318,-0.99400,-1.27486,1.71499,-0.22024 +2.12903,1.30277,-1.85649,-0.98881,-1.27698,1.71623,-0.22213 +2.13825,1.30072,-1.85957,-0.98395,-1.27899,1.71737,-0.22386 +2.14747,1.29886,-1.86243,-0.97940,-1.28089,1.71840,-0.22543 +2.15668,1.29717,-1.86509,-0.97514,-1.28269,1.71934,-0.22686 +2.16590,1.29563,-1.86755,-0.97116,-1.28438,1.72020,-0.22817 +2.17512,1.29423,-1.86985,-0.96744,-1.28599,1.72099,-0.22936 +2.18433,1.29295,-1.87198,-0.96395,-1.28750,1.72170,-0.23045 +2.19355,1.29178,-1.87396,-0.96069,-1.28893,1.72235,-0.23145 +2.20276,1.29074,-1.87572,-0.95781,-1.29020,1.72294,-0.23234 +2.21198,1.28902,-1.87831,-0.95367,-1.29194,1.72389,-0.23380 +2.22120,1.28745,-1.88073,-0.94979,-1.29360,1.72477,-0.23513 +2.23041,1.28603,-1.88298,-0.94616,-1.29516,1.72556,-0.23634 +2.23963,1.28473,-1.88507,-0.94276,-1.29664,1.72629,-0.23745 +2.24885,1.28354,-1.88701,-0.93957,-1.29804,1.72695,-0.23847 +2.25806,1.28265,-1.88850,-0.93713,-1.29912,1.72745,-0.23923 +2.26728,1.28145,-1.89046,-0.93392,-1.30052,1.72812,-0.24025 +2.27650,1.28035,-1.89230,-0.93090,-1.30185,1.72874,-0.24120 +2.28571,1.27980,-1.89319,-0.92943,-1.30250,1.72905,-0.24167 +2.29493,1.27911,-1.89427,-0.92768,-1.30327,1.72943,-0.24226 +2.30415,1.27793,-1.89604,-0.92481,-1.30453,1.73009,-0.24327 +2.31336,1.27762,-1.89630,-0.92445,-1.30467,1.73026,-0.24353 +2.32258,1.27468,-1.89878,-0.92103,-1.30599,1.73188,-0.24600 +2.33180,1.27201,-1.90109,-0.91780,-1.30725,1.73335,-0.24825 +2.34101,1.26959,-1.90325,-0.91477,-1.30846,1.73469,-0.25031 +2.35023,1.26738,-1.90525,-0.91191,-1.30961,1.73591,-0.25217 +2.35945,1.26537,-1.90711,-0.90923,-1.31071,1.73702,-0.25388 +2.36866,1.26355,-1.90885,-0.90671,-1.31175,1.73803,-0.25543 +2.37788,1.26189,-1.91047,-0.90433,-1.31274,1.73895,-0.25684 +2.38710,1.26038,-1.91197,-0.90211,-1.31369,1.73979,-0.25813 +2.39631,1.25924,-1.91304,-0.90055,-1.31434,1.74042,-0.25910 +2.40553,1.25643,-1.91514,-0.89780,-1.31537,1.74197,-0.26148 +2.41475,1.25387,-1.91710,-0.89521,-1.31637,1.74338,-0.26365 +2.42396,1.25154,-1.91892,-0.89277,-1.31732,1.74466,-0.26562 +2.43318,1.24943,-1.92062,-0.89046,-1.31824,1.74583,-0.26742 +2.44240,1.24751,-1.92220,-0.88829,-1.31911,1.74689,-0.26906 +2.45161,1.24576,-1.92368,-0.88625,-1.31995,1.74786,-0.27055 +2.46083,1.24417,-1.92505,-0.88432,-1.32074,1.74874,-0.27191 +2.47005,1.24284,-1.92622,-0.88266,-1.32143,1.74948,-0.27305 +2.47926,1.24129,-1.92758,-0.88074,-1.32223,1.75033,-0.27437 +2.48848,1.24038,-1.92835,-0.87966,-1.32267,1.75084,-0.27515 +2.49770,1.23854,-1.92960,-0.87809,-1.32328,1.75185,-0.27672 +2.50691,1.23687,-1.93075,-0.87662,-1.32387,1.75277,-0.27815 +2.51613,1.23528,-1.93184,-0.87522,-1.32442,1.75365,-0.27951 +2.52535,1.23324,-1.93298,-0.87394,-1.32487,1.75477,-0.28124 +2.53456,1.23139,-1.93404,-0.87273,-1.32532,1.75579,-0.28283 +2.54378,1.22970,-1.93503,-0.87158,-1.32575,1.75672,-0.28426 +2.55300,1.22819,-1.93589,-0.87062,-1.32610,1.75755,-0.28556 +2.56221,1.22555,-1.93698,-0.86971,-1.32633,1.75900,-0.28780 +2.57143,1.22315,-1.93801,-0.86883,-1.32656,1.76031,-0.28984 +2.58065,1.22097,-1.93896,-0.86800,-1.32679,1.76150,-0.29170 +2.58986,1.21898,-1.93984,-0.86721,-1.32703,1.76259,-0.29340 +2.59908,1.21718,-1.94066,-0.86645,-1.32726,1.76358,-0.29494 +2.60829,1.21554,-1.94143,-0.86573,-1.32749,1.76448,-0.29634 +2.61751,1.21486,-1.94172,-0.86547,-1.32756,1.76486,-0.29693 +2.62673,1.21275,-1.94247,-0.86500,-1.32763,1.76601,-0.29873 +2.63594,1.21083,-1.94316,-0.86456,-1.32771,1.76706,-0.30037 +2.64516,1.20908,-1.94380,-0.86412,-1.32779,1.76802,-0.30187 +2.65438,1.20749,-1.94440,-0.86371,-1.32788,1.76889,-0.30323 +2.66359,1.20726,-1.94447,-0.86368,-1.32788,1.76902,-0.30342 +2.67281,1.20509,-1.94514,-0.86340,-1.32784,1.77020,-0.30528 +2.68203,1.20311,-1.94577,-0.86313,-1.32783,1.77128,-0.30697 +2.69124,1.20131,-1.94634,-0.86286,-1.32782,1.77226,-0.30851 +2.70046,1.19967,-1.94688,-0.86260,-1.32783,1.77316,-0.30992 +2.70968,1.19903,-1.94710,-0.86249,-1.32784,1.77351,-0.31047 +2.71889,1.19729,-1.94772,-0.86213,-1.32787,1.77446,-0.31196 +2.72811,1.19569,-1.94828,-0.86181,-1.32791,1.77533,-0.31333 +2.73733,1.19405,-1.94873,-0.86172,-1.32783,1.77623,-0.31474 +2.74654,1.19339,-1.94890,-0.86172,-1.32779,1.77659,-0.31531 +2.75576,1.19142,-1.94925,-0.86196,-1.32753,1.77766,-0.31700 +2.76498,1.18963,-1.94959,-0.86217,-1.32731,1.77864,-0.31853 +2.77419,1.18800,-1.94989,-0.86235,-1.32711,1.77952,-0.31993 +2.78341,1.18735,-1.95000,-0.86245,-1.32702,1.77987,-0.32048 +2.79263,1.18556,-1.95021,-0.86289,-1.32669,1.78085,-0.32202 +2.80184,1.18393,-1.95040,-0.86329,-1.32638,1.78173,-0.32342 +2.81106,1.18312,-1.95047,-0.86355,-1.32621,1.78217,-0.32411 +2.82028,1.18128,-1.95038,-0.86457,-1.32561,1.78317,-0.32569 +2.82949,1.17960,-1.95029,-0.86552,-1.32506,1.78408,-0.32713 +2.83871,1.17808,-1.95021,-0.86639,-1.32455,1.78491,-0.32844 +2.84793,1.17784,-1.95010,-0.86671,-1.32440,1.78504,-0.32865 +2.85714,1.17553,-1.94905,-0.86971,-1.32289,1.78628,-0.33062 +2.86636,1.17344,-1.94808,-0.87251,-1.32148,1.78741,-0.33241 +2.87558,1.17154,-1.94716,-0.87510,-1.32016,1.78844,-0.33403 +2.88479,1.16982,-1.94630,-0.87752,-1.31893,1.78937,-0.33551 +2.89401,1.16825,-1.94550,-0.87977,-1.31779,1.79022,-0.33686 +2.90323,1.16683,-1.94475,-0.88186,-1.31672,1.79099,-0.33808 +2.91244,1.16574,-1.94411,-0.88359,-1.31584,1.79158,-0.33902 +2.92166,1.16404,-1.94275,-0.88694,-1.31419,1.79250,-0.34047 +2.93088,1.16250,-1.94147,-0.89007,-1.31265,1.79333,-0.34179 +2.94009,1.16110,-1.94028,-0.89297,-1.31120,1.79409,-0.34299 +2.94931,1.15984,-1.93917,-0.89568,-1.30985,1.79477,-0.34408 +2.95853,1.15869,-1.93813,-0.89821,-1.30859,1.79539,-0.34507 +2.96774,1.15855,-1.93798,-0.89856,-1.30842,1.79547,-0.34518 +2.97696,1.15725,-1.93649,-0.90197,-1.30676,1.79617,-0.34630 +2.98618,1.15606,-1.93511,-0.90515,-1.30520,1.79681,-0.34731 +2.99539,1.15499,-1.93382,-0.90811,-1.30374,1.79739,-0.34823 +3.00461,1.15436,-1.93296,-0.91003,-1.30281,1.79773,-0.34878 +3.01382,1.15304,-1.93064,-0.91497,-1.30046,1.79844,-0.34990 +3.02304,1.15184,-1.92849,-0.91957,-1.29827,1.79908,-0.35093 +3.03226,1.15075,-1.92648,-0.92385,-1.29622,1.79967,-0.35185 +3.04147,1.14977,-1.92461,-0.92784,-1.29430,1.80019,-0.35269 +3.05069,1.14888,-1.92287,-0.93156,-1.29250,1.80067,-0.35345 +3.05991,1.14808,-1.92124,-0.93502,-1.29082,1.80110,-0.35413 +3.06912,1.14748,-1.91997,-0.93772,-1.28950,1.80143,-0.35464 +3.07834,1.14671,-1.91801,-0.94179,-1.28756,1.80184,-0.35530 +3.08756,1.14601,-1.91618,-0.94558,-1.28574,1.80222,-0.35589 +3.09677,1.14538,-1.91447,-0.94911,-1.28404,1.80256,-0.35643 +3.10599,1.14513,-1.91374,-0.95060,-1.28332,1.80269,-0.35664 +3.11521,1.14448,-1.91142,-0.95526,-1.28113,1.80304,-0.35719 +3.12442,1.14389,-1.90925,-0.95960,-1.27907,1.80336,-0.35768 +3.13364,1.14337,-1.90724,-0.96364,-1.27715,1.80364,-0.35813 +3.14286,1.14289,-1.90537,-0.96740,-1.27535,1.80389,-0.35853 +3.15207,1.14256,-1.90400,-0.97013,-1.27405,1.80407,-0.35880 +3.16129,1.14195,-1.90104,-0.97592,-1.27137,1.80439,-0.35931 +3.17051,1.14141,-1.89828,-0.98131,-1.26886,1.80469,-0.35977 +3.17972,1.14092,-1.89573,-0.98631,-1.26651,1.80495,-0.36018 +3.18894,1.14048,-1.89336,-0.99097,-1.26432,1.80518,-0.36054 +3.19816,1.14009,-1.89116,-0.99529,-1.26227,1.80539,-0.36087 +3.20737,1.13973,-1.88912,-0.99931,-1.26035,1.80558,-0.36115 +3.21659,1.13942,-1.88722,-1.00305,-1.25856,1.80574,-0.36141 +3.22581,1.13931,-1.88648,-1.00450,-1.25787,1.80580,-0.36150 +3.23502,1.13909,-1.88479,-1.00780,-1.25629,1.80592,-0.36168 +3.24424,1.13890,-1.88328,-1.01074,-1.25489,1.80602,-0.36183 +3.25346,1.13874,-1.88124,-1.01465,-1.25305,1.80610,-0.36195 +3.26267,1.13865,-1.87966,-1.01766,-1.25163,1.80615,-0.36202 +3.27189,1.13870,-1.87735,-1.02194,-1.24965,1.80612,-0.36196 +3.28111,1.13875,-1.87520,-1.02592,-1.24780,1.80610,-0.36191 +3.29032,1.13884,-1.87317,-1.02969,-1.24604,1.80605,-0.36182 +3.29954,1.13917,-1.87082,-1.03388,-1.24413,1.80588,-0.36152 +3.30876,1.13947,-1.86865,-1.03777,-1.24235,1.80571,-0.36124 +3.31797,1.13974,-1.86698,-1.04075,-1.24097,1.80557,-0.36100 +3.32719,1.14029,-1.86459,-1.04491,-1.23910,1.80528,-0.36051 +3.33641,1.14079,-1.86238,-1.04876,-1.23735,1.80501,-0.36006 +3.34562,1.14126,-1.86033,-1.05234,-1.23572,1.80476,-0.35964 +3.35484,1.14138,-1.86003,-1.05284,-1.23550,1.80469,-0.35954 +3.36406,1.14255,-1.85712,-1.05760,-1.23344,1.80407,-0.35852 +3.37327,1.14362,-1.85442,-1.06202,-1.23150,1.80350,-0.35758 +3.38249,1.14460,-1.85193,-1.06612,-1.22970,1.80298,-0.35672 +3.39171,1.14551,-1.84963,-1.06993,-1.22801,1.80249,-0.35592 +3.40092,1.14634,-1.84751,-1.07346,-1.22643,1.80205,-0.35519 +3.41014,1.14707,-1.84568,-1.07649,-1.22507,1.80165,-0.35454 +3.41935,1.14817,-1.84339,-1.08019,-1.22345,1.80106,-0.35358 +3.42857,1.14917,-1.84126,-1.08362,-1.22194,1.80052,-0.35270 +3.43779,1.15010,-1.83930,-1.08680,-1.22053,1.80003,-0.35189 +3.44700,1.15031,-1.83888,-1.08748,-1.22023,1.79991,-0.35170 +3.45622,1.15154,-1.83663,-1.09102,-1.21870,1.79925,-0.35063 +3.46544,1.15266,-1.83455,-1.09430,-1.21727,1.79865,-0.34964 +3.47465,1.15369,-1.83263,-1.09735,-1.21594,1.79809,-0.34874 +3.48387,1.15400,-1.83208,-1.09823,-1.21555,1.79793,-0.34847 +3.49309,1.15509,-1.83020,-1.10118,-1.21427,1.79734,-0.34752 +3.50230,1.15635,-1.82824,-1.10417,-1.21298,1.79666,-0.34642 +3.51152,1.15751,-1.82643,-1.10695,-1.21178,1.79604,-0.34541 +3.52074,1.15764,-1.82622,-1.10727,-1.21165,1.79596,-0.34529 +3.52995,1.15894,-1.82423,-1.11030,-1.21036,1.79526,-0.34415 +3.53917,1.16014,-1.82239,-1.11311,-1.20915,1.79462,-0.34311 +3.54839,1.16064,-1.82162,-1.11428,-1.20866,1.79434,-0.34267 +3.55760,1.16228,-1.81924,-1.11782,-1.20719,1.79346,-0.34125 +3.56682,1.16378,-1.81705,-1.12109,-1.20583,1.79266,-0.33995 +3.57604,1.16515,-1.81503,-1.12413,-1.20455,1.79191,-0.33876 +3.58525,1.16641,-1.81317,-1.12695,-1.20336,1.79123,-0.33766 +3.59447,1.16724,-1.81193,-1.12882,-1.20256,1.79078,-0.33693 +3.60369,1.16854,-1.81013,-1.13151,-1.20143,1.79008,-0.33580 +3.61290,1.16931,-1.80908,-1.13307,-1.20077,1.78966,-0.33513 +3.62212,1.17080,-1.80719,-1.13581,-1.19965,1.78885,-0.33384 +3.63134,1.17217,-1.80545,-1.13835,-1.19859,1.78811,-0.33265 +3.64055,1.17295,-1.80446,-1.13980,-1.19799,1.78769,-0.33197 +3.64977,1.17428,-1.80281,-1.14219,-1.19699,1.78696,-0.33082 +3.65899,1.17444,-1.80262,-1.14245,-1.19689,1.78688,-0.33068 +3.66820,1.17594,-1.80088,-1.14493,-1.19588,1.78606,-0.32938 +3.67742,1.17732,-1.79926,-1.14723,-1.19493,1.78532,-0.32819 +3.68664,1.17748,-1.79909,-1.14747,-1.19484,1.78523,-0.32804 +3.69585,1.17906,-1.79747,-1.14969,-1.19395,1.78437,-0.32668 +3.70507,1.18054,-1.79596,-1.15177,-1.19312,1.78357,-0.32540 +3.71429,1.18226,-1.79437,-1.15385,-1.19231,1.78264,-0.32391 +3.72350,1.18383,-1.79291,-1.15579,-1.19155,1.78178,-0.32256 +3.73272,1.18468,-1.79219,-1.15671,-1.19119,1.78133,-0.32183 +3.74194,1.18708,-1.79055,-1.15857,-1.19055,1.78003,-0.31977 +3.75115,1.18927,-1.78904,-1.16029,-1.18995,1.77884,-0.31789 +3.76037,1.19127,-1.78766,-1.16188,-1.18939,1.77776,-0.31617 +3.76959,1.19309,-1.78639,-1.16335,-1.18886,1.77676,-0.31460 +3.77880,1.19476,-1.78523,-1.16472,-1.18837,1.77585,-0.31317 +3.78802,1.19525,-1.78488,-1.16513,-1.18822,1.77559,-0.31274 +3.79724,1.19696,-1.78366,-1.16657,-1.18770,1.77465,-0.31128 +3.80645,1.19794,-1.78295,-1.16741,-1.18739,1.77412,-0.31043 +3.81567,1.19972,-1.78165,-1.16896,-1.18684,1.77315,-0.30891 +3.82488,1.20134,-1.78046,-1.17039,-1.18633,1.77226,-0.30751 +3.83410,1.20150,-1.78034,-1.17054,-1.18628,1.77218,-0.30737 +3.84332,1.20246,-1.77963,-1.17139,-1.18597,1.77165,-0.30655 +3.85253,1.20407,-1.77842,-1.17285,-1.18544,1.77077,-0.30517 +3.86175,1.20423,-1.77830,-1.17300,-1.18539,1.77068,-0.30503 +3.87097,1.20469,-1.77782,-1.17368,-1.18511,1.77043,-0.30463 +3.88018,1.20304,-1.77771,-1.17472,-1.18444,1.77130,-0.30601 +3.88940,1.20234,-1.77769,-1.17512,-1.18417,1.77167,-0.30659 +3.89862,1.20008,-1.77776,-1.17614,-1.18345,1.77286,-0.30848 +3.90783,1.19803,-1.77782,-1.17706,-1.18279,1.77395,-0.31021 +3.91705,1.19617,-1.77788,-1.17791,-1.18218,1.77494,-0.31178 +3.92627,1.19447,-1.77793,-1.17868,-1.18163,1.77585,-0.31321 +3.93548,1.19369,-1.77799,-1.17897,-1.18141,1.77626,-0.31386 +3.94470,1.19088,-1.77839,-1.17967,-1.18078,1.77776,-0.31624 +3.95392,1.18832,-1.77875,-1.18030,-1.18021,1.77913,-0.31840 +3.96313,1.18600,-1.77909,-1.18086,-1.17969,1.78037,-0.32038 +3.97235,1.18388,-1.77941,-1.18137,-1.17923,1.78151,-0.32217 +3.98157,1.18196,-1.77970,-1.18183,-1.17880,1.78254,-0.32381 +3.99078,1.18021,-1.77996,-1.18224,-1.17842,1.78348,-0.32530 +4.00000,1.17929,-1.78010,-1.18247,-1.17821,1.78397,-0.32608 +4.00922,1.17683,-1.78040,-1.18316,-1.17765,1.78529,-0.32818 +4.01843,1.17458,-1.78068,-1.18379,-1.17713,1.78650,-0.33010 +4.02765,1.17254,-1.78095,-1.18435,-1.17666,1.78759,-0.33184 +4.03687,1.17068,-1.78119,-1.18486,-1.17624,1.78859,-0.33343 +4.04608,1.16899,-1.78141,-1.18533,-1.17585,1.78950,-0.33488 +4.05530,1.16861,-1.78147,-1.18542,-1.17577,1.78971,-0.33521 +4.06452,1.16648,-1.78184,-1.18584,-1.17536,1.79085,-0.33703 +4.07373,1.16454,-1.78217,-1.18623,-1.17499,1.79189,-0.33870 +4.08295,1.16278,-1.78248,-1.18657,-1.17465,1.79284,-0.34021 +4.09217,1.16168,-1.78269,-1.18677,-1.17444,1.79343,-0.34116 +4.10138,1.15899,-1.78324,-1.18716,-1.17400,1.79487,-0.34346 +4.11060,1.15655,-1.78375,-1.18750,-1.17360,1.79617,-0.34556 +4.11982,1.15433,-1.78422,-1.18780,-1.17324,1.79736,-0.34747 +4.12903,1.15231,-1.78465,-1.18806,-1.17292,1.79845,-0.34920 +4.13825,1.15048,-1.78505,-1.18829,-1.17263,1.79943,-0.35079 +4.14747,1.14875,-1.78543,-1.18850,-1.17237,1.80036,-0.35228 +4.15668,1.14668,-1.78589,-1.18875,-1.17205,1.80147,-0.35406 +4.16590,1.14480,-1.78631,-1.18897,-1.17177,1.80248,-0.35569 +4.17512,1.14309,-1.78670,-1.18917,-1.17151,1.80339,-0.35717 +4.18433,1.14252,-1.78682,-1.18924,-1.17142,1.80370,-0.35766 +4.19355,1.14018,-1.78731,-1.18959,-1.17104,1.80495,-0.35969 +4.20276,1.13804,-1.78776,-1.18990,-1.17070,1.80609,-0.36153 +4.21198,1.13610,-1.78818,-1.19017,-1.17039,1.80713,-0.36321 +4.22120,1.13433,-1.78856,-1.19041,-1.17012,1.80808,-0.36474 +4.23041,1.13331,-1.78878,-1.19056,-1.16995,1.80862,-0.36563 +4.23963,1.13139,-1.78911,-1.19096,-1.16960,1.80965,-0.36730 +4.24885,1.12965,-1.78942,-1.19133,-1.16927,1.81058,-0.36881 +4.25806,1.12861,-1.78959,-1.19156,-1.16907,1.81114,-0.36972 +4.26728,1.12642,-1.78989,-1.19218,-1.16860,1.81230,-0.37161 +4.27650,1.12443,-1.79016,-1.19274,-1.16817,1.81336,-0.37334 +4.28571,1.12262,-1.79042,-1.19325,-1.16778,1.81433,-0.37491 +4.29493,1.12093,-1.79066,-1.19371,-1.16742,1.81522,-0.37638 +4.30415,1.11907,-1.79096,-1.19416,-1.16705,1.81621,-0.37800 +4.31336,1.11738,-1.79124,-1.19456,-1.16671,1.81711,-0.37947 +4.32258,1.11682,-1.79130,-1.19476,-1.16658,1.81741,-0.37996 +4.33180,1.11452,-1.79133,-1.19592,-1.16587,1.81863,-0.38196 +4.34101,1.11243,-1.79136,-1.19697,-1.16522,1.81974,-0.38378 +4.35023,1.11053,-1.79139,-1.19794,-1.16463,1.82075,-0.38543 +4.35945,1.10880,-1.79142,-1.19881,-1.16409,1.82166,-0.38694 +4.36866,1.10733,-1.79141,-1.19964,-1.16360,1.82244,-0.38822 +4.37788,1.10541,-1.79104,-1.20131,-1.16271,1.82346,-0.38990 +4.38710,1.10366,-1.79071,-1.20284,-1.16189,1.82439,-0.39143 +4.39631,1.10206,-1.79040,-1.20425,-1.16113,1.82523,-0.39282 +4.40553,1.10097,-1.79014,-1.20531,-1.16057,1.82581,-0.39378 +4.41475,1.09894,-1.78932,-1.20787,-1.15930,1.82688,-0.39555 +4.42396,1.09710,-1.78855,-1.21022,-1.15812,1.82785,-0.39715 +4.43318,1.09543,-1.78785,-1.21238,-1.15703,1.82874,-0.39862 +4.44240,1.09390,-1.78721,-1.21437,-1.15602,1.82954,-0.39995 +4.45161,1.09252,-1.78661,-1.21620,-1.15510,1.83027,-0.40116 +4.46083,1.09222,-1.78646,-1.21664,-1.15488,1.83043,-0.40142 +4.47005,1.09061,-1.78556,-1.21912,-1.15366,1.83128,-0.40283 +4.47926,1.08914,-1.78474,-1.22141,-1.15253,1.83205,-0.40411 +4.48848,1.08781,-1.78397,-1.22351,-1.15149,1.83275,-0.40527 +4.49770,1.08726,-1.78362,-1.22446,-1.15102,1.83304,-0.40576 +4.50691,1.08555,-1.78226,-1.22780,-1.14943,1.83394,-0.40725 +4.51613,1.08401,-1.78102,-1.23088,-1.14795,1.83475,-0.40860 +4.52535,1.08260,-1.77987,-1.23371,-1.14659,1.83549,-0.40983 +4.53456,1.08132,-1.77881,-1.23632,-1.14533,1.83616,-0.41095 +4.54378,1.08016,-1.77784,-1.23872,-1.14416,1.83677,-0.41196 +4.55300,1.07982,-1.77754,-1.23946,-1.14381,1.83694,-0.41226 +4.56221,1.07868,-1.77642,-1.24210,-1.14254,1.83755,-0.41326 +4.57143,1.07783,-1.77558,-1.24410,-1.14158,1.83799,-0.41400 +4.58065,1.07679,-1.77445,-1.24670,-1.14034,1.83854,-0.41492 +4.58986,1.07647,-1.77409,-1.24753,-1.13995,1.83870,-0.41519 +4.59908,1.07535,-1.77269,-1.25067,-1.13848,1.83929,-0.41617 +4.60829,1.07433,-1.77139,-1.25356,-1.13712,1.83982,-0.41707 +4.61751,1.07340,-1.77019,-1.25624,-1.13585,1.84031,-0.41788 +4.62673,1.07287,-1.76944,-1.25789,-1.13507,1.84059,-0.41834 +4.63594,1.07210,-1.76803,-1.26086,-1.13370,1.84099,-0.41902 +4.64516,1.07189,-1.76756,-1.26181,-1.13327,1.84111,-0.41920 +4.65438,1.07122,-1.76569,-1.26551,-1.13160,1.84146,-0.41979 +4.66359,1.07061,-1.76397,-1.26892,-1.13006,1.84177,-0.42032 +4.67281,1.07006,-1.76238,-1.27207,-1.12863,1.84206,-0.42079 +4.68203,1.07000,-1.76188,-1.27299,-1.12823,1.84209,-0.42085 +4.69124,1.06990,-1.75854,-1.27891,-1.12570,1.84215,-0.42093 +4.70046,1.06982,-1.75546,-1.28437,-1.12335,1.84219,-0.42099 +4.70968,1.06976,-1.75264,-1.28940,-1.12118,1.84223,-0.42104 +4.71889,1.06971,-1.75004,-1.29404,-1.11917,1.84226,-0.42108 +4.72811,1.06967,-1.74764,-1.29831,-1.11730,1.84228,-0.42110 +4.73733,1.06964,-1.74544,-1.30225,-1.11556,1.84229,-0.42111 +4.74654,1.06962,-1.74342,-1.30588,-1.11396,1.84230,-0.42112 +4.75576,1.06961,-1.74155,-1.30923,-1.11247,1.84231,-0.42112 +4.76498,1.06965,-1.74110,-1.31002,-1.11213,1.84229,-0.42109 +4.77419,1.07001,-1.73848,-1.31445,-1.11024,1.84210,-0.42076 +4.78341,1.07035,-1.73607,-1.31854,-1.10848,1.84192,-0.42045 +4.79263,1.07066,-1.73385,-1.32230,-1.10686,1.84176,-0.42016 +4.80184,1.07096,-1.73182,-1.32578,-1.10535,1.84160,-0.41989 +4.81106,1.07127,-1.73014,-1.32859,-1.10413,1.84144,-0.41961 +4.82028,1.07232,-1.72682,-1.33382,-1.10199,1.84089,-0.41867 +4.82949,1.07330,-1.72377,-1.33864,-1.10001,1.84039,-0.41781 +4.83871,1.07419,-1.72097,-1.34307,-1.09817,1.83992,-0.41700 +4.84793,1.07502,-1.71840,-1.34716,-1.09646,1.83948,-0.41626 +4.85714,1.07579,-1.71603,-1.35093,-1.09487,1.83908,-0.41558 +4.86636,1.07649,-1.71386,-1.35441,-1.09340,1.83871,-0.41494 +4.87558,1.07715,-1.71186,-1.35761,-1.09204,1.83837,-0.41436 +4.88479,1.07742,-1.71106,-1.35889,-1.09150,1.83822,-0.41411 +4.89401,1.07829,-1.70879,-1.36243,-1.09003,1.83777,-0.41334 +4.90323,1.07908,-1.70670,-1.36569,-1.08866,1.83735,-0.41262 +4.91244,1.07986,-1.70473,-1.36876,-1.08737,1.83693,-0.41192 +4.92166,1.08102,-1.70242,-1.37221,-1.08597,1.83633,-0.41090 +4.93088,1.08207,-1.70030,-1.37538,-1.08468,1.83577,-0.40996 +4.94009,1.08304,-1.69835,-1.37830,-1.08347,1.83526,-0.40909 +4.94931,1.08345,-1.69758,-1.37945,-1.08301,1.83505,-0.40873 +4.95853,1.08469,-1.69551,-1.38243,-1.08181,1.83440,-0.40764 +4.96774,1.08582,-1.69361,-1.38517,-1.08070,1.83380,-0.40663 +4.97696,1.08634,-1.69282,-1.38628,-1.08027,1.83353,-0.40617 +4.98618,1.08821,-1.69046,-1.38938,-1.07909,1.83255,-0.40452 +4.99539,1.08993,-1.68830,-1.39225,-1.07800,1.83165,-0.40301 +5.00461,1.09150,-1.68632,-1.39488,-1.07699,1.83082,-0.40162 +5.01382,1.09294,-1.68450,-1.39731,-1.07605,1.83006,-0.40035 +5.02304,1.09406,-1.68313,-1.39913,-1.07535,1.82947,-0.39936 +5.03226,1.09583,-1.68133,-1.40137,-1.07453,1.82854,-0.39780 +5.04147,1.09745,-1.67967,-1.40342,-1.07376,1.82768,-0.39638 +5.05069,1.09889,-1.67824,-1.40519,-1.07311,1.82692,-0.39511 +5.05991,1.10118,-1.67625,-1.40744,-1.07235,1.82572,-0.39310 +5.06912,1.10327,-1.67443,-1.40951,-1.07164,1.82461,-0.39127 +5.07834,1.10519,-1.67276,-1.41142,-1.07097,1.82360,-0.38958 +5.08756,1.10695,-1.67124,-1.41318,-1.07036,1.82267,-0.38804 +5.09677,1.10859,-1.66983,-1.41480,-1.06978,1.82179,-0.38660 +5.10599,1.11045,-1.66844,-1.41627,-1.06930,1.82081,-0.38497 +5.11521,1.11215,-1.66716,-1.41763,-1.06884,1.81991,-0.38348 +5.12442,1.11238,-1.66701,-1.41778,-1.06880,1.81979,-0.38328 +5.13364,1.11454,-1.66555,-1.41922,-1.06837,1.81864,-0.38139 +5.14286,1.11651,-1.66421,-1.42054,-1.06796,1.81759,-0.37966 +5.15207,1.11832,-1.66299,-1.42176,-1.06759,1.81663,-0.37808 +5.16129,1.11918,-1.66241,-1.42233,-1.06741,1.81617,-0.37733 +5.17051,1.12096,-1.66128,-1.42339,-1.06709,1.81522,-0.37578 +5.17972,1.12116,-1.66116,-1.42350,-1.06706,1.81512,-0.37560 +5.18894,1.12304,-1.66002,-1.42453,-1.06678,1.81412,-0.37396 +5.19816,1.12430,-1.65927,-1.42521,-1.06659,1.81344,-0.37286 +5.20737,1.12630,-1.65819,-1.42608,-1.06639,1.81237,-0.37111 +5.21659,1.12813,-1.65720,-1.42688,-1.06619,1.81140,-0.36952 +5.22581,1.12857,-1.65700,-1.42701,-1.06617,1.81117,-0.36914 +5.23502,1.13104,-1.65599,-1.42753,-1.06616,1.80985,-0.36700 +5.24424,1.13329,-1.65506,-1.42801,-1.06615,1.80865,-0.36504 +5.25346,1.13535,-1.65422,-1.42845,-1.06613,1.80755,-0.36325 +5.26267,1.13723,-1.65345,-1.42886,-1.06611,1.80654,-0.36162 +5.27189,1.13780,-1.65323,-1.42898,-1.06611,1.80624,-0.36112 +5.28111,1.13986,-1.65245,-1.42931,-1.06614,1.80513,-0.35933 +5.29032,1.14174,-1.65174,-1.42962,-1.06617,1.80412,-0.35770 +5.29954,1.14236,-1.65150,-1.42972,-1.06618,1.80379,-0.35716 +5.30876,1.14486,-1.65053,-1.43015,-1.06623,1.80246,-0.35500 +5.31797,1.14714,-1.64965,-1.43054,-1.06627,1.80123,-0.35302 +5.32719,1.14923,-1.64885,-1.43090,-1.06631,1.80011,-0.35122 +5.33641,1.15113,-1.64812,-1.43124,-1.06633,1.79909,-0.34957 +5.34562,1.15193,-1.64782,-1.43136,-1.06635,1.79866,-0.34888 +5.35484,1.15448,-1.64693,-1.43164,-1.06648,1.79729,-0.34668 +5.36406,1.15680,-1.64612,-1.43190,-1.06658,1.79604,-0.34467 +5.37327,1.15892,-1.64539,-1.43214,-1.06668,1.79490,-0.34284 +5.38249,1.16086,-1.64472,-1.43237,-1.06676,1.79386,-0.34117 +5.39171,1.16179,-1.64440,-1.43246,-1.06681,1.79335,-0.34036 +5.40092,1.16379,-1.64380,-1.43255,-1.06696,1.79227,-0.33864 +5.41014,1.16552,-1.64329,-1.43260,-1.06709,1.79134,-0.33715 +5.41935,1.16792,-1.64267,-1.43252,-1.06735,1.79005,-0.33509 +5.42857,1.17010,-1.64211,-1.43244,-1.06759,1.78887,-0.33321 +5.43779,1.17209,-1.64160,-1.43237,-1.06781,1.78779,-0.33149 +5.44700,1.17358,-1.64122,-1.43232,-1.06797,1.78698,-0.33021 +5.45622,1.17547,-1.64075,-1.43223,-1.06818,1.78596,-0.32859 +5.46544,1.17610,-1.64064,-1.43213,-1.06828,1.78562,-0.32804 +5.47465,1.17872,-1.64039,-1.43134,-1.06886,1.78421,-0.32580 +5.48387,1.18110,-1.64017,-1.43060,-1.06939,1.78292,-0.32376 +5.49309,1.18327,-1.63998,-1.42992,-1.06987,1.78174,-0.32190 +5.50230,1.18525,-1.63981,-1.42930,-1.07032,1.78067,-0.32020 +5.51152,1.18705,-1.63966,-1.42872,-1.07073,1.77969,-0.31866 +5.52074,1.18726,-1.63965,-1.42864,-1.07078,1.77958,-0.31848 +5.52995,1.18924,-1.63959,-1.42784,-1.07130,1.77850,-0.31678 +5.53917,1.19104,-1.63954,-1.42711,-1.07177,1.77752,-0.31524 +5.54839,1.19143,-1.63954,-1.42691,-1.07189,1.77731,-0.31490 +5.55760,1.19355,-1.63968,-1.42572,-1.07259,1.77616,-0.31310 +5.56682,1.19547,-1.63981,-1.42462,-1.07322,1.77511,-0.31145 +5.57604,1.19722,-1.63993,-1.42361,-1.07381,1.77416,-0.30996 +5.58525,1.19776,-1.63999,-1.42326,-1.07401,1.77387,-0.30950 +5.59447,1.19973,-1.64035,-1.42176,-1.07481,1.77279,-0.30782 +5.60369,1.20152,-1.64069,-1.42038,-1.07556,1.77182,-0.30629 +5.61290,1.20327,-1.64106,-1.41895,-1.07632,1.77086,-0.30479 +5.62212,1.20594,-1.64192,-1.41629,-1.07767,1.76941,-0.30253 +5.63134,1.20837,-1.64271,-1.41384,-1.07891,1.76810,-0.30047 +5.64055,1.21057,-1.64346,-1.41159,-1.08006,1.76690,-0.29860 +5.64977,1.21257,-1.64415,-1.40950,-1.08112,1.76581,-0.29690 +5.65899,1.21439,-1.64479,-1.40758,-1.08211,1.76481,-0.29535 +5.66820,1.21604,-1.64539,-1.40581,-1.08302,1.76391,-0.29395 +5.67742,1.21756,-1.64597,-1.40412,-1.08388,1.76307,-0.29266 +5.68664,1.21914,-1.64677,-1.40205,-1.08490,1.76221,-0.29132 +5.69585,1.22057,-1.64751,-1.40014,-1.08585,1.76142,-0.29010 +5.70507,1.22101,-1.64776,-1.39951,-1.08616,1.76118,-0.28973 +5.71429,1.22264,-1.64883,-1.39696,-1.08738,1.76029,-0.28835 +5.72350,1.22411,-1.64982,-1.39460,-1.08851,1.75948,-0.28710 +5.73272,1.22545,-1.65073,-1.39244,-1.08956,1.75875,-0.28597 +5.74194,1.22595,-1.65109,-1.39160,-1.08996,1.75847,-0.28554 +5.75115,1.22671,-1.65167,-1.39026,-1.09060,1.75806,-0.28490 +5.76037,1.22805,-1.65282,-1.38769,-1.09181,1.75732,-0.28377 +5.76959,1.22927,-1.65388,-1.38532,-1.09293,1.75665,-0.28274 +5.77880,1.22973,-1.65431,-1.38437,-1.09338,1.75639,-0.28234 +5.78802,1.23089,-1.65552,-1.38178,-1.09459,1.75576,-0.28137 +5.79724,1.23176,-1.65647,-1.37975,-1.09553,1.75528,-0.28063 +5.80645,1.23300,-1.65798,-1.37660,-1.09697,1.75460,-0.27958 +5.81567,1.23413,-1.65937,-1.37370,-1.09830,1.75398,-0.27864 +5.82488,1.23514,-1.66066,-1.37102,-1.09954,1.75342,-0.27778 +5.83410,1.23562,-1.66129,-1.36972,-1.10014,1.75316,-0.27738 +5.84332,1.23656,-1.66260,-1.36703,-1.10138,1.75264,-0.27659 +5.85253,1.23683,-1.66298,-1.36624,-1.10174,1.75249,-0.27636 +5.86175,1.23709,-1.66348,-1.36525,-1.10221,1.75235,-0.27614 +5.87097,1.23540,-1.66203,-1.36835,-1.10086,1.75325,-0.27755 +5.88018,1.23386,-1.66070,-1.37120,-1.09961,1.75407,-0.27883 +5.88940,1.23247,-1.65948,-1.37382,-1.09846,1.75482,-0.27999 +5.89862,1.23119,-1.65836,-1.37623,-1.09740,1.75550,-0.28106 +5.90783,1.23024,-1.65749,-1.37809,-1.09657,1.75602,-0.28186 +5.91705,1.22892,-1.65616,-1.38089,-1.09533,1.75672,-0.28296 +5.92627,1.22772,-1.65493,-1.38347,-1.09418,1.75737,-0.28396 +5.93548,1.22671,-1.65385,-1.38574,-1.09317,1.75791,-0.28481 +5.94470,1.22537,-1.65218,-1.38914,-1.09167,1.75864,-0.28593 +5.95392,1.22415,-1.65065,-1.39228,-1.09028,1.75929,-0.28695 +5.96313,1.22304,-1.64924,-1.39515,-1.08900,1.75989,-0.28788 +5.97235,1.22203,-1.64795,-1.39780,-1.08782,1.76043,-0.28873 +5.98157,1.22163,-1.64740,-1.39891,-1.08732,1.76065,-0.28906 +5.99078,1.22052,-1.64565,-1.40237,-1.08581,1.76125,-0.28999 +6.00000,1.21951,-1.64405,-1.40554,-1.08440,1.76179,-0.29084 +6.00922,1.21860,-1.64258,-1.40846,-1.08311,1.76229,-0.29161 +6.01843,1.21773,-1.64103,-1.41150,-1.08177,1.76276,-0.29233 +6.02765,1.21664,-1.63786,-1.41734,-1.07930,1.76334,-0.29324 +6.03687,1.21566,-1.63495,-1.42271,-1.07703,1.76387,-0.29406 +6.04608,1.21477,-1.63228,-1.42764,-1.07492,1.76436,-0.29481 +6.05530,1.21396,-1.62983,-1.43217,-1.07298,1.76479,-0.29548 +6.06452,1.21323,-1.62759,-1.43633,-1.07119,1.76519,-0.29609 +6.07373,1.21256,-1.62553,-1.44016,-1.06954,1.76554,-0.29664 +6.08295,1.21197,-1.62364,-1.44367,-1.06801,1.76587,-0.29714 +6.09217,1.21142,-1.62191,-1.44690,-1.06660,1.76616,-0.29759 +6.10138,1.21094,-1.62032,-1.44987,-1.06530,1.76642,-0.29800 +6.11060,1.21083,-1.61992,-1.45059,-1.06499,1.76648,-0.29809 +6.11982,1.21026,-1.61761,-1.45478,-1.06320,1.76679,-0.29856 +6.12903,1.20974,-1.61550,-1.45863,-1.06156,1.76707,-0.29899 +6.13825,1.20928,-1.61356,-1.46216,-1.06004,1.76732,-0.29938 +6.14747,1.20886,-1.61178,-1.46541,-1.05863,1.76754,-0.29972 +6.15668,1.20848,-1.61014,-1.46840,-1.05734,1.76775,-0.30003 +6.16590,1.20845,-1.60986,-1.46889,-1.05713,1.76776,-0.30006 +6.17512,1.20816,-1.60716,-1.47359,-1.05519,1.76792,-0.30030 +6.18433,1.20790,-1.60468,-1.47791,-1.05339,1.76806,-0.30051 +6.19355,1.20767,-1.60241,-1.48188,-1.05174,1.76818,-0.30069 +6.20276,1.20747,-1.60033,-1.48552,-1.05021,1.76829,-0.30085 +6.21198,1.20729,-1.59842,-1.48887,-1.04879,1.76838,-0.30099 +6.22120,1.20713,-1.59666,-1.49195,-1.04749,1.76847,-0.30112 +6.23041,1.20711,-1.59629,-1.49260,-1.04722,1.76848,-0.30114 +6.23963,1.20704,-1.59434,-1.49595,-1.04582,1.76851,-0.30118 +6.24885,1.20698,-1.59255,-1.49903,-1.04453,1.76854,-0.30122 +6.25806,1.20699,-1.59215,-1.49971,-1.04425,1.76854,-0.30121 +6.26728,1.20715,-1.58997,-1.50333,-1.04278,1.76845,-0.30107 +6.27650,1.20730,-1.58797,-1.50666,-1.04142,1.76837,-0.30093 +6.28571,1.20745,-1.58613,-1.50972,-1.04017,1.76829,-0.30080 +6.29493,1.20749,-1.58586,-1.51016,-1.03999,1.76826,-0.30076 +6.30415,1.20790,-1.58325,-1.51436,-1.03834,1.76804,-0.30040 +6.31336,1.20828,-1.58086,-1.51821,-1.03682,1.76783,-0.30006 +6.32258,1.20864,-1.57867,-1.52175,-1.03541,1.76763,-0.29975 +6.33180,1.20897,-1.57666,-1.52501,-1.03411,1.76745,-0.29946 +6.34101,1.20925,-1.57497,-1.52775,-1.03301,1.76729,-0.29921 +6.35023,1.20956,-1.57304,-1.53087,-1.03176,1.76712,-0.29893 +6.35945,1.20971,-1.57222,-1.53218,-1.03124,1.76704,-0.29880 +6.36866,1.21030,-1.56966,-1.53621,-1.02969,1.76672,-0.29829 +6.37788,1.21085,-1.56730,-1.53990,-1.02826,1.76642,-0.29781 +6.38710,1.21136,-1.56515,-1.54330,-1.02693,1.76614,-0.29737 +6.39631,1.21184,-1.56317,-1.54642,-1.02571,1.76587,-0.29695 +6.40553,1.21212,-1.56201,-1.54824,-1.02499,1.76572,-0.29671 +6.41475,1.21266,-1.55978,-1.55174,-1.02364,1.76542,-0.29624 +6.42396,1.21316,-1.55773,-1.55494,-1.02240,1.76514,-0.29580 +6.43318,1.21365,-1.55584,-1.55790,-1.02125,1.76488,-0.29537 +6.44240,1.21408,-1.55462,-1.55975,-1.02054,1.76464,-0.29500 +6.45161,1.21528,-1.55192,-1.56369,-1.01912,1.76398,-0.29397 +6.46083,1.21639,-1.54945,-1.56730,-1.01780,1.76338,-0.29302 +6.47005,1.21741,-1.54718,-1.57063,-1.01658,1.76282,-0.29214 +6.47926,1.21836,-1.54510,-1.57368,-1.01546,1.76231,-0.29133 +6.48848,1.21922,-1.54320,-1.57648,-1.01442,1.76183,-0.29058 +6.49770,1.21936,-1.54296,-1.57682,-1.01430,1.76175,-0.29046 +6.50691,1.22071,-1.54064,-1.58006,-1.01316,1.76102,-0.28931 +6.51613,1.22196,-1.53852,-1.58304,-1.01211,1.76034,-0.28824 +6.52535,1.22310,-1.53657,-1.58578,-1.01113,1.75971,-0.28726 +6.53456,1.22376,-1.53555,-1.58718,-1.01065,1.75935,-0.28670 +6.54378,1.22597,-1.53284,-1.59066,-1.00953,1.75815,-0.28482 +6.55300,1.22799,-1.53036,-1.59387,-1.00850,1.75704,-0.28310 +6.56221,1.22985,-1.52809,-1.59681,-1.00755,1.75603,-0.28151 +6.57143,1.23156,-1.52600,-1.59951,-1.00667,1.75509,-0.28006 +6.58065,1.23313,-1.52409,-1.60200,-1.00585,1.75423,-0.27872 +6.58986,1.23458,-1.52234,-1.60428,-1.00509,1.75343,-0.27748 +6.59908,1.23477,-1.52214,-1.60453,-1.00501,1.75333,-0.27732 +6.60829,1.23664,-1.52020,-1.60694,-1.00427,1.75230,-0.27573 +6.61751,1.23835,-1.51841,-1.60915,-1.00358,1.75136,-0.27428 +6.62673,1.23984,-1.51689,-1.61103,-1.00299,1.75054,-0.27300 +6.63594,1.24203,-1.51491,-1.61335,-1.00233,1.74934,-0.27114 +6.64516,1.24404,-1.51310,-1.61548,-1.00172,1.74824,-0.26944 +6.65438,1.24588,-1.51144,-1.61744,-1.00115,1.74722,-0.26787 +6.66359,1.24729,-1.51020,-1.61890,-1.00073,1.74645,-0.26668 +6.67281,1.24927,-1.50863,-1.62065,-1.00025,1.74536,-0.26499 +6.68203,1.25121,-1.50714,-1.62228,-0.99982,1.74429,-0.26336 +6.69124,1.25396,-1.50536,-1.62405,-0.99945,1.74278,-0.26102 +6.70046,1.25649,-1.50372,-1.62568,-0.99910,1.74139,-0.25889 +6.70968,1.25881,-1.50223,-1.62717,-0.99878,1.74011,-0.25693 +6.71889,1.26093,-1.50086,-1.62854,-0.99847,1.73894,-0.25513 +6.72811,1.26293,-1.49959,-1.62982,-0.99820,1.73783,-0.25344 +6.73733,1.26521,-1.49824,-1.63109,-0.99796,1.73657,-0.25151 +6.74654,1.26731,-1.49701,-1.63226,-0.99773,1.73542,-0.24974 +6.75576,1.26853,-1.49631,-1.63291,-0.99761,1.73474,-0.24871 +6.76498,1.27089,-1.49512,-1.63390,-0.99749,1.73344,-0.24672 +6.77419,1.27304,-1.49404,-1.63481,-0.99738,1.73224,-0.24490 +6.78341,1.27435,-1.49339,-1.63534,-0.99732,1.73152,-0.24379 +6.79263,1.27724,-1.49206,-1.63635,-0.99727,1.72993,-0.24137 +6.80184,1.27988,-1.49084,-1.63728,-0.99722,1.72847,-0.23915 +6.81106,1.28229,-1.48973,-1.63813,-0.99717,1.72713,-0.23711 +6.82028,1.28450,-1.48871,-1.63892,-0.99712,1.72590,-0.23525 +6.82949,1.28598,-1.48804,-1.63944,-0.99709,1.72508,-0.23401 +6.83871,1.28830,-1.48703,-1.64017,-0.99707,1.72379,-0.23206 +6.84793,1.29042,-1.48610,-1.64085,-0.99706,1.72261,-0.23027 +6.85714,1.29087,-1.48591,-1.64099,-0.99706,1.72236,-0.22989 +6.86636,1.29329,-1.48489,-1.64170,-0.99707,1.72102,-0.22786 +6.87558,1.29550,-1.48396,-1.64235,-0.99708,1.71979,-0.22600 +6.88479,1.29678,-1.48343,-1.64271,-0.99709,1.71908,-0.22493 +6.89401,1.29914,-1.48258,-1.64318,-0.99719,1.71776,-0.22294 +6.90323,1.30130,-1.48180,-1.64362,-0.99728,1.71656,-0.22113 +6.91244,1.30194,-1.48158,-1.64374,-0.99730,1.71620,-0.22059 +6.92166,1.30408,-1.48086,-1.64408,-0.99742,1.71501,-0.21879 +6.93088,1.30453,-1.48073,-1.64413,-0.99746,1.71476,-0.21842 +6.94009,1.30680,-1.48009,-1.64429,-0.99766,1.71349,-0.21651 +6.94931,1.30856,-1.47965,-1.64435,-0.99784,1.71251,-0.21504 +6.95853,1.31125,-1.47932,-1.64390,-0.99832,1.71102,-0.21279 +6.96774,1.31371,-1.47902,-1.64348,-0.99876,1.70965,-0.21073 +6.97696,1.31596,-1.47874,-1.64310,-0.99916,1.70839,-0.20885 +6.98618,1.31788,-1.47855,-1.64271,-0.99953,1.70732,-0.20725 +6.99539,1.32042,-1.47858,-1.64174,-1.00018,1.70591,-0.20513 +7.00461,1.32274,-1.47862,-1.64085,-1.00078,1.70461,-0.20319 +7.01382,1.32485,-1.47865,-1.64003,-1.00133,1.70343,-0.20142 +7.02304,1.32652,-1.47880,-1.63921,-1.00183,1.70250,-0.20003 +7.03226,1.32932,-1.47994,-1.63642,-1.00317,1.70093,-0.19770 +7.04147,1.33188,-1.48099,-1.63385,-1.00440,1.69951,-0.19557 +7.05069,1.33420,-1.48196,-1.63149,-1.00555,1.69821,-0.19364 +7.05991,1.33631,-1.48285,-1.62933,-1.00660,1.69703,-0.19189 +7.06912,1.33823,-1.48367,-1.62734,-1.00757,1.69595,-0.19029 +7.07834,1.33998,-1.48442,-1.62551,-1.00846,1.69497,-0.18883 +7.08756,1.34157,-1.48512,-1.62383,-1.00929,1.69408,-0.18750 +7.09677,1.34173,-1.48522,-1.62361,-1.00939,1.69399,-0.18737 +7.10599,1.34326,-1.48621,-1.62148,-1.01037,1.69312,-0.18609 +7.11521,1.34467,-1.48718,-1.61944,-1.01131,1.69233,-0.18492 +7.12442,1.34609,-1.48856,-1.61674,-1.01248,1.69153,-0.18374 +7.13364,1.34738,-1.48982,-1.61427,-1.01356,1.69080,-0.18267 +7.14286,1.34855,-1.49098,-1.61200,-1.01456,1.69014,-0.18170 +7.15207,1.34877,-1.49129,-1.61142,-1.01480,1.69002,-0.18151 +7.16129,1.34984,-1.49325,-1.60792,-1.01623,1.68941,-0.18062 +7.17051,1.35080,-1.49504,-1.60471,-1.01754,1.68887,-0.17982 +7.17972,1.35168,-1.49668,-1.60176,-1.01876,1.68837,-0.17910 +7.18894,1.35246,-1.49819,-1.59904,-1.01989,1.68793,-0.17845 +7.19816,1.35282,-1.49896,-1.59768,-1.02045,1.68772,-0.17815 +7.20737,1.35343,-1.50084,-1.59444,-1.02175,1.68738,-0.17765 +7.21659,1.35397,-1.50256,-1.59147,-1.02295,1.68707,-0.17720 +7.22581,1.35443,-1.50405,-1.58888,-1.02400,1.68681,-0.17682 +7.23502,1.35494,-1.50620,-1.58523,-1.02544,1.68652,-0.17640 +7.24424,1.35541,-1.50817,-1.58188,-1.02678,1.68625,-0.17602 +7.25346,1.35583,-1.50997,-1.57879,-1.02802,1.68601,-0.17567 +7.26267,1.35619,-1.51168,-1.57587,-1.02920,1.68581,-0.17537 +7.27189,1.35646,-1.51375,-1.57241,-1.03056,1.68566,-0.17516 +7.28111,1.35669,-1.51565,-1.56922,-1.03183,1.68552,-0.17497 +7.29032,1.35689,-1.51739,-1.56629,-1.03300,1.68540,-0.17481 +7.29954,1.35692,-1.51765,-1.56586,-1.03316,1.68539,-0.17479 +7.30876,1.35712,-1.52015,-1.56171,-1.03478,1.68528,-0.17463 +7.31797,1.35729,-1.52245,-1.55790,-1.03627,1.68518,-0.17449 +7.32719,1.35744,-1.52455,-1.55439,-1.03766,1.68509,-0.17437 +7.33641,1.35758,-1.52648,-1.55116,-1.03895,1.68502,-0.17427 +7.34562,1.35769,-1.52825,-1.54818,-1.04014,1.68495,-0.17418 +7.35484,1.35768,-1.52853,-1.54774,-1.04032,1.68496,-0.17419 +7.36406,1.35761,-1.53116,-1.54345,-1.04197,1.68500,-0.17426 +7.37327,1.35754,-1.53357,-1.53951,-1.04350,1.68504,-0.17433 +7.38249,1.35747,-1.53578,-1.53588,-1.04493,1.68508,-0.17439 +7.39171,1.35739,-1.53781,-1.53253,-1.04625,1.68512,-0.17446 +7.40092,1.35732,-1.53967,-1.52945,-1.04747,1.68516,-0.17453 +7.41014,1.35728,-1.54026,-1.52848,-1.04786,1.68518,-0.17457 +7.41935,1.35705,-1.54253,-1.52480,-1.04929,1.68532,-0.17477 +7.42857,1.35683,-1.54461,-1.52141,-1.05061,1.68544,-0.17496 +7.43779,1.35662,-1.54652,-1.51829,-1.05184,1.68556,-0.17514 +7.44700,1.35654,-1.54729,-1.51704,-1.05234,1.68560,-0.17521 +7.45622,1.35635,-1.54940,-1.51359,-1.05370,1.68571,-0.17538 +7.46544,1.35617,-1.55133,-1.51041,-1.05496,1.68581,-0.17554 +7.47465,1.35607,-1.55244,-1.50859,-1.05568,1.68587,-0.17563 +7.48387,1.35586,-1.55436,-1.50544,-1.05693,1.68599,-0.17582 +7.49309,1.35577,-1.55511,-1.50422,-1.05742,1.68604,-0.17589 +7.50230,1.35554,-1.55704,-1.50105,-1.05867,1.68618,-0.17610 +7.51152,1.35542,-1.55797,-1.49954,-1.05927,1.68624,-0.17620 +7.52074,1.35523,-1.55907,-1.49772,-1.06001,1.68635,-0.17636 +7.52995,1.35536,-1.55723,-1.50057,-1.05905,1.68628,-0.17626 +7.53917,1.35595,-1.55418,-1.50522,-1.05747,1.68596,-0.17576 +7.54839,1.35650,-1.55138,-1.50948,-1.05601,1.68565,-0.17529 +7.55760,1.35702,-1.54881,-1.51340,-1.05467,1.68537,-0.17486 +7.56682,1.35750,-1.54646,-1.51700,-1.05342,1.68510,-0.17446 +7.57604,1.35794,-1.54430,-1.52030,-1.05227,1.68486,-0.17408 +7.58525,1.35835,-1.54232,-1.52334,-1.05120,1.68462,-0.17374 +7.59447,1.35852,-1.54165,-1.52435,-1.05085,1.68453,-0.17359 +7.60369,1.35940,-1.53891,-1.52847,-1.04943,1.68404,-0.17286 +7.61290,1.36020,-1.53639,-1.53226,-1.04813,1.68359,-0.17219 +7.62212,1.36095,-1.53408,-1.53574,-1.04692,1.68318,-0.17156 +7.63134,1.36164,-1.53196,-1.53893,-1.04580,1.68279,-0.17098 +7.64055,1.36228,-1.53001,-1.54187,-1.04476,1.68243,-0.17044 +7.64977,1.36245,-1.52965,-1.54239,-1.04459,1.68233,-0.17030 +7.65899,1.36412,-1.52621,-1.54738,-1.04293,1.68141,-0.16891 +7.66820,1.36566,-1.52305,-1.55196,-1.04141,1.68055,-0.16762 +7.67742,1.36708,-1.52015,-1.55617,-1.03999,1.67976,-0.16644 +7.68664,1.36838,-1.51749,-1.56003,-1.03869,1.67902,-0.16534 +7.69585,1.36959,-1.51506,-1.56358,-1.03749,1.67834,-0.16433 +7.70507,1.37070,-1.51282,-1.56683,-1.03638,1.67772,-0.16340 +7.71429,1.37173,-1.51077,-1.56983,-1.03535,1.67714,-0.16254 +7.72350,1.37261,-1.50903,-1.57238,-1.03448,1.67664,-0.16180 +7.73272,1.37381,-1.50682,-1.57556,-1.03341,1.67597,-0.16080 +7.74194,1.37491,-1.50480,-1.57848,-1.03242,1.67534,-0.15987 +7.75115,1.37584,-1.50314,-1.58086,-1.03162,1.67482,-0.15910 +7.76037,1.37784,-1.49988,-1.58544,-1.03016,1.67370,-0.15743 +7.76959,1.37968,-1.49689,-1.58964,-1.02881,1.67267,-0.15590 +7.77880,1.38138,-1.49415,-1.59350,-1.02757,1.67172,-0.15448 +7.78802,1.38294,-1.49163,-1.59704,-1.02642,1.67084,-0.15318 +7.79724,1.38438,-1.48933,-1.60030,-1.02537,1.67002,-0.15197 +7.80645,1.38570,-1.48721,-1.60329,-1.02439,1.66927,-0.15086 +7.81567,1.38692,-1.48527,-1.60603,-1.02349,1.66858,-0.14984 +7.82488,1.38768,-1.48412,-1.60765,-1.02296,1.66816,-0.14921 +7.83410,1.38937,-1.48183,-1.61078,-1.02199,1.66720,-0.14780 +7.84332,1.39094,-1.47973,-1.61366,-1.02109,1.66632,-0.14650 +7.85253,1.39237,-1.47781,-1.61630,-1.02027,1.66551,-0.14530 +7.86175,1.39356,-1.47628,-1.61838,-1.01962,1.66484,-0.14431 +7.87097,1.39591,-1.47371,-1.62173,-1.01868,1.66352,-0.14236 +7.88018,1.39807,-1.47135,-1.62481,-1.01780,1.66230,-0.14056 +7.88940,1.40006,-1.46919,-1.62764,-1.01700,1.66118,-0.13891 +7.89862,1.40189,-1.46721,-1.63024,-1.01625,1.66015,-0.13739 +7.90783,1.40357,-1.46539,-1.63262,-1.01556,1.65920,-0.13599 +7.91705,1.40487,-1.46401,-1.63443,-1.01505,1.65846,-0.13490 +7.92627,1.40690,-1.46209,-1.63686,-1.01440,1.65731,-0.13322 +7.93548,1.40877,-1.46033,-1.63909,-1.01380,1.65626,-0.13167 +7.94470,1.41059,-1.45866,-1.64120,-1.01324,1.65523,-0.13015 +7.95392,1.41326,-1.45659,-1.64366,-1.01268,1.65373,-0.12794 +7.96313,1.41571,-1.45469,-1.64591,-1.01216,1.65235,-0.12591 +7.97235,1.41796,-1.45296,-1.64798,-1.01169,1.65107,-0.12405 +7.98157,1.42003,-1.45137,-1.64988,-1.01124,1.64991,-0.12233 +7.99078,1.42199,-1.44988,-1.65165,-1.01084,1.64880,-0.12071 +8.00000,1.42434,-1.44828,-1.65348,-1.01047,1.64747,-0.11876 +8.00922,1.42650,-1.44681,-1.65516,-1.01013,1.64625,-0.11697 +8.01843,1.42864,-1.44540,-1.65676,-1.00982,1.64503,-0.11520 +8.02765,1.43201,-1.44351,-1.65872,-1.00955,1.64314,-0.11242 +8.03687,1.43509,-1.44178,-1.66053,-1.00931,1.64141,-0.10988 +8.04608,1.43792,-1.44020,-1.66218,-1.00908,1.63981,-0.10754 +8.05530,1.44051,-1.43875,-1.66370,-1.00887,1.63834,-0.10540 +8.06452,1.44289,-1.43742,-1.66510,-1.00868,1.63699,-0.10343 +8.07373,1.44507,-1.43620,-1.66638,-1.00850,1.63575,-0.10163 +8.08295,1.44618,-1.43560,-1.66702,-1.00842,1.63512,-0.10071 +8.09217,1.44893,-1.43419,-1.66843,-1.00828,1.63357,-0.09844 +8.10138,1.45145,-1.43291,-1.66972,-1.00816,1.63214,-0.09636 +8.11060,1.45376,-1.43173,-1.67091,-1.00804,1.63083,-0.09445 +8.11982,1.45580,-1.43071,-1.67193,-1.00795,1.62967,-0.09276 +8.12903,1.45903,-1.42931,-1.67320,-1.00794,1.62785,-0.09010 +8.13825,1.46198,-1.42802,-1.67437,-1.00793,1.62618,-0.08767 +8.14747,1.46469,-1.42685,-1.67544,-1.00792,1.62464,-0.08543 +8.15668,1.46718,-1.42578,-1.67643,-1.00791,1.62323,-0.08338 +8.16590,1.46945,-1.42479,-1.67734,-1.00790,1.62194,-0.08150 +8.17512,1.47037,-1.42441,-1.67768,-1.00790,1.62142,-0.08075 +8.18433,1.47292,-1.42343,-1.67850,-1.00796,1.61997,-0.07864 +8.19355,1.47526,-1.42254,-1.67925,-1.00802,1.61864,-0.07671 +8.20276,1.47662,-1.42204,-1.67966,-1.00806,1.61787,-0.07558 +8.21198,1.47921,-1.42126,-1.68018,-1.00823,1.61640,-0.07345 +8.22120,1.48158,-1.42054,-1.68066,-1.00839,1.61505,-0.07150 +8.23041,1.48301,-1.42014,-1.68090,-1.00851,1.61424,-0.07032 +8.23963,1.48606,-1.41955,-1.68101,-1.00889,1.61251,-0.06781 +8.24885,1.48886,-1.41901,-1.68110,-1.00925,1.61092,-0.06551 +8.25806,1.49142,-1.41852,-1.68119,-1.00957,1.60947,-0.06340 +8.26728,1.49376,-1.41807,-1.68128,-1.00987,1.60814,-0.06147 +8.27650,1.49514,-1.41784,-1.68128,-1.01006,1.60735,-0.06034 +8.28571,1.49785,-1.41761,-1.68094,-1.01056,1.60582,-0.05811 +8.29493,1.50033,-1.41740,-1.68063,-1.01102,1.60441,-0.05607 +8.30415,1.50260,-1.41721,-1.68035,-1.01144,1.60312,-0.05420 +8.31336,1.50357,-1.41716,-1.68018,-1.01164,1.60257,-0.05341 +8.32258,1.50669,-1.41721,-1.67932,-1.01237,1.60080,-0.05085 +8.33180,1.50954,-1.41725,-1.67854,-1.01305,1.59918,-0.04850 +8.34101,1.51214,-1.41730,-1.67782,-1.01368,1.59770,-0.04636 +8.35023,1.51452,-1.41734,-1.67716,-1.01425,1.59635,-0.04441 +8.35945,1.51669,-1.41738,-1.67655,-1.01478,1.59511,-0.04262 +8.36866,1.51741,-1.41741,-1.67633,-1.01497,1.59470,-0.04203 +8.37788,1.52035,-1.41761,-1.67529,-1.01575,1.59304,-0.03962 +8.38710,1.52302,-1.41780,-1.67434,-1.01648,1.59152,-0.03743 +8.39631,1.52547,-1.41797,-1.67347,-1.01715,1.59013,-0.03542 +8.40553,1.52770,-1.41813,-1.67267,-1.01776,1.58886,-0.03358 +8.41475,1.52960,-1.41828,-1.67197,-1.01829,1.58778,-0.03202 +8.42396,1.53203,-1.41854,-1.67098,-1.01900,1.58640,-0.03002 +8.43318,1.53425,-1.41878,-1.67006,-1.01966,1.58513,-0.02820 +8.44240,1.53634,-1.41902,-1.66918,-1.02029,1.58394,-0.02648 +8.45161,1.53875,-1.41945,-1.66794,-1.02108,1.58258,-0.02450 +8.46083,1.54095,-1.41985,-1.66680,-1.02181,1.58132,-0.02270 +8.47005,1.54295,-1.42021,-1.66576,-1.02249,1.58018,-0.02105 +8.47926,1.54356,-1.42032,-1.66544,-1.02269,1.57984,-0.02055 +8.48848,1.54567,-1.42074,-1.66428,-1.02342,1.57864,-0.01882 +8.49770,1.54745,-1.42112,-1.66327,-1.02405,1.57762,-0.01736 +8.50691,1.54956,-1.42178,-1.66176,-1.02490,1.57642,-0.01562 +8.51613,1.55149,-1.42239,-1.66037,-1.02568,1.57532,-0.01404 +8.52535,1.55262,-1.42278,-1.65949,-1.02616,1.57468,-0.01311 +8.53456,1.55475,-1.42388,-1.65732,-1.02724,1.57347,-0.01137 +8.54378,1.55668,-1.42489,-1.65532,-1.02823,1.57237,-0.00978 +8.55300,1.55844,-1.42581,-1.65349,-1.02915,1.57136,-0.00834 +8.56221,1.56009,-1.42675,-1.65165,-1.03005,1.57043,-0.00699 +8.57143,1.56191,-1.42843,-1.64865,-1.03136,1.56939,-0.00550 +8.58065,1.56357,-1.42998,-1.64589,-1.03258,1.56844,-0.00414 +8.58986,1.56508,-1.43139,-1.64336,-1.03370,1.56759,-0.00290 +8.59908,1.56644,-1.43269,-1.64103,-1.03474,1.56680,-0.00178 +8.60829,1.56770,-1.43391,-1.63883,-1.03573,1.56609,-0.00075 +8.61751,1.56895,-1.43537,-1.63627,-1.03683,1.56537,0.00027 +8.62673,1.57009,-1.43671,-1.63392,-1.03785,1.56472,0.00121 +8.63594,1.57053,-1.43733,-1.63286,-1.03829,1.56447,0.00157 +8.64516,1.57167,-1.43959,-1.62910,-1.03979,1.56382,0.00249 +8.65438,1.57270,-1.44166,-1.62565,-1.04117,1.56323,0.00333 +8.66359,1.57363,-1.44356,-1.62247,-1.04246,1.56270,0.00409 +8.67281,1.57447,-1.44531,-1.61955,-1.04364,1.56222,0.00478 +8.68203,1.57523,-1.44690,-1.61686,-1.04474,1.56178,0.00541 +8.69124,1.57558,-1.44770,-1.61552,-1.04529,1.56157,0.00570 +8.70046,1.57626,-1.44961,-1.61237,-1.04653,1.56119,0.00624 +8.70968,1.57686,-1.45135,-1.60948,-1.04768,1.56084,0.00674 +8.71889,1.57736,-1.45286,-1.60698,-1.04868,1.56055,0.00714 +8.72811,1.57788,-1.45495,-1.60358,-1.04999,1.56026,0.00756 +8.73733,1.57834,-1.45686,-1.60045,-1.05121,1.55999,0.00794 +8.74654,1.57876,-1.45862,-1.59757,-1.05234,1.55975,0.00828 +8.75576,1.57891,-1.45932,-1.59642,-1.05279,1.55967,0.00840 +8.76498,1.57917,-1.46131,-1.59321,-1.05401,1.55951,0.00861 +8.77419,1.57941,-1.46313,-1.59026,-1.05515,1.55937,0.00880 +8.78341,1.57950,-1.46383,-1.58911,-1.05559,1.55932,0.00887 +8.79263,1.57971,-1.46565,-1.58617,-1.05672,1.55920,0.00904 +8.80184,1.57975,-1.46623,-1.58523,-1.05707,1.55918,0.00907 +8.81106,1.57974,-1.46852,-1.58160,-1.05841,1.55918,0.00905 +8.82028,1.57972,-1.47062,-1.57826,-1.05965,1.55919,0.00903 +8.82949,1.57970,-1.47254,-1.57519,-1.06080,1.55920,0.00901 +8.83871,1.57966,-1.47370,-1.57334,-1.06149,1.55922,0.00897 +8.84793,1.57934,-1.47617,-1.56947,-1.06288,1.55939,0.00871 +8.85714,1.57905,-1.47843,-1.56591,-1.06417,1.55955,0.00846 +8.86636,1.57878,-1.48051,-1.56263,-1.06536,1.55970,0.00823 +8.87558,1.57853,-1.48241,-1.55961,-1.06647,1.55985,0.00802 +8.88479,1.57845,-1.48285,-1.55893,-1.06672,1.55989,0.00796 +8.89401,1.57794,-1.48526,-1.55517,-1.06805,1.56018,0.00752 +8.90323,1.57746,-1.48747,-1.55171,-1.06929,1.56045,0.00712 +8.91244,1.57702,-1.48950,-1.54852,-1.07044,1.56070,0.00676 +8.92166,1.57666,-1.49108,-1.54603,-1.07135,1.56090,0.00646 +8.93088,1.57600,-1.49362,-1.54209,-1.07274,1.56127,0.00590 +8.94009,1.57539,-1.49594,-1.53846,-1.07403,1.56162,0.00540 +8.94931,1.57483,-1.49808,-1.53512,-1.07523,1.56194,0.00493 +8.95853,1.57432,-1.50004,-1.53204,-1.07634,1.56223,0.00450 +8.96774,1.57412,-1.50080,-1.53084,-1.07678,1.56235,0.00433 +8.97696,1.57356,-1.50277,-1.52775,-1.07789,1.56266,0.00386 +8.98618,1.57335,-1.50352,-1.52657,-1.07832,1.56278,0.00368 +8.99539,1.57285,-1.50506,-1.52416,-1.07919,1.56306,0.00327 +9.00461,1.57211,-1.50707,-1.52103,-1.08029,1.56349,0.00265 +9.01382,1.57162,-1.50840,-1.51897,-1.08102,1.56377,0.00224 +9.02304,1.57101,-1.50993,-1.51659,-1.08186,1.56411,0.00173 +9.03226,1.57013,-1.51194,-1.51350,-1.08294,1.56461,0.00100 +9.04147,1.56951,-1.51329,-1.51141,-1.08367,1.56497,0.00049 +9.05069,1.56827,-1.51548,-1.50811,-1.08477,1.56567,-0.00054 +9.05991,1.56713,-1.51748,-1.50507,-1.08580,1.56631,-0.00148 +9.06912,1.56605,-1.51937,-1.50220,-1.08678,1.56692,-0.00237 +9.07834,1.56472,-1.52148,-1.49902,-1.08783,1.56768,-0.00347 +9.08756,1.56351,-1.52342,-1.49609,-1.08881,1.56837,-0.00448 +9.09677,1.56253,-1.52495,-1.49379,-1.08958,1.56892,-0.00528 +9.10599,1.56073,-1.52746,-1.49007,-1.09077,1.56994,-0.00676 +9.11521,1.55909,-1.52977,-1.48664,-1.09188,1.57086,-0.00812 +9.12442,1.55760,-1.53189,-1.48347,-1.09292,1.57171,-0.00935 +9.13364,1.55623,-1.53384,-1.48055,-1.09389,1.57249,-0.01049 +9.14286,1.55498,-1.53563,-1.47785,-1.09479,1.57320,-0.01152 +9.15207,1.55483,-1.53585,-1.47753,-1.09490,1.57329,-0.01165 +9.16129,1.55332,-1.53790,-1.47447,-1.09590,1.57415,-0.01290 +9.17051,1.55195,-1.53979,-1.47164,-1.09684,1.57493,-0.01403 +9.17972,1.55092,-1.54121,-1.46952,-1.09755,1.57551,-0.01488 +9.18894,1.54974,-1.54285,-1.46705,-1.09837,1.57619,-0.01586 +9.19816,1.54812,-1.54504,-1.46380,-1.09943,1.57711,-0.01721 +9.20737,1.54663,-1.54705,-1.46080,-1.10042,1.57795,-0.01843 +9.21659,1.54528,-1.54889,-1.45803,-1.10134,1.57873,-0.01955 +9.22581,1.54451,-1.54996,-1.45644,-1.10188,1.57917,-0.02020 +9.23502,1.54316,-1.55183,-1.45362,-1.10282,1.57994,-0.02132 +9.24424,1.54220,-1.55314,-1.45166,-1.10348,1.58048,-0.02211 +9.25346,1.54031,-1.55552,-1.44815,-1.10461,1.58156,-0.02367 +9.26267,1.53858,-1.55771,-1.44490,-1.10567,1.58254,-0.02510 +9.27189,1.53700,-1.55972,-1.44191,-1.10666,1.58344,-0.02641 +9.28111,1.53556,-1.56157,-1.43914,-1.10758,1.58426,-0.02760 +9.29032,1.53445,-1.56301,-1.43700,-1.10830,1.58490,-0.02852 +9.29954,1.53278,-1.56516,-1.43379,-1.10936,1.58585,-0.02991 +9.30876,1.53125,-1.56714,-1.43083,-1.11035,1.58672,-0.03117 +9.31797,1.52986,-1.56897,-1.42809,-1.11128,1.58752,-0.03233 +9.32719,1.52903,-1.57004,-1.42648,-1.11182,1.58799,-0.03301 +9.33641,1.52738,-1.57210,-1.42343,-1.11283,1.58893,-0.03439 +9.34562,1.52586,-1.57399,-1.42060,-1.11378,1.58979,-0.03564 +9.35484,1.52448,-1.57573,-1.41799,-1.11466,1.59058,-0.03678 +9.36406,1.52417,-1.57610,-1.41745,-1.11485,1.59076,-0.03704 +9.37327,1.52248,-1.57804,-1.41459,-1.11578,1.59172,-0.03844 +9.38249,1.52093,-1.57982,-1.41195,-1.11666,1.59260,-0.03972 +9.39171,1.51964,-1.58132,-1.40973,-1.11741,1.59334,-0.04080 +9.40092,1.51816,-1.58301,-1.40722,-1.11824,1.59419,-0.04202 +9.41014,1.51772,-1.58351,-1.40649,-1.11849,1.59444,-0.04238 +9.41935,1.51623,-1.58519,-1.40400,-1.11931,1.59529,-0.04362 +9.42857,1.51575,-1.58571,-1.40324,-1.11956,1.59556,-0.04402 +9.43779,1.51388,-1.58761,-1.40048,-1.12045,1.59663,-0.04556 +9.44700,1.51217,-1.58937,-1.39792,-1.12128,1.59760,-0.04698 +9.45622,1.51062,-1.59099,-1.39555,-1.12206,1.59848,-0.04826 +9.46544,1.51016,-1.59147,-1.39486,-1.12229,1.59875,-0.04864 +9.47465,1.50860,-1.59308,-1.39249,-1.12306,1.59964,-0.04994 +9.48387,1.50813,-1.59356,-1.39181,-1.12329,1.59990,-0.05032 +9.49309,1.50646,-1.59511,-1.38957,-1.12400,1.60085,-0.05170 +9.50230,1.50580,-1.59571,-1.38872,-1.12427,1.60123,-0.05225 +9.51152,1.50397,-1.59723,-1.38659,-1.12492,1.60227,-0.05377 +9.52074,1.50243,-1.59850,-1.38480,-1.12548,1.60315,-0.05503 +9.52995,1.50071,-1.59986,-1.38290,-1.12605,1.60413,-0.05646 +9.53917,1.50049,-1.60001,-1.38270,-1.12611,1.60425,-0.05664 +9.54839,1.49847,-1.60142,-1.38080,-1.12665,1.60540,-0.05831 +9.55760,1.49662,-1.60273,-1.37903,-1.12716,1.60645,-0.05983 +9.56682,1.49590,-1.60322,-1.37837,-1.12735,1.60686,-0.06043 +9.57604,1.49399,-1.60439,-1.37685,-1.12776,1.60794,-0.06200 +9.58525,1.49323,-1.60484,-1.37626,-1.12791,1.60837,-0.06263 +9.59447,1.49119,-1.60602,-1.37477,-1.12829,1.60954,-0.06432 +9.60369,1.48932,-1.60711,-1.37338,-1.12865,1.61060,-0.06586 +9.61290,1.48911,-1.60722,-1.37323,-1.12868,1.61072,-0.06603 +9.62212,1.48715,-1.60832,-1.37186,-1.12902,1.61183,-0.06765 +9.63134,1.48602,-1.60894,-1.37108,-1.12921,1.61247,-0.06858 +9.64055,1.48404,-1.60991,-1.36993,-1.12946,1.61360,-0.07021 +9.64977,1.48310,-1.61037,-1.36938,-1.12958,1.61413,-0.07099 +9.65899,1.48108,-1.61135,-1.36824,-1.12982,1.61528,-0.07265 +9.66820,1.47833,-1.61259,-1.36684,-1.13007,1.61683,-0.07491 +9.67742,1.47583,-1.61375,-1.36553,-1.13030,1.61825,-0.07698 +9.68664,1.47354,-1.61481,-1.36432,-1.13054,1.61955,-0.07886 +9.69585,1.47146,-1.61580,-1.36318,-1.13076,1.62073,-0.08058 +9.70507,1.46952,-1.61672,-1.36214,-1.13097,1.62183,-0.08218 +9.71429,1.46741,-1.61760,-1.36118,-1.13111,1.62303,-0.08392 +9.72350,1.46546,-1.61843,-1.36029,-1.13126,1.62414,-0.08553 +9.73272,1.46344,-1.61930,-1.35936,-1.13141,1.62529,-0.08721 +9.74194,1.46225,-1.61981,-1.35880,-1.13150,1.62596,-0.08819 +9.75115,1.45996,-1.62080,-1.35775,-1.13166,1.62726,-0.09008 +9.76037,1.45787,-1.62171,-1.35678,-1.13182,1.62844,-0.09181 +9.76959,1.45594,-1.62255,-1.35587,-1.13196,1.62954,-0.09340 +9.77880,1.45401,-1.62330,-1.35512,-1.13205,1.63064,-0.09499 +9.78802,1.45380,-1.62338,-1.35504,-1.13206,1.63076,-0.09517 +9.79724,1.45178,-1.62419,-1.35423,-1.13216,1.63190,-0.09684 +9.80645,1.45064,-1.62465,-1.35376,-1.13222,1.63255,-0.09778 +9.81567,1.44871,-1.62542,-1.35298,-1.13232,1.63365,-0.09938 +9.82488,1.44755,-1.62584,-1.35259,-1.13234,1.63431,-0.10034 +9.83410,1.44552,-1.62659,-1.35189,-1.13240,1.63545,-0.10201 +9.84332,1.44437,-1.62701,-1.35149,-1.13243,1.63611,-0.10296 +9.85253,1.44244,-1.62775,-1.35078,-1.13250,1.63720,-0.10456 +9.86175,1.44225,-1.62781,-1.35073,-1.13250,1.63731,-0.10472 +9.87097,1.44109,-1.62819,-1.35042,-1.13249,1.63797,-0.10567 +9.88018,1.43906,-1.62879,-1.34997,-1.13245,1.63912,-0.10735 +9.88940,1.43791,-1.62914,-1.34971,-1.13242,1.63977,-0.10830 +9.89862,1.43598,-1.62975,-1.34922,-1.13240,1.64087,-0.10990 +9.90783,1.43579,-1.62981,-1.34917,-1.13240,1.64097,-0.11006 +9.91705,1.43482,-1.63012,-1.34893,-1.13239,1.64152,-0.11086 +9.92627,1.43278,-1.63072,-1.34850,-1.13233,1.64268,-0.11254 +9.93548,1.43164,-1.63105,-1.34828,-1.13229,1.64333,-0.11349 +9.94470,1.43027,-1.63138,-1.34810,-1.13221,1.64410,-0.11462 +9.95392,1.42815,-1.63189,-1.34786,-1.13206,1.64530,-0.11637 +9.96313,1.42622,-1.63235,-1.34764,-1.13193,1.64639,-0.11796 +9.97235,1.42603,-1.63239,-1.34763,-1.13191,1.64650,-0.11813 +9.98157,1.42489,-1.63262,-1.34758,-1.13181,1.64715,-0.11907 +9.99078,1.42375,-1.63287,-1.34750,-1.13171,1.64779,-0.12001 +10.00000,1.42282,-1.63307,-1.34743,-1.13163,1.64832,-0.12078 diff --git a/dmp/my_sol/run_dmp.py b/dmp/my_sol/run_dmp.py index be774e58af25b8e02c40a990de8fdc460e8f7154..554104b7a0b0e1be5c274d8b934c6b89b23e46c2 100644 --- a/dmp/my_sol/run_dmp.py +++ b/dmp/my_sol/run_dmp.py @@ -10,26 +10,22 @@ import os import time import signal import matplotlib.pyplot as plt +import sys +import copy +sys.path.insert(0, '../../util') +from give_me_the_calibrated_model import get_model -# TODO -# add scaling (point of albin's paper) -# generate this from other trajectories - - -#urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" -#urdf_path_absolute = os.path.abspath(urdf_path_relative) -#mesh_dir = "../../robot_descriptions/" -#mesh_dir_absolute = os.path.abspath(mesh_dir) -##print(mesh_dir_absolute) -#model = pin.buildModelFromUrdf(urdf_path_absolute) -##print(model) -#data = pin.Data(model) -##print(data) +urdf_path_relative = "../../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" +urdf_path_absolute = os.path.abspath(urdf_path_relative) +mesh_dir = "../../robot_descriptions/" +mesh_dir_absolute = os.path.abspath(mesh_dir) +model, data = get_model(urdf_path_absolute, mesh_dir_absolute) rtde_control = RTDEControl("192.168.1.102") rtde_receive = RTDEReceive("192.168.1.102") rtde_io = RTDEIOInterface("192.168.1.102") -rtde_io.setSpeedSlider(0.2) +# on scale from 0 to 1 +rtde_io.setSpeedSlider(0.7) # run if marker isn't gripped #gripper = RobotiqGripper() @@ -48,10 +44,10 @@ dmp_poss = np.zeros((N_ITER, 6)) dqs = np.zeros((N_ITER, 6)) dmp_vels = np.zeros((N_ITER, 6)) + def handler(signum, frame): print('sending 100 speedjs full of zeros') for i in range(100): - rtde_control.endFreedriveMode() vel_cmd = np.zeros(6) rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500) @@ -82,6 +78,9 @@ def handler(signum, frame): signal.signal(signal.SIGINT, handler) dmp = DMP() +current_pose = rtde_receive.getActualTCPPose() +current_pose[2] = current_pose[2] + 0.03 +rtde_control.moveL(current_pose) rtde_control.moveJ(dmp.pos.reshape((6,))) # TODO check that you're there instead of a sleep #t.sleep(3) @@ -91,11 +90,26 @@ update_rate = 500 dt = 1.0 / update_rate JOINT_ID = 6 +task_frame = [0, 0, 0, 0, 0, 0] +# these are in {0,1} and select which task frame direction compliance is active in +# just be soft everywhere +selection_vector = [1, 1, 1, 1, 1, 1] +# the wrench applied to the environment: +# position is adjusted to achieve the specified wrench +# let's pretend speedjs are this and see what happens (idk honestly) +wrench = [0, 0, 0, 0, 0, 0] +ftype = 2 +# limits for: +# - compliant axes: highest tcp velocities allowed on compliant axes +# - non-compliant axes: maximum tcp position error compared to the program (which prg, +# and where is this set?) +# why these values? +limits = [2, 2, 2, 2, 2, 2] # parameters from yaml config file in albin's repo kp = 2 -#acceleration = 1.7 -acceleration = 0.5 +acceleration = 1.7 +#acceleration = 0.5 if not TEMPORAL_COUPLING: tc = NoTC() @@ -109,6 +123,11 @@ else: a_max = np.ones(6) * 1.7 tc = TCVelAccConstrained(gamma_nominal, gamma_a, v_max, a_max, eps) +# TODO: check sign! +alpha = 0.003 +# lame hack for the current orientation (which it doesn't change so it's ok) +wrench_offset = np.array([-1.07988, -1.407225, -2.63069, 0.071115, -0.0487768, 0.089271]) +wrench_avg = np.zeros((5,6)) print("starting the trajectory") for i in range(N_ITER): @@ -118,16 +137,36 @@ for i in range(N_ITER): # temporal coupling tau = dmp.tau + tc.update(dmp, dt) * dt dmp.set_tau(tau) - q = np.array(rtde_receive.getActualQ()) - dq = np.array(rtde_receive.getActualQd()) - vel_cmd = dmp.vel + kp * (dmp.pos - q.reshape((6,1))) + q = rtde_receive.getActualQ() + # TODO this fucker feel the weight of the gripper, this causes bias -> fix it! + wrench = np.array(rtde_receive.getActualTCPForce()) + wrench_avg[i % 5] = wrench + wrench = np.average(wrench_avg, axis=0) + q6 = np.array(copy.deepcopy(q)) + q.append(0.0) + q.append(0.0) + q = np.array(q) + pin.forwardKinematics(model, data, q) + J = pin.computeJointJacobian(model, data, q, JOINT_ID) + dq = np.array(rtde_receive.getActualQd()).reshape((6,1)) + tau = J.T @ wrench + tau = tau[:6].reshape((6,1)) + vel_cmd = dmp.vel + kp * (dmp.pos - q6.reshape((6,1))) - alpha * tau vel_cmd = vel_cmd.reshape((6,)) vel_cmd = np.clip(vel_cmd, -1 * v_max, v_max) if np.isnan(vel_cmd[0]): break rtde_control.speedJ(vel_cmd, acceleration, dt) - - qs[i] = q.reshape((6,)) + # this is very stupind, but it was quick to implement + #vel_cmd8 = list(vel_cmd) + #vel_cmd8.append(0.0) + #vel_cmd8.append(0.0) + #vel_cmd8 = np.array(vel_cmd8) + #vel_tcp = J @ vel_cmd8 + #vel_tcp = vel_tcp * 10 + #rtde_control.forceMode(task_frame, selection_vector, vel_tcp, ftype, limits) + + qs[i] = q6.reshape((6,)) dmp_poss[i] = dmp.pos.reshape((6,)) dqs[i] = dq.reshape((6,)) dmp_vels[i] = dmp.vel.reshape((6,)) diff --git a/dmp/notes.md b/dmp/notes.md index d623781255144169f87aa81f10c3951c548932db..aeb3bfa15ada961675be7cae16a97ab45dd51361 100644 --- a/dmp/notes.md +++ b/dmp/notes.md @@ -9,13 +9,14 @@ covers everything reasonably. you might want to look into bezier-ing the path into something smooth. but looks OK as is also -# 3D cartesian trajectory: +# 3D cartesian trajectory: DONE ------------------------- just put your pixels onto a plane onto a predefined place with the right coordinate transform. ofc you have the pixel -> mm conversion and mins and maxes. whatever makes sense workspace-wise is good. +- wrote an algorithm to automatically calibrate where the board is TODO: -- write an algorithm to automatically calibrate where the board is -- doing anything else is asinine +- i manually set signs of the rotation matrix rn, would be nice if this was consistent + (also fck rpy, but that's what i have access to) # timed joint trajectory: DONE ----------------------------- @@ -66,3 +67,8 @@ def compute_ctrl(self, target_state, robot_state): return vel_cmd ``` + +# add some impedance to live with errors +-------------------------------------- +- f/t readings are added and works fine for impedance +- TODO: cancel out the gripper weight diff --git a/dmp/todos.md b/dmp/todos.md deleted file mode 100644 index 6ac3bb831992623388fb33de998b165b22caa598..0000000000000000000000000000000000000000 --- a/dmp/todos.md +++ /dev/null @@ -1,12 +0,0 @@ -# trajectory generation is in -/home/gospodar/lund/praxis/UR traj gen -and it's matlab - -# calculating the dmp from the trajectory -is in -TC_DMP_constrainedVelAcc/matlab/DMP.m - -# running the dmp node -TC_DMP_constrainedVelAcc/catkin_ws/src/motion_planning/nodes/dmp_node -it's this file in the github repo - diff --git a/docs/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf b/docs/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf new file mode 100644 index 0000000000000000000000000000000000000000..67fef1114a433f4420353ef8f57d7d74fe9ad5c3 Binary files /dev/null and b/docs/Hand-E_Manual_UniversalRobots_PDF_20220114.pdf differ diff --git a/docs/scriptManual-3.5.4.pdf b/docs/scriptManual-3.5.4.pdf deleted file mode 100644 index 88ceef89c4986a8cf7ecc1701c1e3b44a03dfe7b..0000000000000000000000000000000000000000 Binary files a/docs/scriptManual-3.5.4.pdf and /dev/null differ diff --git a/docs/scriptManual_SW5.11.pdf b/docs/scriptManual_SW5.11.pdf new file mode 100644 index 0000000000000000000000000000000000000000..a91d00c0ec731d65733d6d0f74705b671919b3a5 Binary files /dev/null and b/docs/scriptManual_SW5.11.pdf differ diff --git a/util/calib_board_hacks.py b/util/calib_board_hacks.py index ef356a4e8118cb404665aba0ead363a61209dfda..44309a46af274c95ccb8bd70a2bfdda678b35026 100644 --- a/util/calib_board_hacks.py +++ b/util/calib_board_hacks.py @@ -1,3 +1,9 @@ +# TODO: +# ideally make this a continuous update process +# where you use the previous estimate to try to hit the board at the +# right orientation, thereby making the estimate more precise + + import pinocchio as pin import numpy as np import sys @@ -8,6 +14,7 @@ from pinocchio.visualize import GepettoVisualizer import gepetto.corbaserver from rtde_control import RTDEControlInterface as RTDEControl from rtde_receive import RTDEReceiveInterface as RTDEReceive +from rtde_io import RTDEIOInterface import os import copy import signal @@ -23,6 +30,8 @@ def handler(signum, frame): rtde_control = RTDEControl("192.168.1.102") rtde_receive = RTDEReceive("192.168.1.102") +rtde_io = RTDEIOInterface("192.168.1.102") +rtde_io.setSpeedSlider(0.2) while not rtde_control.isConnected(): continue print("connected") @@ -46,10 +55,49 @@ new_pose = copy.deepcopy(init_pose) # generate 10 and try them out # but let's try to get it done with only 3 to begin with + +def estimate_R(positions): + # find the angle + positions = np.array(positions) + #print("positions") + #print(*positions, sep=',\n') + # the offset does not matter, we only need the angle + # i.e. the normal vector to the plane + n = np.linalg.lstsq(positions, np.ones(len(positions)), rcond=None)[0] + #print("n", *n, sep=',') + # normalize + #n = n - 1 + n = n / np.linalg.norm(n) + #print("n normalized:", *n, sep=',') + for p in positions: + print("cdot", p @ n) + z_new = n + x_new = np.array([1.0, 0.0, 0.0]) + y_new = np.cross(x_new, z_new) + # just fix the signs idc + y_new[0] = np.abs(y_new[0]) + y_new[1] = np.abs(y_new[1]) * -1 + y_new[2] = np.abs(y_new[2]) * -1 + z_new[0] = np.abs(z_new[0]) + z_new[1] = np.abs(z_new[1]) + z_new[2] = np.abs(z_new[2]) * -1 + # y is good tho + R = np.hstack((x_new.reshape((3,1)), y_new.reshape((3,1)))) + R = np.hstack((R, z_new.reshape((3,1)))) + + print('rot mat to new frame:') + print(*R, sep=',\n') + + return R + # TODO change this, i just shoved the pen through the board -speed = [0, 0, -0.5, 0, 0, 0] -n_tests = 5 +speed = [0, 0, -0.3, 0, 0, 0] +n_tests = 10 positions = [] +R = np.array([[1., 0., 0.03236534], +[ 0., -0.82404727, 0.56559577], +[ 0. , -0.56559577, -0.82404727]]) + for i in range(n_tests): rtde_control.moveUntilContact(speed) q = rtde_receive.getActualQ() @@ -67,6 +115,18 @@ for i in range(n_tests): new_pose[0] = init_pose[0] + np.random.random() * 0.3 new_pose[1] = init_pose[1] - np.random.random() * 0.2 rtde_control.moveL(new_pose) + # fix orientation + rpy = pin.rpy.matrixToRpy(R) + print("rpy", rpy) + if rpy[0] > 0.0: + rpy[0] = rpy[0] - 2*np.pi + # who knows if this is ok + new_pose[3] = rpy[0] + new_pose[4] = rpy[1] + new_pose[5] = rpy[2] + rtde_control.moveL(new_pose) + R = estimate_R(positions) + current_pose = rtde_receive.getActualTCPPose() new_pose = copy.deepcopy(current_pose) @@ -74,36 +134,4 @@ new_pose[2] = init_pose[2] rtde_control.moveL(new_pose) rtde_control.moveL(init_pose) -# find the angle -positions = np.array(positions) - - -print("positions") -print(*positions, sep=',\n') -# the offset does not matter, we only need the angle -# i.e. the normal vector to the plane -n = np.linalg.lstsq(positions, np.ones(len(positions)), rcond=None)[0] -print("n", *n, sep=',') -# normalize -#n = n - 1 -n = n / np.linalg.norm(n) -print("n normalized:", *n, sep=',') -for p in positions: - print("cdot", p @ n) -z_new = n -x_new = np.array([1.0, 0.0, 0.0]) -y_new = np.cross(x_new, z_new) -# it just is -z_new = z_new * -1 -# y is good tho -R = np.hstack((x_new.reshape((3,1)), y_new.reshape((3,1)))) -R = np.hstack((R, z_new.reshape((3,1)))) - -print('rot mat to new frame:') -print(*R, sep=',\n') -# question now is in what f-ing frame is this n in -# has to be base frame because that's where the position numbers are from -# so -# rot @ np.eye(3) = n -# but n is one vector -# keep x where it was?, make y complete the frame? + diff --git a/util/currents.png b/util/currents.png new file mode 100644 index 0000000000000000000000000000000000000000..6a4fea5032cdd1a62ab74d541cc002aa20db59fa Binary files /dev/null and b/util/currents.png differ diff --git a/util/freedrive.py b/util/freedrive.py index e2f1b8ccd737f2fb29a5dc59e1e6ec08084f64bf..307069d87d69fc612b04b50e621e975f746373b7 100644 --- a/util/freedrive.py +++ b/util/freedrive.py @@ -1,7 +1,8 @@ import numpy as np import time -from rtde_control import RTDEControlInterface as RTDEControl -from rtde_receive import RTDEReceiveInterface as RTDEReceive +from rtde_control import RTDEControlInterface +from rtde_receive import RTDEReceiveInterface +from rtde_io import RTDEIOInterface import os import copy import signal @@ -12,8 +13,10 @@ def handler(signum, frame): exit() -rtde_control = RTDEControl("192.168.1.102") -rtde_receive = RTDEReceive("192.168.1.102") +rtde_control = RTDEControlInterface("192.168.1.102") +rtde_receive = RTDEReceiveInterface("192.168.1.102") +rtde_io = RTDEIOInterface("192.168.1.102") +rtde_io.setSpeedSlider(0.2) while not rtde_control.isConnected(): continue print("connected") diff --git a/util/ft_readings.py b/util/ft_readings.py new file mode 100644 index 0000000000000000000000000000000000000000..b721486d6b3028065fc66d424e5fe4f402875ebf --- /dev/null +++ b/util/ft_readings.py @@ -0,0 +1,91 @@ +import pinocchio as pin +import numpy as np +import matplotlib.pyplot as plt +import sys +import os +from os.path import dirname, join, abspath +import time +from pinocchio.visualize import GepettoVisualizer +import gepetto.corbaserver +from rtde_control import RTDEControlInterface +from rtde_receive import RTDEReceiveInterface +import os +import copy +import signal +from give_me_the_calibrated_model import get_model + +def handler(signum, frame): + print('i will end freedrive and exit') + rtde_control.endFreedriveMode() + exit() + + +rtde_control = RTDEControlInterface("192.168.1.102") +rtde_receive = RTDEReceiveInterface("192.168.1.102") +while not rtde_control.isConnected(): + continue +print("connected") +print("payload", rtde_receive.getPayload()) +print("payload cog", rtde_receive.getPayloadCog()) +print("payload ixx, iyy, izz, angular", rtde_receive.getPayloadInertia()) +#exit() + +signal.signal(signal.SIGINT, handler) + +urdf_path_relative = "../robot_descriptions/urdf/ur5e_with_robotiq_hande.urdf" +urdf_path_absolute = os.path.abspath(urdf_path_relative) +mesh_dir = "../robot_descriptions/" +mesh_dir_absolute = os.path.abspath(mesh_dir) +model, data = get_model(urdf_path_absolute, mesh_dir_absolute) +ft_readings = [] +dt = 1/500 +#while True: +for i in range(5000): + start = time.time() + q = rtde_receive.getActualQ() + ft = rtde_receive.getActualTCPForce() + tau = rtde_control.getJointTorques() + current = rtde_receive.getActualCurrent() + #print("current", current) + #print("getActualTCPForce", ft) + #print("tau", tau) + ft_readings.append(ft) + end = time.time() + diff = end - start + if diff < dt: + time.sleep(dt - diff) + +ft_readings = np.array(ft_readings) +time = np.arange(len(ft_readings)) +plt.title('fts') +ax = plt.subplot(231) +ax.plot(time, ft_readings[:,0]) +ax = plt.subplot(232) +ax.plot(time, ft_readings[:,1]) +ax = plt.subplot(233) +ax.plot(time, ft_readings[:,2]) +ax = plt.subplot(234) +ax.plot(time, ft_readings[:,3]) +ax = plt.subplot(235) +ax.plot(time, ft_readings[:,4]) +ax = plt.subplot(236) +ax.plot(time, ft_readings[:,5]) +plt.savefig('fts.png', dpi=600) +plt.show() +# ft = rtde_receive.getFtRawWrench() +# print("getFtRawWrench", ft) +# print("payload inertia", rtde_receive.getPayloadInertia()) +# print("momentum", rtde_receive.getActualMomentum()) +# print("target qdd", rtde_receive.getTargetQdd()) +# print("robot_current", rtde_receive.getActualRobotCurrent()) +# print("joint_voltage", rtde_receive.getActualJointVoltage()) +# print("robot_voltage", rtde_receive.getActualRobotVoltage()) +# print("getSafetyMode", rtde_receive.getSafetyMode()) +# print("tool_accelerometer", rtde_receive.getActualToolAccelerometer()) +# q.append(0.0) +# q.append(0.0) +# pin.forwardKinematics(model, data, np.array(q)) +# print(data.oMi[6]) +# print("pin:", *data.oMi[6].translation.round(4), *pin.rpy.matrixToRpy(data.oMi[6].rotation).round(4)) +# print("ur5:", *np.array(rtde_receive.getActualTCPPose()).round(4)) +# time.sleep(0.005) diff --git a/util/fts.png b/util/fts.png new file mode 100644 index 0000000000000000000000000000000000000000..c425e6ad19ac9d6f16c5d123919944483f2561e2 Binary files /dev/null and b/util/fts.png differ diff --git a/util/taus.png b/util/taus.png new file mode 100644 index 0000000000000000000000000000000000000000..a57b5f8bd24aea364b12c3a553bcb607651c3db5 Binary files /dev/null and b/util/taus.png differ