Skip to content
Snippets Groups Projects
Commit 61c50326 authored by Pep Martí Saumell's avatar Pep Martí Saumell
Browse files

Merge branch 'UAM_devel' of ssh://gitlab.iri.upc.edu:2202/jmarti/crocoddyl into UAM_devel

parents 3bd3d177 a575b7cb
No related branches found
No related tags found
No related merge requests found
Pipeline #4385 failed
Showing
with 1460 additions and 10145 deletions
...@@ -22,9 +22,10 @@ class ActuationModelUAM: ...@@ -22,9 +22,10 @@ class ActuationModelUAM:
self.cf = coefF self.cf = coefF
def calc(self, data, x, u): def calc(self, data, x, u):
# data.a[2:] = u
d, cf, cm = self.d, self.cf, self.cf d, cf, cm = self.d, self.cf, self.cf
S = np.array(np.zeros([self.nv,self.nu])) S = np.array(np.zeros([self.nv,self.nu]))
S[2:6,:4] = np.array([[1,1,1,1],[-d,d,-d,d],[-d,-d,d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]]) S[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
np.fill_diagonal(S[6:, 4:], 1) np.fill_diagonal(S[6:, 4:], 1)
data.a = np.dot(S,u) data.a = np.dot(S,u)
return data.a return data.a
...@@ -48,17 +49,14 @@ class ActuationDataUAM: ...@@ -48,17 +49,14 @@ class ActuationDataUAM:
self.Au = self.A[:, ndx:] self.Au = self.A[:, ndx:]
self.Au[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]]) self.Au[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
np.fill_diagonal(self.Au[6:, 4:], 1) np.fill_diagonal(self.Au[6:, 4:], 1)
# Actuation considering motor forces instead of thrust and moments #np.fill_diagonal(self.Au[2:, :], 1)
# This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment # This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment
# [ 0, 0, 0, 0] # [ 0, 0, 0, 0]
# [ 0, 0, 0, 0] # [ 0, 0, 0, 0]
# [ 1, 1, 1, 1] # [ 1, 1, 1, 1]
# [ -d, d, -d, d] # [ -d, d, -d, d]
# [ -d, -d, d, d] # [ -d, -d, d, d]
# [ -cm/cf, -cm/cf, cm/cf, cm/cf] # [ -cm/cf, -cm/cf, cm/cf, cm/cf]
class ActuationModelFreeFloating: class ActuationModelFreeFloating:
......
import numpy as np import numpy as np
import scipy.linalg as scl import scipy.linalg as scl
import time
from .solver import SolverAbstract from .solver import SolverAbstract
from .utils import raiseIfNan from .utils import raiseIfNan
...@@ -140,7 +141,9 @@ class SolverFDDP(SolverAbstract): ...@@ -140,7 +141,9 @@ class SolverFDDP(SolverAbstract):
recalc = True recalc = True
while True: while True:
try: try:
# t = time.time()
self.computeDirection(recalc=recalc) self.computeDirection(recalc=recalc)
# print "TIME, Solving: Compute direction. Iteration " + str(i) + ": " + str(time.time()-t)
except ArithmeticError: except ArithmeticError:
recalc = False recalc = False
self.increaseRegularization() self.increaseRegularization()
......
from crocoddyl import *
import pinocchio as pin
import numpy as np
from crocoddyl.diagnostic import displayTrajectory
# LOAD ROBOT
robot = loadKinton()
robot.initViewer(loadModel=True)
robot.display(robot.q0)
robot.framesForwardKinematics(robot.q0)
rmodel = robot.model
# DEFINE TARGET POSITION
target_pos = np.array([0,0,1])
target_quat = pin.Quaternion(1, 0, 0, 0)
target_quat.normalize()
# Plot goal frame
robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)
robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])
robot.viewer.gui.refresh()
# ACTUATION MODEL
distanceRotorCOG = 0.1525
cf = 6.6e-5
cm = 1e-6
actModel = ActuationModelUAM(robot.model, distanceRotorCOG, cf, cm)
# COST MODEL
# Create a cost model per the running and terminal action model.
runningCostModel = CostModelSum(robot.model, actModel.nu)
terminalCostModel = CostModelSum(robot.model, actModel.nu)
frameName = 'base_link'
state = StatePinocchio(robot.model)
SE3ref = pin.SE3()
SE3ref.translation = target_pos.reshape(3,1)
SE3ref.rotation = target_quat.matrix()
wBasePos = [1]
wBaseOri = [500]
wArmPos = [1]
wBaseVel = [10]
wBaseRate = [10]
wArmVel = [10]
stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + wArmPos * (robot.model.nv - 6) + wBaseVel * robot.model.nv)
controlWeights = np.array([0.1]*4 + [100]*6)
goalTrackingCost = CostModelFramePlacement(rmodel,
frame=rmodel.getFrameId(frameName),
ref=SE3ref,
nu =actModel.nu)
xRegCost = CostModelState(rmodel,
state,
ref=state.zero(),
nu=actModel.nu,
activation=ActivationModelWeightedQuad(stateWeights))
uRegCost = CostModelControl(rmodel,
nu=robot.
model.nv-2,
activation = ActivationModelWeightedQuad(controlWeights))
uLimCost = CostModelControl(rmodel,
nu=robot.
model.nv-2,
activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1, -1, -1, -1, -1, -1, -1]),
np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))
# Then let's add the running and terminal cost functions
runningCostModel.addCost(name="pos", weight=0.1, cost=goalTrackingCost)
runningCostModel.addCost(name="regx", weight=1e-4, cost=xRegCost)
runningCostModel.addCost(name="regu", weight=1e-6, cost=uRegCost)
runningCostModel.addCost(name="limu", weight=1e-3, cost=uLimCost)
terminalCostModel.addCost(name="pos", weight=0, cost=goalTrackingCost)
# DIFFERENTIAL ACTION MODEL
runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))
terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))
# DEFINING THE SHOOTING PROBLEM & SOLVING
import time
# Defining the time duration for running action models and the terminal one
dt = 1e-2
runningModel.timeStep = dt
T = 100
q0 = rmodel.referenceConfigurations["initial_pose"].copy()
v0 = pin.utils.zero(rmodel.nv)
x0 = m2a(np.concatenate([q0, v0]))
rmodel.defaultState = x0.copy()
t = time.time()
problem = ShootingProblem(x0, [runningModel] * T, terminalModel)
print "TIME: Shooting problem, " + str(time.time()-t)
# Creating the DDP solver for this OC problem, defining a logger
fddp = SolverFDDP(problem)
fddp.callback = [CallbackDDPVerbose()]
fddp.callback.append(CallbackDDPLogger())
#fddp.setCallbacks([CallbackVerbose()])
# us0 = [
# m.differential.quasiStatic(d.differential, rmodel.defaultState)
# if isinstance(m, IntegratedActionModelEuler) else np.zeros(0)
# for m, d in zip(fddp.problem.runningModels, fddp.problem.runningDatas)]
# xs0 = [problem.initialState]*len(fddp.models())
# Solving it with the DDP algorithm
#fddp.solve(init_xs=xs0, init_us=us0)
t = time.time()
fddp.solve()
print "TIME: Solve time, " + str(time.time()-t)
displayTrajectory(robot, fddp.xs, runningModel.timeStep)
# Control trajectory
f1 = []
f2 = [];
f3 = [];
f4 = [];
for u in fddp.us:
f1.append(u[0])
f2.append(u[1])
f3.append(u[2])
f4.append(u[3])
# State trajectory
Xx = [];
Xy = [];
Xz = [];
Vx = [];
Vy = [];
Vz = [];
for x in fddp.xs:
Xx.append(x[0])
Xy.append(x[1])
Xz.append(x[2])
Vx.append(x[13])
Vy.append(x[14])
Vz.append(x[15])
import matplotlib.pyplot as plt
t = np.arange(0., 1, dt)
fig, axs = plt.subplots(2,2, figsize=(15,10))
fig.suptitle('Motor forces')
axs[0, 0].plot(t,f1)
axs[0, 0].set_title('Motor 1')
axs[0, 1].plot(t,f2)
axs[0, 1].set_title('Motor 2')
axs[1, 0].plot(t,f3)
axs[1, 0].set_title('Motor 3')
axs[1, 1].plot(t,f4)
axs[1, 1].set_title('Motor 4')
plt.figure()
t = np.append(t, 1)
plt.plot(t,Xx,t,Xy,t,Xz)
plt.legend(['x','y','z'])
plt.title('State - Position')
plt.ylabel('Position, [m]')
plt.xlabel('[s]')
plt.figure()
plt.plot(t,Vx,t,Vy,t,Vz)
plt.legend(['x','y','z'])
plt.title('State - Velocity')
plt.ylabel('Velocity, [m/s]')
plt.xlabel('[s]')
plt.show()
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
from crocoddyl import * from crocoddyl import *
import pinocchio as pin import pinocchio as pin
import numpy as np import numpy as np
robot = loadKintonArm() robot = loadKintonArm()
#robot.initDisplay(loadModel=True) #robot.initDisplay(loadModel=True)
#robot.display(robot.q0) #robot.display(robot.q0)
robot.framesForwardKinematics(robot.q0) robot.framesForwardKinematics(robot.q0)
# Create a cost model per the running and terminal action model. # Create a cost model per the running and terminal action model.
runningCostModel = CostModelSum(robot.model) runningCostModel = CostModelSum(robot.model)
terminalCostModel = CostModelSum(robot.model) terminalCostModel = CostModelSum(robot.model)
``` ```
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
target_pos = np.array([-0.1,-0.05,-0.15]) target_pos = np.array([-0.1,-0.05,-0.15])
target_quat = pin.Quaternion(.4, .02, -.5, .7) target_quat = pin.Quaternion(.4, .02, -.5, .7)
target_quat.normalize() target_quat.normalize()
# Plot goal frame # Plot goal frame
robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4) robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 1)
robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]]) robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])
robot.viewer.gui.refresh() robot.viewer.gui.refresh()
IDX_BASE = robot.model.getFrameId('base_link', pin.FrameType.BODY) IDX_BASE = robot.model.getFrameId('base_link', pin.FrameType.BODY)
Mbase = robot.data.oMf[IDX_BASE] Mbase = robot.data.oMf[IDX_BASE]
robot.viewer.gui.addXYZaxis('world/framebase', [1., 0., 0., 1.], .015, 4) robot.viewer.gui.addXYZaxis('world/framebase', [1., 0., 0., 1.], .03, 0.5)
robot.viewer.gui.applyConfiguration('world/framebase', pin.se3ToXYZQUATtuple(Mbase)) robot.viewer.gui.applyConfiguration('world/framebase', pin.se3ToXYZQUATtuple(Mbase))
robot.viewer.gui.refresh() robot.viewer.gui.refresh()
Mbase
IDX_EE = robot.model.getFrameId('link6', pin.FrameType.BODY)
Mee = robot.data.oMf[IDX_EE]
robot.viewer.gui.addXYZaxis('world/frameee', [1., 0., 0., 1.], .03, 0.5)
robot.viewer.gui.applyConfiguration('world/frameee', pin.se3ToXYZQUATtuple(Mee))
robot.viewer.gui.refresh()
``` ```
%% Output %% Output
------------------------------------------------------ ------------------------------------------------------
AttributeError Traceback (most recent call last) AttributeError Traceback (most recent call last)
<ipython-input-6-cd53aa81cd48> in <module>() <ipython-input-6-cd53aa81cd48> in <module>()
4 4
5 # Plot goal frame 5 # Plot goal frame
----> 6 robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4) ----> 6 robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)
7 robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]]) 7 robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])
8 robot.viewer.gui.refresh() 8 robot.viewer.gui.refresh()
/opt/openrobots/lib/python2.7/site-packages/pinocchio/robot_wrapper.pyc in viewer(self) /opt/openrobots/lib/python2.7/site-packages/pinocchio/robot_wrapper.pyc in viewer(self)
213 @property 213 @property
214 def viewer(self): 214 def viewer(self):
--> 215 return self.viz.viewer --> 215 return self.viz.viewer
216 216
217 def setVisualizer(self, visualizer, init=True, copy_models=False): 217 def setVisualizer(self, visualizer, init=True, copy_models=False):
AttributeError: 'NoneType' object has no attribute 'viewer' AttributeError: 'NoneType' object has no attribute 'viewer'
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
# Note that we need to include a cost model (i.e. set of cost functions) in # Note that we need to include a cost model (i.e. set of cost functions) in
# order to fully define the action model for our optimal control problem. # order to fully define the action model for our optimal control problem.
# For this particular example, we formulate three running-cost functions: # For this particular example, we formulate three running-cost functions:
# goal-tracking cost, state and control regularization; and one terminal-cost: # goal-tracking cost, state and control regularization; and one terminal-cost:
# goal cost. First, let's create the common cost functions # goal cost. First, let's create the common cost functions
frameName = 'link6' frameName = 'link6'
state = StatePinocchio(robot.model) state = StatePinocchio(robot.model)
SE3ref = pin.SE3() SE3ref = pin.SE3()
SE3ref.translation = target_pos.reshape(3,1) SE3ref.translation = target_pos.reshape(3,1)
SE3ref.rotation = target_quat.matrix() SE3ref.rotation = target_quat.matrix()
goalTrackingCost = CostModelFramePlacement(robot.model, nu=robot.model.nv, frame=robot.model.getFrameId(frameName), ref=SE3ref) goalTrackingCost = CostModelFramePlacement(robot.model, nu=robot.model.nv, frame=robot.model.getFrameId(frameName), ref=SE3ref)
xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=robot.model.nv) xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=robot.model.nv)
uRegCost = CostModelControl(robot.model, nu=robot.model.nv) uRegCost = CostModelControl(robot.model, nu=robot.model.nv)
# Then let's add the running and terminal cost functions # Then let's add the running and terminal cost functions
runningCostModel.addCost(name="pos", weight=1e-3, cost=goalTrackingCost) runningCostModel.addCost(name="pos", weight=1e-3, cost=goalTrackingCost)
runningCostModel.addCost(name="regx", weight=1e-7, cost=xRegCost) runningCostModel.addCost(name="regx", weight=1e-7, cost=xRegCost)
runningCostModel.addCost(name="regu", weight=1e-7, cost=uRegCost) runningCostModel.addCost(name="regu", weight=1e-7, cost=uRegCost)
terminalCostModel.addCost(name="pos", weight=50, cost=goalTrackingCost) terminalCostModel.addCost(name="pos", weight=50, cost=goalTrackingCost)
``` ```
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
# Next, we need to create an action model for running and terminal knots. The # Next, we need to create an action model for running and terminal knots. The
# forward dynamics (computed using ABA) are implemented # forward dynamics (computed using ABA) are implemented
# inside DifferentialActionModelFullyActuated. # inside DifferentialActionModelFullyActuated.
runningModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, runningCostModel)) runningModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, runningCostModel))
terminalModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, terminalCostModel)) terminalModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, terminalCostModel))
# Defining the time duration for running action models and the terminal one # Defining the time duration for running action models and the terminal one
dt = 1e-3 dt = 1e-3
runningModel.timeStep = dt runningModel.timeStep = dt
# For this optimal control problem, we define 250 knots (or running action # For this optimal control problem, we define 250 knots (or running action
# models) plus a terminal knot # models) plus a terminal knot
T = 250 T = 250
q0 = [0., 0., 0., 0., 0., 0.] q0 = [0., 0., 0., 0., 0., 0.]
x0 = np.hstack([q0, np.zeros(robot.model.nv)]) x0 = np.hstack([q0, np.zeros(robot.model.nv)])
problem = ShootingProblem(x0, [runningModel] * T, terminalModel) problem = ShootingProblem(x0, [runningModel] * T, terminalModel)
# Creating the DDP solver for this OC problem, defining a logger # Creating the DDP solver for this OC problem, defining a logger
ddp = SolverDDP(problem) ddp = SolverDDP(problem)
# ddp.callback = [CallbackDDPVerbose()] # ddp.callback = [CallbackDDPVerbose()]
# ddp.callback.append(CallbackDDPLogger()) # ddp.callback.append(CallbackDDPLogger())
# Solving it with the DDP algorithm # Solving it with the DDP algorithm
ddp.solve() ddp.solve()
``` ```
%% Output %% Output
([array([0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.]), ([array([0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.]),
array([-8.56312177e-04, 1.89532152e-03, 2.73421184e-03, 1.40535055e-04, array([-8.56312177e-04, 1.89532152e-03, 2.73421184e-03, 1.40535055e-04,
-6.80910601e-03, -1.47306350e-02, -8.56312177e-01, 1.89532152e+00, -6.80910601e-03, -1.47306350e-02, -8.56312177e-01, 1.89532152e+00,
2.73421184e+00, 1.40535055e-01, -6.80910601e+00, -1.47306350e+01]), 2.73421184e+00, 1.40535055e-01, -6.80910601e+00, -1.47306350e+01]),
array([-2.54926553e-03, 5.12874409e-03, 7.81062478e-03, -3.01186931e-05, array([-2.54926553e-03, 5.12874409e-03, 7.81062478e-03, -3.01186931e-05,
-1.90322663e-02, -4.14852078e-02, -1.69295335e+00, 3.23342257e+00, -1.90322663e-02, -4.14852078e-02, -1.69295335e+00, 3.23342257e+00,
5.07641293e+00, -1.70653748e-01, -1.22231603e+01, -2.67545728e+01]), 5.07641293e+00, -1.70653748e-01, -1.22231603e+01, -2.67545728e+01]),
array([-5.08231018e-03, 9.22720244e-03, 1.48413991e-02, -8.04175234e-04, array([-5.08231018e-03, 9.22720244e-03, 1.48413991e-02, -8.04175234e-04,
-3.54988967e-02, -7.79179637e-02, -2.53304466e+00, 4.09845835e+00, -3.54988967e-02, -7.79179637e-02, -2.53304466e+00, 4.09845835e+00,
7.03077430e+00, -7.74056541e-01, -1.64666304e+01, -3.64327559e+01]), 7.03077430e+00, -7.74056541e-01, -1.64666304e+01, -3.64327559e+01]),
array([-8.46800128e-03, 1.37903845e-02, 2.34569133e-02, -2.35975061e-03, array([-8.46800128e-03, 1.37903845e-02, 2.34569133e-02, -2.35975061e-03,
-5.52243122e-02, -1.22000964e-01, -3.38569110e+00, 4.56318206e+00, -5.52243122e-02, -1.22000964e-01, -3.38569110e+00, 4.56318206e+00,
8.61551424e+00, -1.55557537e+00, -1.97254155e+01, -4.40830008e+01]), 8.61551424e+00, -1.55557537e+00, -1.97254155e+01, -4.40830008e+01]),
array([-1.27186474e-02, 1.84809680e-02, 3.33145786e-02, -4.79397616e-03, array([-1.27186474e-02, 1.84809680e-02, 3.33145786e-02, -4.79397616e-03,
-7.73790286e-02, -1.71986456e-01, -4.25064615e+00, 4.69058353e+00, -7.73790286e-02, -1.71986456e-01, -4.25064615e+00, 4.69058353e+00,
9.85766525e+00, -2.43422556e+00, -2.21547164e+01, -4.99854912e+01]), 9.85766525e+00, -2.43422556e+00, -2.21547164e+01, -4.99854912e+01]),
array([-1.78404033e-02, 2.30163561e-02, 4.41040294e-02, -8.14709277e-03, array([-1.78404033e-02, 2.30163561e-02, 4.41040294e-02, -8.14709277e-03,
-1.01264181e-01, -2.26373762e-01, -5.12175590e+00, 4.53538811e+00, -1.01264181e-01, -2.26373762e-01, -5.12175590e+00, 4.53538811e+00,
1.07894509e+01, -3.35311661e+00, -2.38851526e+01, -5.43873060e+01]), 1.07894509e+01, -3.35311661e+00, -2.38851526e+01, -5.43873060e+01]),
array([-2.38298841e-02, 2.71617013e-02, 5.55497401e-02, -1.24199321e-02, array([-2.38298841e-02, 2.71617013e-02, 5.55497401e-02, -1.24199321e-02,
-1.26291684e-01, -2.83879975e-01, -5.98948076e+00, 4.14534516e+00, -1.26291684e-01, -2.83879975e-01, -5.98948076e+00, 4.14534516e+00,
1.14457107e+01, -4.27283935e+00, -2.50275032e+01, -5.75062132e+01]), 1.14457107e+01, -4.27283935e+00, -2.50275032e+01, -5.75062132e+01]),
array([-3.06726033e-02, 3.07239957e-02, 6.74117742e-02, -1.75865554e-02, array([-3.06726033e-02, 3.07239957e-02, 6.74117742e-02, -1.75865554e-02,
-1.51968056e-01, -3.43413880e-01, -6.84271922e+00, 3.56229443e+00, -1.51968056e-01, -3.43413880e-01, -6.84271922e+00, 3.56229443e+00,
1.18620341e+01, -5.16662324e+00, -2.56763713e+01, -5.95339055e+01]), 1.18620341e+01, -5.16662324e+00, -2.56763713e+01, -5.95339055e+01]),
array([-3.83427059e-02, 3.35470230e-02, 7.94851689e-02, -2.36033530e-02, array([-3.83427059e-02, 3.35470230e-02, 7.94851689e-02, -2.36033530e-02,
-1.77881070e-01, -4.04052690e-01, -7.67010261e+00, 2.82302730e+00, -1.77881070e-01, -4.04052690e-01, -7.67010261e+00, 2.82302730e+00,
1.20733947e+01, -6.01679762e+00, -2.59130143e+01, -6.06388091e+01]), 1.20733947e+01, -6.01679762e+00, -2.59130143e+01, -6.06388091e+01]),
array([-4.68035939e-02, 3.55069954e-02, 9.15983289e-02, -3.04155662e-02, array([-4.68035939e-02, 3.55069954e-02, 9.15983289e-02, -3.04155662e-02,
-2.03688603e-01, -4.65021251e-01, -8.46088799e+00, 1.95997236e+00, -2.03688603e-01, -4.65021251e-01, -8.46088799e+00, 1.95997236e+00,
1.21131600e+01, -6.81221321e+00, -2.58075331e+01, -6.09685612e+01]), 1.21131600e+01, -6.81221321e+00, -2.58075331e+01, -6.09685612e+01]),
array([-5.60091391e-02, 3.65087333e-02, 1.03610720e-01, -3.79619363e-02, array([-5.60091391e-02, 3.65087333e-02, 1.03610720e-01, -3.79619363e-02,
-2.29109180e-01, -5.25673474e-01, -9.20554513e+00, 1.00173792e+00, -2.29109180e-01, -5.25673474e-01, -9.20554513e+00, 1.00173792e+00,
1.20123911e+01, -7.54637012e+00, -2.54205768e+01, -6.06522231e+01]), 1.20123911e+01, -7.54637012e+00, -2.54205768e+01, -6.06522231e+01]),
array([-6.59052492e-02, 3.64822755e-02, 1.15410099e-01, -4.61780004e-02, array([-6.59052492e-02, 3.64822755e-02, 1.15410099e-01, -4.61780004e-02,
-2.53913861e-01, -5.85475750e-01, -9.89611015e+00, -2.64577972e-02, -2.53913861e-01, -5.85475750e-01, -9.89611015e+00, -2.64577972e-02,
1.17993788e+01, -8.21606409e+00, -2.48046815e+01, -5.98022757e+01]), 1.17993788e+01, -8.21606409e+00, -2.48046815e+01, -5.98022757e+01]),
array([-7.64316113e-02, 3.53798340e-02, 1.26909472e-01, -5.49984119e-02, array([-7.64316113e-02, 3.53798340e-02, 1.26909472e-01, -5.49984119e-02,
-2.77919200e-01, -6.43992178e-01, -1.05263621e+01, -1.10244147e+00, -2.77919200e-01, -6.43992178e-01, -1.05263621e+01, -1.10244147e+00,
1.14993727e+01, -8.82041147e+00, -2.40053389e+01, -5.85164289e+01]), 1.14993727e+01, -8.82041147e+00, -2.40053389e+01, -5.85164289e+01]),
array([-8.75234771e-02, 3.31730321e-02, 1.38043940e-01, -6.43585617e-02, array([-8.75234771e-02, 3.31730321e-02, 1.38043940e-01, -6.43585617e-02,
-3.00981066e-01, -7.00871445e-01, -1.10918658e+01, -2.20680192e+00, -3.00981066e-01, -7.00871445e-01, -1.10918658e+01, -2.20680192e+00,
1.11344687e+01, -9.36014983e+00, -2.30618659e+01, -5.68792667e+01]), 1.11344687e+01, -9.36014983e+00, -2.30618659e+01, -5.68792667e+01]),
array([-9.91133938e-02, 2.98503805e-02, 1.48767566e-01, -7.41956993e-02, array([-9.91133938e-02, 2.98503805e-02, 1.48767566e-01, -7.41956993e-02,
-3.22989193e-01, -7.55835190e-01, -1.15899167e+01, -3.32265166e+00, -3.22989193e-01, -7.55835190e-01, -1.15899167e+01, -3.32265166e+00,
1.07236258e+01, -9.83713756e+00, -2.20081270e+01, -5.49637450e+01]), 1.07236258e+01, -9.83713756e+00, -2.20081270e+01, -5.49637450e+01]),
array([-1.11132809e-01, 2.54149615e-02, 1.59050350e-01, -8.44496956e-02, array([-1.11132809e-01, 2.54149615e-02, 1.59050350e-01, -8.44496956e-02,
-3.43862344e-01, -8.08667742e-01, -1.20194151e+01, -4.43541893e+00, -3.43862344e-01, -8.08667742e-01, -1.20194151e+01, -4.43541893e+00,
1.02827840e+01, -1.02539963e+01, -2.08731508e+01, -5.28325516e+01]), 1.02827840e+01, -1.02539963e+01, -2.08731508e+01, -5.28325516e+01]),
array([-1.23513502e-01, 1.98823017e-02, 1.68875407e-01, -9.50635507e-02, array([-1.23513502e-01, 1.98823017e-02, 1.68875407e-01, -9.50635507e-02,
-3.63544010e-01, -8.59207080e-01, -1.23806934e+01, -5.53265979e+00, -3.63544010e-01, -8.59207080e-01, -1.23806934e+01, -5.53265979e+00,
9.82505690e+00, -1.06138552e+01, -1.96816663e+01, -5.05393383e+01]), 9.82505690e+00, -1.06138552e+01, -1.96816663e+01, -5.05393383e+01]),
array([-1.36188819e-01, 1.32784184e-02, 1.78236385e-01, -1.05983717e-01, array([-1.36188819e-01, 1.32784184e-02, 1.78236385e-01, -1.05983717e-01,
-3.81998590e-01, -9.07336913e-01, -1.26753164e+01, -6.60388340e+00, -3.81998590e-01, -9.07336913e-01, -1.26753164e+01, -6.60388340e+00,
9.36097833e+00, -1.09201664e+01, -1.84545794e+01, -4.81298329e+01]), 9.36097833e+00, -1.09201664e+01, -1.84545794e+01, -4.81298329e+01]),
array([-1.49094686e-01, 5.63803259e-03, 1.87135165e-01, -1.17160289e-01, array([-1.49094686e-01, 5.63803259e-03, 1.87135165e-01, -1.17160289e-01,
-3.99207991e-01, -9.52979751e-01, -1.29058673e+01, -7.64038576e+00, -3.99207991e-01, -9.52979751e-01, -1.29058673e+01, -7.64038576e+00,
8.89877975e+00, -1.11765718e+01, -1.72094018e+01, -4.56428385e+01]), 8.89877975e+00, -1.11765718e+01, -1.72094018e+01, -4.56428385e+01]),
array([-1.62170422e-01, -2.99705683e-03, 1.95579848e-01, -1.28547092e-01, array([-1.62170422e-01, -2.99705683e-03, 1.95579848e-01, -1.28547092e-01,
-4.15168633e-01, -9.96090877e-01, -1.30757358e+01, -8.63508942e+00, -4.15168633e-01, -9.96090877e-01, -1.30757358e+01, -8.63508942e+00,
8.44468278e+00, -1.13868033e+01, -1.59606421e+01, -4.31111258e+01]), 8.44468278e+00, -1.13868033e+01, -1.59606421e+01, -4.31111258e+01]),
array([-1.75359335e-01, -1.25794448e-02, 2.03583039e-01, -1.40101702e-01, array([-1.75359335e-01, -1.25794448e-02, 2.03583039e-01, -1.40101702e-01,
-4.29888797e-01, -1.03665310e+00, -1.31889131e+01, -9.58238800e+00, -4.29888797e-01, -1.03665310e+00, -1.31889131e+01, -9.58238800e+00,
8.00319163e+00, -1.15546094e+01, -1.47201632e+01, -4.05622272e+01]), 8.00319163e+00, -1.15546094e+01, -1.47201632e+01, -4.05622272e+01]),
array([-1.88609140e-01, -2.30574403e-02, 2.11160414e-01, -1.51785399e-01, array([-1.88609140e-01, -2.30574403e-02, 2.11160414e-01, -1.51785399e-01,
-4.43386307e-01, -1.07467224e+00, -1.32498049e+01, -1.04779954e+01, -4.43386307e-01, -1.07467224e+00, -1.32498049e+01, -1.04779954e+01,
7.57737427e+00, -1.16836977e+01, -1.34975104e+01, -3.80191388e+01]), 7.57737427e+00, -1.16836977e+01, -1.34975104e+01, -3.80191388e+01]),
array([-2.01872203e-01, -3.43762410e-02, 2.18329538e-01, -1.63563090e-01, array([-2.01872203e-01, -3.43762410e-02, 2.18329538e-01, -1.63563090e-01,
-4.55686519e-01, -1.11017318e+00, -1.32630632e+01, -1.13188007e+01, -4.55686519e-01, -1.11017318e+00, -1.32630632e+01, -1.13188007e+01,
7.16912438e+00, -1.17776903e+01, -1.23002120e+01, -3.55009380e+01]), 7.16912438e+00, -1.17776903e+01, -1.23002120e+01, -3.55009380e+01]),
array([ -0.21510564, -0.04647897, 0.22510894, -0.17540318, array([ -0.21510564, -0.04647897, 0.22510894, -0.17540318,
-0.46682057, -1.14319651, -13.23344193, -12.10272852, -0.46682057, -1.14319651, -13.23344193, -12.10272852,
6.77939849, -11.84008895, -11.13405288, -33.02332443]), 6.77939849, -11.84008895, -11.13405288, -33.02332443]),
array([ -0.22827132, -0.05930758, 0.23151736, -0.18727743, array([ -0.22827132, -0.05930758, 0.23151736, -0.18727743,
-0.4768239 , -1.1737956 , -13.16567615, -12.82860748, -0.4768239 , -1.1737956 , -13.16567615, -12.82860748,
6.40842551, -11.87424711, -10.00332469, -30.59909137]), 6.40842551, -11.87424711, -10.00332469, -30.59909137]),
array([ -0.24133571, -0.07280362, 0.23757325, -0.19916077, array([ -0.24133571, -0.07280362, 0.23757325, -0.19916077,
-0.48573495, -1.20203413, -13.06438462, -13.4960463 , -0.48573495, -1.20203413, -13.06438462, -13.4960463 ,
6.0558876 , -11.8833484 , -8.91105036, -28.23853502]), 6.0558876 , -11.8833484 , -8.91105036, -28.23853502]),
array([ -0.2542697 , -0.08690894, 0.24329432, -0.21103116, array([ -0.2542697 , -0.08690894, 0.24329432, -0.21103116,
-0.49359413, -1.22798394, -12.93399439, -14.10531885, -0.49359413, -1.22798394, -12.93399439, -14.10531885,
5.72107287, -11.87039025, -7.85918639, -25.94980885]), 5.72107287, -11.87039025, -7.85918639, -25.94980885]),
array([ -0.26704839, -0.1015662 , 0.24869732, -0.22286934, array([ -0.26704839, -0.1015662 , 0.24869732, -0.22286934,
-0.50044294, -1.25172317, -12.77868549, -14.65725873, -0.50044294, -1.25172317, -12.77868549, -14.65725873,
5.40300168, -11.83817235, -6.84880291, -23.73922952]), 5.40300168, -11.83817235, -6.84880291, -23.73922952]),
array([ -0.27965074, -0.11671936, 0.25379785, -0.23465863, array([ -0.27965074, -0.11671936, 0.25379785, -0.23465863,
-0.50632318, -1.27333471, -12.6023533 , -15.15316343, -0.50632318, -1.27333471, -12.6023533 , -15.15316343,
5.10052876, -11.78928931, -5.88024295, -21.61154057]), 5.10052876, -11.78928931, -5.88024295, -21.61154057]),
array([ -0.29205932, -0.13231407, 0.25861028, -0.24638475, array([ -0.29205932, -0.13231407, 0.25861028, -0.24638475,
-0.51127644, -1.29290485, -12.40858594, -15.59470826, -0.51127644, -1.29290485, -12.40858594, -15.59470826,
4.81242403, -11.72612727, -4.95326222, -19.57013972]), 4.81242403, -11.72612727, -4.95326222, -19.57013972]),
array([ -0.30425998, -0.14829794, 0.26314771, -0.25803562, array([ -0.30425998, -0.14829794, 0.26314771, -0.25803562,
-0.51534359, -1.31052213, -12.20065427, -15.98386974, -0.51534359, -1.31052213, -12.20065427, -15.98386974,
4.53743491, -11.65086397, -4.06715096, -17.61727455]), 4.53743491, -11.65086397, -4.06715096, -17.61727455]),
array([ -0.31624149, -0.1646208 , 0.26742205, -0.26960109, array([ -0.31624149, -0.1646208 , 0.26742205, -0.26960109,
-0.51856443, -1.32627634, -11.98151204, -16.32285807, -0.51856443, -1.32627634, -11.98151204, -16.32285807,
4.27433311, -11.56547179, -3.22083904, -15.75421143]), 4.27433311, -11.56547179, -3.22083904, -15.75421143]),
array([ -0.32799529, -0.18123486, 0.27144399, -0.28107281, array([ -0.32799529, -0.18123486, 0.27144399, -0.28107281,
-0.52097742, -1.34025772, -11.7538038 , -16.61405829, -0.52097742, -1.34025772, -11.7538038 , -16.61405829,
4.02194851, -11.47172349, -2.4129861 , -13.98138136]), 4.02194851, -11.47172349, -2.4129861 , -13.98138136]),
array([ -0.33951517, -0.19809484, 0.27522319, -0.29244401, array([ -0.33951517, -0.19809484, 0.27522319, -0.29244401,
-0.52261948, -1.35255622, -11.51987881, -16.85997941, -0.52261948, -1.35255622, -11.51987881, -16.85997941,
3.77919261, -11.37120003, -1.6420579 , -12.29850626]), 3.77919261, -11.37120003, -1.6420579 , -12.29850626]),
array([ -0.35079698, -0.21515805, 0.27876826, -0.30370931, array([ -0.35079698, -0.21515805, 0.27876826, -0.30370931,
-0.52352587, -1.36326093, -11.28180904, -17.06321082, -0.52352587, -1.36326093, -11.28180904, -17.06321082,
3.54507366, -11.26530018, -0.90639058, -10.70470859]), 3.54507366, -11.26530018, -0.90639058, -10.70470859]),
array([ -0.36183839, -0.23238443, 0.28208697, -0.31486456, array([ -0.36183839, -0.23238443, 0.28208697, -0.31486456,
-0.52373011, -1.37245954, -11.04140998, -17.22638542, -0.52373011, -1.37245954, -11.04140998, -17.22638542,
3.31870542, -11.15525131, -0.20424393, -9.19860674]), 3.31870542, -11.15525131, -0.20424393, -9.19860674]),
array([ -0.37263866, -0.24973658, 0.28518628, -0.32590669, array([ -0.37263866, -0.24973658, 0.28518628, -0.32590669,
-0.52326396, -1.38023794, -10.80026286, -17.35214865, -0.52326396, -1.38023794, -10.80026286, -17.35214865,
3.09931088, -11.04212114, 0.46615488, -7.77839827]), 3.09931088, -11.04212114, 0.46615488, -7.77839827]),
array([ -0.38319839, -0.26717972, 0.2880725 , -0.33683352, array([ -0.38319839, -0.26717972, 0.2880725 , -0.33683352,
-0.52215738, -1.38667987, -10.55973759, -17.44313278, -0.52215738, -1.38667987, -10.55973759, -17.44313278,
2.88622244, -10.92682999, 1.10657594, -6.44193265]), 2.88622244, -10.92682999, 1.10657594, -6.44193265]),
array([ -0.39351941, -0.28468165, 0.29075138, -0.34764368, array([ -0.39351941, -0.28468165, 0.29075138, -0.34764368,
-0.52043862, -1.39186665, -10.32101545, -17.50193583, -0.52043862, -1.39186665, -10.32101545, -17.50193583,
2.67887935, -10.81016323, 1.71875861, -5.18677509]), 2.67887935, -10.81016323, 1.71875861, -5.18677509]),
array([ -0.40360452, -0.30221276, 0.2932282 , -0.35833646, array([ -0.40360452, -0.30221276, 0.2932282 , -0.35833646,
-0.51813423, -1.39587691, -10.08511111, -17.53110454, -0.51813423, -1.39587691, -10.08511111, -17.53110454,
2.4768233 , -10.69278365, 2.30438977, -4.01026241]), 2.4768233 , -10.69278365, 2.30438977, -4.01026241]),
array([ -0.41345741, -0.31974588, 0.29550789, -0.36891171, array([ -0.41345741, -0.31974588, 0.29550789, -0.36891171,
-0.51526914, -1.39878646, -9.85289355, -17.53312077, -0.51526914, -1.39878646, -9.85289355, -17.53312077,
2.27969282, -10.57524351, 2.86508752, -2.90955215]), 2.27969282, -10.57524351, 2.86508752, -2.90955215]),
array([ -0.42308252, -0.33725627, 0.29759511, -0.3793697 , array([ -0.42308252, -0.33725627, 0.29759511, -0.3793697 ,
-0.51186675, -1.40066813, -9.62510553, -17.51039097, -0.51186675, -1.40066813, -9.62510553, -17.51039097,
2.08721677, -10.45799618, 3.40238942, -1.88166562]), 2.08721677, -10.45799618, 3.40238942, -1.88166562]),
array([ -0.4324849 , -0.35472151, 0.29949432, -0.38971111, array([ -0.4324849 , -0.35472151, 0.29949432, -0.38971111,
-0.50794901, -1.40159165, -9.40238156, -17.46523805, -0.50794901, -1.40159165, -9.40238156, -17.46523805,
1.8992075 , -10.34140712, 3.9177446 , -0.92352558]), 1.8992075 , -10.34140712, 3.9177446 , -0.92352558]),
array([ -0.44167016, -0.3721214 , 0.30120987, -0.39993687, array([ -0.44167016, -0.3721214 , 0.30120987, -0.39993687,
-0.5035365 , -1.40162364, -9.18526418, -17.39989559, -0.5035365 , -1.40162364, -9.18526418, -17.39989559,
1.71555366, -10.22576415, 4.41250911, -0.03198926]), 1.71555366, -10.22576415, 4.41250911, -0.03198926]),
array([ -0.45064438, -0.38943791, 0.30274609, -0.41004816, array([ -0.45064438, -0.38943791, 0.30274609, -0.41004816,
-0.49864856, -1.40082752, -8.97421853, -17.31650363, -0.49864856, -1.40082752, -8.97421853, -17.31650363,
1.53621308, -10.11128696, 4.88794389, 0.79612301]), 1.53621308, -10.11128696, 4.88794389, 0.79612301]),
array([ -0.45941403, -0.40665501, 0.30410729, -0.4200463 , array([ -0.45941403, -0.40665501, 0.30410729, -0.4200463 ,
-0.49330334, -1.39926351, -8.76964528, -17.21710619, -0.49330334, -1.39926351, -8.76964528, -17.21710619,
1.36120565, -9.99813587, 5.3452149 , 1.56400283]), 1.36120565, -9.99813587, 5.3452149 , 1.56400283]),
array([ -0.46798592, -0.42375866, 0.3052979 , -0.42993272, array([ -0.46798592, -0.42375866, 0.3052979 , -0.42993272,
-0.48751795, -1.39698868, -8.57189195, -17.10364986, -0.48751795, -1.39698868, -8.57189195, -17.10364986,
1.19060638, -9.88641969, 5.785395 , 2.27483231]), 1.19060638, -9.88641969, 5.785395 , 2.27483231]),
array([ -0.47636718, -0.44073664, 0.30632244, -0.43970892, array([ -0.47636718, -0.44073664, 0.30632244, -0.43970892,
-0.48130848, -1.39405692, -8.3812626 , -16.9779835 , -0.48130848, -1.39405692, -8.3812626 , -16.9779835 ,
1.02453858, -9.7762029 , 6.20946714, 2.93176567]), 1.02453858, -9.7762029 , 6.20946714, 2.93176567]),
array([ -0.48456521, -0.4575785 , 0.3071856 , -0.44937643, array([ -0.48456521, -0.4575785 , 0.3071856 , -0.44937643,
-0.47469015, -1.390519 , -8.19802619, -16.84185876, -0.47469015, -1.390519 , -8.19802619, -16.84185876,
0.86316738, -9.66751201, 6.61832861, 3.5379136 ]), 0.86316738, -9.66751201, 6.61832861, 3.5379136 ]),
array([ -0.49258763, -0.47427543, 0.3078923 , -0.45893677, array([ -0.49258763, -0.47427543, 0.3078923 , -0.45893677,
-0.46767735, -1.38642267, -8.02242347, -16.69693127, -0.46767735, -1.38642267, -8.02242347, -16.69693127,
0.70669335, -9.56034122, 7.01279599, 4.09633016]), 0.70669335, -9.56034122, 7.01279599, 4.09633016]),
array([ -0.50044231, -0.4908202 , 0.30844764, -0.46839143, array([ -0.50044231, -0.4908202 , 0.30844764, -0.46839143,
-0.46028374, -1.38181267, -7.85467273, -16.54476232, -0.46028374, -1.38181267, -7.85467273, -16.54476232,
0.55534643, -9.45465741, 7.39361069, 4.61000189]), 0.55534643, -9.45465741, 7.39361069, 4.61000189]),
array([ -0.50813728, -0.50720702, 0.30885702, -0.47774183, array([ -0.50813728, -0.50720702, 0.30885702, -0.47774183,
-0.4525223 , -1.37673083, -7.6949744 , -16.38682098, -0.4525223 , -1.37673083, -7.6949744 , -16.38682098,
0.40938011, -9.35040457, 7.76144476, 5.08183887]), 0.40938011, -9.35040457, 7.76144476, 5.08183887]),
array([ -0.51568079, -0.5234315 , 0.30912609, -0.48698934, array([ -0.51568079, -0.5234315 , 0.30912609, -0.48698934,
-0.44440539, -1.37121616, -7.54351458, -16.22448659, -0.44440539, -1.37121616, -7.54351458, -16.22448659,
0.26906582, -9.24750761, 8.11690684, 5.5146676 ]), 0.26906582, -9.24750761, 8.11690684, 5.5146676 ]),
array([ -0.52308126, -0.53949056, 0.30926078, -0.49613522, array([ -0.52308126, -0.53949056, 0.30926078, -0.49613522,
-0.43594484, -1.36530494, -7.40046775, -16.05905138, -0.43594484, -1.36530494, -7.40046775, -16.05905138,
0.13468759, -9.14587574, 8.46054817, 5.91122542]), 0.13468759, -9.14587574, 8.46054817, 5.91122542]),
array([-5.30347261e-01, -5.55382279e-01, 3.09267313e-01, -5.05180622e-01, array([-5.30347261e-01, -5.55382279e-01, 3.09267313e-01, -5.05180622e-01,
-4.27151976e-01, -1.35903078e+00, -7.26599866e+00, -1.58917233e+01, -4.27151976e-01, -1.35903078e+00, -7.26599866e+00, -1.58917233e+01,
6.53699818e-03, -9.04540539e+00, 8.79286848e+00, 6.27415632e+00]), 6.53699818e-03, -9.04540539e+00, 8.79286848e+00, 6.27415632e+00]),
array([ -0.53748752, -0.57110591, 0.30915222, -0.51412661, array([ -0.53748752, -0.57110591, 0.30915222, -0.51412661,
-0.41803765, -1.35242478, -7.14026352, -15.72362899, -0.41803765, -1.35242478, -7.14026352, -15.72362899,
-0.11509169, -8.94598278, 9.1143217 , 6.60600793]), -0.11509169, -8.94598278, 9.1143217 , 6.60600793]),
array([ -0.54451093, -0.58666173, 0.30892232, -0.52297409, array([ -0.54451093, -0.58666173, 0.30892232, -0.52297409,
-0.40861233, -1.34551555, -7.02341061, -15.55581677, -0.40861233, -1.34551555, -7.02341061, -15.55581677,
-0.22990601, -8.84748612, 9.4253214 , 6.90922956]), -0.22990601, -8.84748612, 9.4253214 , 6.90922956]),
array([ -0.55142652, -0.60205098, 0.3085847 , -0.53172388, array([ -0.55142652, -0.60205098, 0.3085847 , -0.53172388,
-0.39888609, -1.33832937, -6.91558037, -15.38925966, -0.39888609, -1.33832937, -6.91558037, -15.38925966,
-0.33761958, -8.7497876 , 9.72624596, 7.18617115]), -0.33761958, -8.7497876 , 9.72624596, 7.18617115]),
array([ -0.55824342, -0.61727584, 0.30814674, -0.54037663, array([ -0.55824342, -0.61727584, 0.30814674, -0.54037663,
-0.38886864, -1.33089029, -6.81690514, -15.22485838, -0.38886864, -1.33089029, -6.81690514, -15.22485838,
-0.43795602, -8.65275509, 10.01744331, 7.439083 ]), -0.43795602, -8.65275509, 10.01744331, 7.439083 ]),
array([ -0.56497093, -0.63233929, 0.30761609, -0.54893289, array([ -0.56497093, -0.63233929, 0.30761609, -0.54893289,
-0.37856941, -1.32322018, -6.72750852, -15.06344434, -0.37856941, -1.32322018, -6.72750852, -15.06344434,
-0.53065258, -8.55625368, 10.29923541, 7.67011608]), -0.53065258, -8.55625368, 10.29923541, 7.67011608]),
array([ -0.57161843, -0.64724507, 0.30700062, -0.55739303, array([ -0.57161843, -0.64724507, 0.30700062, -0.55739303,
-0.36799749, -1.31533885, -6.64750444, -14.90578262, -0.36799749, -1.31533885, -6.64750444, -14.90578262,
-0.61546344, -8.46014706, 10.57192223, 7.88132295]), -0.61546344, -8.46014706, 10.57192223, 7.88132295]),
array([ -0.57819543, -0.66199764, 0.30630846, -0.56575733, array([ -0.57819543, -0.66199764, 0.30630846, -0.56575733,
-0.3571617 , -1.30726419, -6.57699617, -14.75257477, -0.3571617 , -1.30726419, -6.57699617, -14.75257477,
-0.69216269, -8.36429872, 10.83578536, 8.07465908]), -0.69216269, -8.36429872, 10.83578536, 8.07465908]),
array([ -0.5847115 , -0.67660211, 0.30554791, -0.57402591, array([ -0.5847115 , -0.67660211, 0.30554791, -0.57402591,
-0.34607061, -1.29901221, -6.51607506, -14.60446164, -0.34607061, -1.29901221, -6.51607506, -14.60446164,
-0.76054691, -8.26857311, 11.09109123, 8.25198457]), -0.76054691, -8.26857311, 11.09109123, 8.25198457]),
array([ -0.59117632, -0.69106413, 0.30472748, -0.58219874, array([ -0.59117632, -0.69106413, 0.30472748, -0.58219874,
-0.33473252, -1.29059714, -6.46481929, -14.46202614, -0.33473252, -1.29059714, -6.46481929, -14.46202614,
-0.82043742, -8.1728367 , 11.33809393, 8.4150661 ]), -0.82043742, -8.1728367 , 11.33809393, 8.4150661 ]),
array([ -0.59759962, -0.70538993, 0.30385579, -0.5902757 , array([ -0.59759962, -0.70538993, 0.30385579, -0.5902757 ,
-0.32315548, -1.28203156, -6.42329262, -14.32579581, -0.32315548, -1.28203156, -6.42329262, -14.32579581,
-0.8716822 , -8.07695892, 11.57703762, 8.56557919]), -0.8716822 , -8.07695892, 11.57703762, 8.56557919]),
array([ -0.60399116, -0.71958617, 0.30294164, -0.59825652, array([ -0.60399116, -0.71958617, 0.30294164, -0.59825652,
-0.31134732, -1.27332645, -6.39154306, -14.19624542, -0.31134732, -1.27332645, -6.39154306, -14.19624542,
-0.91415738, -7.98081308, 11.80815858, 8.70511053]), -0.91415738, -7.98081308, 11.80815858, 8.70511053]),
array([ -0.61036076, -0.73365997, 0.30199387, -0.60614079, array([ -0.61036076, -0.73365997, 0.30199387, -0.60614079,
-0.29931563, -1.26449129, -6.36960168, -14.07379943, -0.29931563, -1.26449129, -6.36960168, -14.07379943,
-0.94776843, -7.88427728, 12.03168691, 8.83516047]), -0.94776843, -7.88427728, 12.03168691, 8.83516047]),
array([ -0.61671824, -0.74761881, 0.30102142, -0.61392803, array([ -0.61671824, -0.74761881, 0.30102142, -0.61392803,
-0.28706778, -1.25553415, -6.3574815 , -13.95883437, -0.28706778, -1.25553415, -6.3574815 , -13.95883437,
-0.97245098, -7.78723516, 12.24784788, 8.95714568]), -0.97245098, -7.78723516, 12.24784788, 8.95714568]),
array([ -0.62307342, -0.76147049, 0.30003325, -0.6216176 , array([ -0.62307342, -0.76147049, 0.30003325, -0.6216176 ,
-0.27461092, -1.24646175, -6.3551764 , -13.85168117, -0.27461092, -1.24646175, -6.3551764 , -13.85168117,
-0.98817127, -7.6895768 , 12.45686299, 9.07240169]), -0.98817127, -7.6895768 , 12.45686299, 9.07240169]),
array([ -0.62943608, -0.77522312, 0.29903832, -0.6292088 , array([ -0.62943608, -0.77522312, 0.29903832, -0.6292088 ,
-0.26195197, -1.23727956, -6.36266027, -13.75262739, -0.26195197, -1.23727956, -6.36266027, -13.75262739,
-0.99492633, -7.59119936, 12.65895071, 9.18218558]), -0.99492633, -7.59119936, 12.65895071, 9.18218558]),
array([ -0.63581597, -0.78888504, 0.29804558, -0.63670081, array([ -0.63581597, -0.78888504, 0.29804558, -0.63670081,
-0.24909764, -1.22799188, -6.37988614, -13.66191935, -0.24909764, -1.22799188, -6.37988614, -13.66191935,
-0.99274382, -7.49200791, 12.85432699, 9.28767864]), -0.99274382, -7.49200791, 12.85432699, 9.28767864]),
array([ -0.64222275, -0.8024648 , 0.2970639 , -0.64409273, array([ -0.64222275, -0.8024648 , 0.2970639 , -0.64409273,
-0.23605444, -1.21860189, -6.40678561, -13.57976429, -0.23605444, -1.21860189, -6.40678561, -13.57976429,
-0.98168158, -7.39191608, 13.04320548, 9.38998897]), -0.98168158, -7.39191608, 13.04320548, 9.38998897]),
array([ -0.64866602, -0.81597113, 0.29610207, -0.65138357, array([ -0.64866602, -0.81597113, 0.29610207, -0.65138357,
-0.22282864, -1.20911174, -6.44326823, -13.50633234, -0.22282864, -1.20911174, -6.44326823, -13.50633234,
-0.96182695, -7.29084673, 13.22579764, 9.49015406]), -0.96182695, -7.29084673, 13.22579764, 9.49015406]),
array([ -0.65515524, -0.82941289, 0.29516877, -0.65857231, array([ -0.65515524, -0.82941289, 0.29516877, -0.65857231,
-0.20942633, -1.19952259, -6.48922118, -13.44175848, -0.20942633, -1.19952259, -6.48922118, -13.44175848,
-0.93329584, -7.18873261, 13.40231249, 9.58914333]), -0.93329584, -7.18873261, 13.40231249, 9.58914333]),
array([ -0.66169975, -0.84279904, 0.29427254, -0.66565782, array([ -0.66169975, -0.84279904, 0.29427254, -0.66565782,
-0.19585337, -1.18983473, -6.54450888, -13.38614451, -0.19585337, -1.18983473, -6.54450888, -13.38614451,
-0.89623163, -7.08551695, 13.57295639, 9.68786058]), -0.89623163, -7.08551695, 13.57295639, 9.68786058]),
array([ -0.66830872, -0.8561386 , 0.29342174, -0.67263898, array([ -0.66830872, -0.8561386 , 0.29342174, -0.67263898,
-0.18211544, -1.18004759, -6.60897287, -13.33956084, -0.18211544, -1.18004759, -6.60897287, -13.33956084,
-0.8508039 , -6.98115404, 13.73793249, 9.78714635]), -0.8508039 , -6.98115404, 13.73793249, 9.78714635]),
array([ -0.67499115, -0.86944064, 0.29262453, -0.67951459, array([ -0.67499115, -0.86944064, 0.29262453, -0.67951459,
-0.168218 , -1.17015981, -6.68243165, -13.30204826, -0.168218 , -1.17015981, -6.68243165, -13.30204826,
-0.79720702, -6.87560983, 13.8974402 , 9.88778023]), -0.79720702, -6.87560983, 13.8974402 , 9.88778023]),
array([ -0.68175583, -0.88271426, 0.29188887, -0.68628345, array([ -0.68175583, -0.88271426, 0.29188887, -0.68628345,
-0.15416632, -1.16016932, -6.76468059, -13.27361976, -0.15416632, -1.16016932, -6.76468059, -13.27361976,
-0.73565866, -6.76886237, 14.05167446, 9.990483 ]), -0.73565866, -6.76886237, 14.05167446, 9.990483 ]),
array([ -0.68861133, -0.89596853, 0.29122247, -0.69294435, array([ -0.68861133, -0.89596853, 0.29122247, -0.69294435,
-0.1399655 , -1.15007341, -6.85549197, -13.25426213, -0.1399655 , -1.15007341, -6.85549197, -13.25426213,
-0.66639828, -6.66090239, 14.20082496, 10.09591868]), -0.66639828, -6.66090239, 14.20082496, 10.09591868]),
array([ -0.69556594, -0.90921246, 0.29063279, -0.69949609, array([ -0.69556594, -0.90921246, 0.29063279, -0.69949609,
-0.12562042, -1.13986871, -6.95461487, -13.24393758, -0.12562042, -1.13986871, -6.95461487, -13.24393758,
-0.58968554, -6.5517337 , 14.34507534, 10.20469651]), -0.58968554, -6.5517337 , 14.34507534, 10.20469651]),
array([ -0.70262772, -0.92245505, 0.29012699, -0.70593746, array([ -0.70262772, -0.92245505, 0.29012699, -0.70593746,
-0.11113582, -1.12955134, -7.06177522, -13.24258537, -0.11113582, -1.12955134, -7.06177522, -13.24258537,
-0.50579883, -6.44137369, 14.48460221, 10.31737269]), -0.50579883, -6.44137369, 14.48460221, 10.31737269]),
array([ -0.70980439, -0.93570517, 0.28971195, -0.71226731, array([ -0.70980439, -0.93570517, 0.28971195, -0.71226731,
-0.09651625, -1.11911688, -7.17667564, -13.25012325, -0.09651625, -1.11911688, -7.17667564, -13.25012325,
-0.41503378, -6.32985377, 14.61957428, 10.434452 ]), -0.41503378, -6.32985377, 14.61957428, 10.434452 ]),
array([ -0.71710339, -0.94897162, 0.28939425, -0.71848453, array([ -0.71710339, -0.94897162, 0.28939425, -0.71848453,
-0.0817661 , -1.1085605 , -7.29899532, -13.2664489 , -0.0817661 , -1.1085605 , -7.29899532, -13.2664489 ,
-0.3177019 , -6.21721975, 14.75015135, 10.5563893 ]), -0.3177019 , -6.21721975, 14.75015135, 10.5563893 ]),
array([ -0.72453178, -0.96226306, 0.28918012, -0.72458807, array([ -0.72453178, -0.96226306, 0.28918012, -0.72458807,
-0.06688961, -1.0978769 , -7.42838975, -13.29144137, -0.06688961, -1.0978769 , -7.42838975, -13.29144137,
-0.21412938, -6.10353226, 14.87648338, 10.68359081]), -0.21412938, -6.10353226, 14.87648338, 10.68359081]),
array([ -0.73209627, -0.97558802, 0.28907547, -0.73057693, array([ -0.73209627, -0.97558802, 0.28907547, -0.73057693,
-0.0518909 , -1.08706049, -7.5644903 , -13.32496232, -0.0518909 , -1.08706049, -7.5644903 , -13.32496232,
-0.10465604, -5.98886722, 14.99870949, 10.81641516]), -0.10465604, -5.98886722, 14.99870949, 10.81641516]),
array([-7.39803171e-01, -9.88954882e-01, 2.89085833e-01, -7.36450249e-01, array([-7.39803171e-01, -9.88954882e-01, 2.89085833e-01, -7.36450249e-01,
-3.67739462e-02, -1.07610531e+00, -7.70690368e+00, -1.33668573e+01, -3.67739462e-02, -1.07610531e+00, -7.70690368e+00, -1.33668573e+01,
1.03654748e-02, -5.87331615e+00, 1.51169570e+01, 1.09551743e+01]), 1.03654748e-02, -5.87331615e+00, 1.51169570e+01, 1.09551743e+01]),
array([ -0.74765838, -1.00237184, 0.2892164 , -0.74220724, array([ -0.74765838, -1.00237184, 0.2892164 , -0.74220724,
-0.02154261, -1.06500518, -7.85521117, -13.41695703, -0.02154261, -1.06500518, -7.85521117, -13.41695703,
0.13057031, -5.75698669, 15.23134061, 11.10013423]), 0.13057031, -5.75698669, 15.23134061, 11.10013423]),
array([-7.55667350e-01, -1.01584692e+00, 2.89471985e-01, -7.47847239e-01, array([-7.55667350e-01, -1.01584692e+00, 2.89471985e-01, -7.47847239e-01,
-6.20064425e-03, -1.05375367e+00, -8.00896769e+00, -1.34750782e+01, -6.20064425e-03, -1.05375367e+00, -8.00896769e+00, -1.34750782e+01,
2.55581661e-01, -5.64000293e+00, 1.53419613e+01, 1.12515153e+01]), 2.55581661e-01, -5.64000293e+00, 1.53419613e+01, 1.12515153e+01]),
array([-7.63835051e-01, -1.02938794e+00, 2.89856995e-01, -7.53369745e-01, array([-7.63835051e-01, -1.02938794e+00, 2.89856995e-01, -7.53369745e-01,
9.24826154e-03, -1.04234417e+00, -8.16770052e+00, -1.35410248e+01, 9.24826154e-03, -1.04234417e+00, -8.16770052e+00, -1.35410248e+01,
3.85010746e-01, -5.52250593e+00, 1.54489058e+01, 1.14094924e+01]), 3.85010746e-01, -5.52250593e+00, 1.54489058e+01, 1.14094924e+01]),
array([ -0.77216596, -1.04300253, 0.29037545, -0.7587744 , array([ -0.77216596, -1.04300253, 0.29037545, -0.7587744 ,
0.02480051, -1.03076998, -8.33090785, -13.61458907, 0.02480051, -1.03076998, -8.33090785, -13.61458907,
0.51845642, -5.40465411, 15.5522455 , 11.57419512]), 0.51845642, -5.40465411, 15.5522455 , 11.57419512]),
array([ -0.78066402, -1.05669808, 0.29103096, -0.76406102, array([ -0.78066402, -1.05669808, 0.29103096, -0.76406102,
0.04045254, -1.01902427, -8.49805702, -13.69555202, 0.04045254, -1.01902427, -8.49805702, -13.69555202,
0.65550439, -5.28662374, 15.65203609, 11.74570724]), 0.65550439, -5.28662374, 15.65203609, 11.74570724]),
array([ -0.7893326 , -1.07048177, 0.29182668, -0.76922963, array([ -0.7893326 , -1.07048177, 0.29182668, -0.76922963,
0.05620086, -1.0071002 , -8.6685824 , -13.78368461, 0.05620086, -1.0071002 , -8.6685824 , -13.78368461,
0.79572601, -5.16860944, 15.74831676, 11.92406621]), 0.79572601, -5.16860944, 15.74831676, 11.92406621]),
array([ -0.79817448, -1.08436052, 0.29276536, -0.77428046, array([ -0.79817448, -1.08436052, 0.29276536, -0.77428046,
0.07204197, -0.99499094, -8.84188304, -13.87874825, 0.07204197, -0.99499094, -8.84188304, -13.87874825,
0.93867661, -5.05082459, 15.84110985, 12.1092623 ]), 0.93867661, -5.05082459, 15.84110985, 12.1092623 ]),
array([ -0.8071918 , -1.09834101, 0.29384925, -0.77921396, array([ -0.8071918 , -1.09834101, 0.29384925, -0.77921396,
0.08797239, -0.9826897 , -9.01731994, -13.98049544, 0.08797239, -0.9826897 , -9.01731994, -13.98049544,
1.08389336, -4.93350187, 15.93042051, 12.30123763]), 1.08389336, -4.93350187, 15.93042051, 12.30123763]),
array([ -0.81638601, -1.11242968, 0.29508014, -0.78403085, array([ -0.81638601, -1.11242968, 0.29508014, -0.78403085,
0.10398863, -0.97018982, -9.19421298, -14.08867029, 0.10398863, -0.97018982, -9.19421298, -14.08867029,
1.23089264, -4.81689369, 16.0162365 , 12.49988475]), 1.23089264, -4.81689369, 16.0162365 , 12.49988475]),
array([ -0.82575785, -1.12663269, 0.29645931, -0.78873212, array([ -0.82575785, -1.12663269, 0.29645931, -0.78873212,
0.12008715, -0.95748477, -9.37183768, -14.20300897, 0.12008715, -0.95748477, -9.37183768, -14.20300897,
1.37916686, -4.70127256, 16.09852823, 12.70504523]), 1.37916686, -4.70127256, 16.09852823, 12.70504523]),
array([ -0.83530727, -1.14095593, 0.29798749, -0.79331906, array([ -0.83530727, -1.14095593, 0.29798749, -0.79331906,
0.1362644 , -0.94456827, -9.54942153, -14.32323999, 0.1362644 , -0.94456827, -9.54942153, -14.32323999,
1.52818082, -4.58693149, 16.17724894, 12.91650789]), 1.52818082, -4.58693149, 16.17724894, 12.91650789]),
array([ -0.84503341, -1.15540502, 0.29966486, -0.79779324, array([ -0.84503341, -1.15540502, 0.29966486, -0.79779324,
0.15251674, -0.93143426, -9.72614024, -14.44908447, 0.15251674, -0.93143426, -9.72614024, -14.44908447,
1.67736753, -4.4741842 , 16.25233514, 13.13400702]), 1.67736753, -4.4741842 , 16.25233514, 13.13400702]),
array([ -0.85493453, -1.16998527, 0.30149098, -0.80215661, array([ -0.85493453, -1.16998527, 0.30149098, -0.80215661,
0.16884045, -0.91807704, -9.9011138 , -14.58025626, 0.16884045, -0.91807704, -9.9011138 , -14.58025626,
1.82612363, -4.36336523, 16.32370724, 13.35722043]), 1.82612363, -4.36336523, 16.32370724, 13.35722043]),
array([ -0.86500793, -1.18470173, 0.30346479, -0.80641144, array([ -0.86500793, -1.18470173, 0.30346479, -0.80641144,
0.18523172, -0.90449127, -10.07340252, -14.71646196, 0.18523172, -0.90449127, -10.07340252, -14.71646196,
1.97380437, -4.25482988, 16.39127052, 13.58576756]), 1.97380437, -4.25482988, 16.39127052, 13.58576756]),
array([ -0.87524993, -1.19955913, 0.30558451, -0.81056039, array([ -0.87524993, -1.19955913, 0.30558451, -0.81056039,
0.20168663, -0.89067206, -10.24200319, -14.85740083, 0.20168663, -0.89067206, -10.24200319, -14.85740083,
2.11971834, -4.14895382, 16.45491622, 13.8192076 ]), 2.11971834, -4.14895382, 16.45491622, 13.8192076 ]),
array([ -0.88565578, -1.2145619 , 0.30784763, -0.81460652, array([ -0.88565578, -1.2145619 , 0.30784763, -0.81460652,
0.21820116, -0.87661503, -10.40584554, -15.00276464, 0.21820116, -0.87661503, -10.40584554, -15.00276464,
2.26312208, -4.04613254, 16.51452315, 14.05703782]), 2.26312208, -4.04613254, 16.51452315, 14.05703782]),
array([ -0.89621957, -1.22971414, 0.31025084, -0.8185533 , array([ -0.89621957, -1.22971414, 0.31025084, -0.8185533 ,
0.23477112, -0.86231633, -10.56378922, -15.15223736, 0.23477112, -0.86231633, -10.56378922, -15.15223736,
2.4032147 , -3.9467803 , 16.56995935, 14.29869225]), 2.4032147 , -3.9467803 , 16.56995935, 14.29869225]),
array([ -0.90693419, -1.24501963, 0.31278998, -0.82240463, array([ -0.90693419, -1.24501963, 0.31278998, -0.82240463,
0.2513922 , -0.84777279, -10.71462159, -15.30549477, 0.2513922 , -0.84777279, -10.71462159, -15.30549477,
2.53913287, -3.85132866, 16.62108426, 14.5435408 ]), 2.53913287, -3.85132866, 16.62108426, 14.5435408 ]),
array([ -0.91779125, -1.26048184, 0.31545992, -0.82616486, array([ -0.91779125, -1.26048184, 0.31545992, -0.82616486,
0.26805995, -0.8329819 , -10.85705664, -15.46220406, 0.26805995, -0.8329819 , -10.85705664, -15.46220406,
2.66994647, -3.76022451, 16.66775103, 14.79088897]), 2.66994647, -3.76022451, 16.66775103, 14.79088897]),
array([ -0.92878098, -1.27610386, 0.31825458, -0.82983878, array([ -0.92878098, -1.27610386, 0.31825458, -0.82983878,
0.28476976, -0.81794193, -10.98973552, -15.62202322, 0.28476976, -0.81794193, -10.98973552, -15.62202322,
2.79465524, -3.67392749, 16.70980925, 15.03997855]), 2.79465524, -3.67392749, 16.70980925, 15.03997855]),
array([ -0.93989221, -1.29188846, 0.32116676, -0.83343169, array([ -0.93989221, -1.29188846, 0.32116676, -0.83343169,
0.30151687, -0.80265194, -11.11122896, -15.78460053, 0.30151687, -0.80265194, -11.11122896, -15.78460053,
2.91218705, -3.59290666, 16.74710782, 15.28998925]), 2.91218705, -3.59290666, 16.74710782, 15.28998925]),
array([ -0.95111225, -1.30783803, 0.32418816, -0.83694933, array([ -0.95111225, -1.30783803, 0.32418816, -0.83694933,
0.31829637, -0.78711189, -11.22004232, -15.94957391, 0.31829637, -0.78711189, -11.22004232, -15.94957391,
3.02139823, -3.51763649, 16.77949816, 15.54004168]), 3.02139823, -3.51763649, 16.77949816, 15.54004168]),
array([ -0.96242688, -1.3239546 , 0.32730924, -0.84039792, array([ -0.96242688, -1.3239546 , 0.32730924, -0.84039792,
0.3351032 , -0.77132269, -11.31462365, -16.1165704 , 0.3351032 , -0.77132269, -11.31462365, -16.1165704 ,
3.12107664, -3.44859198, 16.8068375 , 15.78920187]), 3.12107664, -3.44859198, 16.8068375 , 15.78920187]),
array([ -0.97382025, -1.34023981, 0.33051919, -0.84378416, array([ -0.97382025, -1.34023981, 0.33051919, -0.84378416,
0.3519322 , -0.75528621, -11.39337534, -16.28520561, 0.3519322 , -0.75528621, -11.39337534, -16.28520561,
3.20994822, -3.38624303, 16.82899234, 16.03648757]), 3.20994822, -3.38624303, 16.82899234, 16.03648757]),
array([ -0.98527492, -1.35669489, 0.33380588, -0.84711521, array([ -0.98527492, -1.35669489, 0.33380588, -0.84711521,
0.36877804, -0.73900533, -11.45467004, -16.45508338, 0.36877804, -0.73900533, -11.45467004, -16.45508338,
3.2866876 , -3.33104788, 16.84584196, 16.28087642]), 3.2866876 , -3.33104788, 16.84584196, 16.28087642]),
array([ -0.99677179, -1.37332069, 0.33715581, -0.85039865, array([ -0.99677179, -1.37332069, 0.33715581, -0.85039865,
0.38563532, -0.72248401, -11.49687118, -16.62579552, 0.38563532, -0.72248401, -11.49687118, -16.62579552,
3.34993357, -3.28344581, 16.85728188, 16.52131626]), 3.34993357, -3.28344581, 16.85728188, 16.52131626]),
array([ -1.00829015, -1.39011761, 0.34055412, -0.8536425 , array([ -1.00829015, -1.39011761, 0.34055412, -0.8536425 ,
0.40249855, -0.70572728, -11.51835857, -16.79692187, 0.40249855, -0.70572728, -11.51835857, -16.79692187,
3.39830993, -3.24384918, 16.86322715, 16.75673763]), 3.39830993, -3.24384918, 16.86322715, 16.75673763]),
array([ -1.01980771, -1.40708564, 0.34398457, -0.85685514, array([ -1.01980771, -1.40708564, 0.34398457, -0.85685514,
0.41936216, -0.68874121, -11.51755923, -16.96803066, 0.41936216, -0.68874121, -11.51755923, -16.96803066,
3.43045216, -3.21263479, 16.86361551, 16.9860682 ]), 3.43045216, -3.21263479, 16.86361551, 16.9860682 ]),
array([ -1.03130069, -1.42422432, 0.34742961, -0.86004527, array([ -1.03130069, -1.42422432, 0.34742961, -0.86004527,
0.43622057, -0.67153296, -11.49298346, -17.13867923, 0.43622057, -0.67153296, -11.49298346, -17.13867923,
3.4450402 , -3.19013505, 16.85841006, 17.20824929]), 3.4450402 , -3.19013505, 16.85841006, 17.20824929]),
array([ -1.04274396, -1.44153273, 0.35087045, -0.8632219 , array([ -1.04274396, -1.44153273, 0.35087045, -0.8632219 ,
0.45306817, -0.6541107 , -11.44326564, -17.30841513, 0.45306817, -0.6541107 , -11.44326564, -17.30841513,
3.44083697, -3.17662891, 16.84760165, 17.42225374]), 3.44083697, -3.17662891, 16.84760165, 17.42225374]),
array([ -1.05411117, -1.45900951, 0.35428718, -0.86639424, array([ -1.05411117, -1.45900951, 0.35428718, -0.86639424,
0.46989938, -0.6364836 , -11.36720908, -17.47677782, 0.46989938, -0.6364836 , -11.36720908, -17.47677782,
3.41673229, -3.17233319, 16.83121066, 17.62710492]), 3.41673229, -3.17233319, 16.83121066, 17.62710492]),
array([ -1.065375 , -1.47665281, 0.35765897, -0.86957163, array([ -1.065375 , -1.47665281, 0.35765897, -0.86957163,
0.48670867, -0.6186617 , -11.26383348, -17.64330072, 0.48670867, -0.6186617 , -11.26383348, -17.64330072,
3.37179088, -3.17739441, 16.80928813, 17.82189591]), 3.37179088, -3.17739441, 16.80928813, 17.82189591]),
array([ -1.07650743, -1.49446033, 0.36096427, -0.87276351, array([ -1.07650743, -1.49446033, 0.36096427, -0.87276351,
0.50349059, -0.60065589, -11.13242342, -17.80751385, 0.50349059, -0.60065589, -11.13242342, -17.80751385,
3.30530282, -3.19188172, 16.78191635, 18.00580825]), 3.30530282, -3.19188172, 16.78191635, 18.00580825]),
array([ -1.08748 , -1.51242927, 0.36418111, -0.87597929, array([ -1.08748 , -1.51242927, 0.36418111, -0.87597929,
0.5202398 , -0.58247777, -10.97257543, -17.9689469 , 0.5202398 , -0.58247777, -10.97257543, -17.9689469 ,
3.21683423, -3.21578135, 16.74920855, 18.17812899]), 3.21683423, -3.21578135, 16.74920855, 18.17812899]),
array([ -1.09826424, -1.53055641, 0.36728738, -0.87922829, array([ -1.09826424, -1.53055641, 0.36728738, -0.87922829,
0.53695111, -0.5641395 , -10.78424102, -18.12713283, 0.53695111, -0.5641395 , -10.78424102, -18.12713283,
3.10627521, -3.24899287, 16.71130802, 18.33826537]), 3.10627521, -3.24899287, 16.71130802, 18.33826537]),
array([ -1.108832 , -1.54883802, 0.37026127, -0.88251961, array([ -1.108832 , -1.54883802, 0.37026127, -0.88251961,
0.55361949, -0.54565374, -10.56776264, -18.28161168, 0.55361949, -0.54565374, -10.56776264, -18.28161168,
2.97388186, -3.29132773, 16.66838638, 18.48575592]), 2.97388186, -3.29132773, 16.66838638, 18.48575592]),
array([ -1.1191559 , -1.56726995, 0.37308157, -0.88586212, array([ -1.1191559 , -1.56726995, 0.37308157, -0.88586212,
0.57024013, -0.52703347, -10.32389935, -18.43193482, 0.57024013, -0.52703347, -10.32389935, -18.43193482,
2.8203087 , -3.34251034, 16.62064121, 18.62027732]), 2.8203087 , -3.34251034, 16.62064121, 18.62027732]),
array([ -1.12920974, -1.58584762, 0.3757282 , -0.88926431, array([ -1.12920974, -1.58584762, 0.3757282 , -0.88926431,
0.58680843, -0.50829182, -10.05383925, -18.57766927, 0.58680843, -0.50829182, -10.05383925, -18.57766927,
2.64662803, -3.4021817 , 16.568293 , 18.74164654]), 2.64662803, -3.4021817 , 16.568293 , 18.74164654]),
array([ -1.13896894, -1.60456602, 0.37818254, -0.89273421, array([ -1.13896894, -1.60456602, 0.37818254, -0.89273421,
0.60332001, -0.489442 , -9.75919604, -18.71840214, 0.60332001, -0.489442 , -9.75919604, -18.71840214,
2.45433279, -3.4699056 , 16.51158156, 18.84981797]), 2.45433279, -3.4699056 , 16.51158156, 18.84981797]),
array([ -1.14841093, -1.62341977, 0.38042786, -0.89627939, array([ -1.14841093, -1.62341977, 0.38042786, -0.89627939,
0.61977077, -0.47049713, -9.44198757, -18.85374498, 0.61977077, -0.47049713, -9.44198757, -18.85374498,
2.24532042, -3.54517708, 16.45076195, 18.94487593]), 2.24532042, -3.54517708, 16.45076195, 18.94487593]),
array([ -1.15751552, -1.64240311, 0.38244971, -0.89990682, array([ -1.15751552, -1.64240311, 0.38244971, -0.89990682,
0.63615687, -0.4514701 , -9.1045957 , -18.98333792, 0.63615687, -0.4514701 , -9.1045957 , -18.98333792,
2.02185592, -3.62743262, 16.38610011, 19.02702317]), 2.02185592, -3.62743262, 16.38610011, 19.02702317]),
array([ -1.16626523, -1.66150996, 0.38423623, -0.90362288, array([ -1.16626523, -1.66150996, 0.38423623, -0.90362288,
0.65247474, -0.43237354, -8.74970755, -19.10685358, 0.65247474, -0.43237354, -8.74970755, -19.10685358,
1.78651381, -3.71606143, 16.31786815, 19.09656648]), 1.78651381, -3.71606143, 16.31786815, 19.09656648]),
array([ -1.17464547, -1.68073396, 0.38577833, -0.9074333 , array([ -1.17464547, -1.68073396, 0.38577833, -0.9074333 ,
0.66872108, -0.41321964, -8.38023998, -19.22400046, 0.66872108, -0.41321964, -8.38023998, -19.22400046,
1.54210032, -3.810417 , 16.24633974, 19.15390072]), 1.54210032, -3.810417 , 16.24633974, 19.15390072]),
array([ -1.18264472, -1.70006849, 0.38706988, -0.91134313, array([ -1.18264472, -1.70006849, 0.38706988, -0.91134313,
0.68489286, -0.39402014, -7.99925041, -19.33452593, 0.68489286, -0.39402014, -7.99925041, -19.33452593,
1.29155856, -3.90982793, 16.1717854 , 19.19949292]), 1.29155856, -3.90982793, 16.1717854 , 19.19949292]),
array([ -1.19025456, -1.71950671, 0.38810775, -0.91535674, array([ -1.19025456, -1.71950671, 0.38810775, -0.91535674,
0.70098733, -0.37478628, -7.60983853, -19.43821861, 0.70098733, -0.37478628, -7.60983853, -19.43821861,
1.0378616 , -4.01360743, 16.09446813, 19.23386774]), 1.0378616 , -4.01360743, 16.09446813, 19.23386774]),
array([ -1.1974696 , -1.73904162, 0.38889165, -0.9194778 , array([ -1.1974696 , -1.73904162, 0.38889165, -0.9194778 ,
0.71700197, -0.35552868, -7.21504457, -19.5349101 , 0.71700197, -0.35552868, -7.21504457, -19.5349101 ,
0.78389951, -4.12106075, 16.01463933, 19.25759585]), 0.78389951, -4.12106075, 16.01463933, 19.25759585]),
array([ -1.20428735, -1.75866609, 0.38942401, -0.92370929, array([ -1.20428735, -1.75866609, 0.38942401, -0.92370929,
0.73293451, -0.33625739, -6.81775056, -19.62447611, 0.73293451, -0.33625739, -6.81775056, -19.62447611,
0.53236778, -4.23149029, 15.93253531, 19.2712858 ]), 0.53236778, -4.23149029, 15.93253531, 19.2712858 ]),
array([ -1.21070795, -1.77837293, 0.38970968, -0.92805348, array([ -1.21070795, -1.77837293, 0.38970968, -0.92805348,
0.74878288, -0.31698181, -6.42059105, -19.706837 , 0.74878288, -0.31698181, -6.42059105, -19.706837 ,
0.28566501, -4.34419857, 15.84837446, 19.27558001]), 0.28566501, -4.34419857, 15.84837446, 19.27558001]),
array([ -1.21673382, -1.79815489, 0.38975549, -0.93251197, array([ -1.21673382, -1.79815489, 0.38975549, -0.93251197,
0.76454524, -0.29771066, -6.02587943, -19.78195756, 0.76454524, -0.29771066, -6.02587943, -19.78195756,
0.04580761, -4.45848952, 15.76235521, 19.27115448]), 0.04580761, -4.45848952, 15.76235521, 19.27115448]),
array([ -1.22236938, -1.81800473, 0.38956985, -0.93708564, array([ -1.22236938, -1.81800473, 0.38956985, -0.93708564,
0.78021989, -0.27845194, -5.63555483, -19.84984636, 0.78021989, -0.27845194, -5.63555483, -19.84984636,
-0.1856317 , -4.57366904, 15.67465492, 19.25872159]), -0.1856317 , -4.57366904, 15.67465492, 19.25872159]),
array([ -1.22762053, -1.83791529, 0.3891623 , -0.94177469, array([ -1.22762053, -1.83791529, 0.3891623 , -0.94177469,
0.79580532, -0.2592129 , -5.25115301, -19.91055441, 0.79580532, -0.2592129 , -5.25115301, -19.91055441,
-0.40755674, -4.68904599, 15.58542974, 19.23903459]), -0.40755674, -4.68904599, 15.58542974, 19.23903459]),
array([ -1.23249434, -1.85787946, 0.38854295, -0.94657862, array([ -1.23249434, -1.85787946, 0.38854295, -0.94657862,
0.81130014, -0.24000001, -4.87380241, -19.96417331, 0.81130014, -0.24000001, -4.87380241, -19.96417331,
-0.61934952, -4.80393471, 15.49481548, 19.21289229]), -0.61934952, -4.80393471, 15.49481548, 19.21289229]),
array([ -1.23699858, -1.87789029, 0.38772211, -0.95149628, array([ -1.23699858, -1.87789029, 0.38772211, -0.95149628,
0.82670307, -0.22081887, -4.5042444 , -20.01083296, 0.82670307, -0.22081887, -4.5042444 , -20.01083296,
-0.82084119, -4.91766001, 15.40292944, 19.18114228]), -0.82084119, -4.91766001, 15.40292944, 19.18114228]),
array([ -1.24114145, -1.89794099, 0.38670985, -0.95652585, array([ -1.24114145, -1.89794099, 0.38670985, -0.95652585,
0.84201294, -0.20167419, -4.14287467, -20.05069859, 0.84201294, -0.20167419, -4.14287467, -20.05069859,
-1.01225547, -5.02956527, 15.30987311, 19.14468112]), -1.01225547, -5.02956527, 15.30987311, 19.14468112]),
array([ -1.24493125, -1.91802496, 0.38551572, -0.96166487, array([ -1.24493125, -1.91802496, 0.38551572, -0.96166487,
0.85722867, -0.18256974, -3.78980067, -20.0839675 , 0.85722867, -0.18256974, -3.78980067, -20.0839675 ,
-1.19413068, -5.1390233 , 15.21573544, 19.1044503 ]), -1.19413068, -5.1390233 , 15.21573544, 19.1044503 ]),
array([ -1.24837616, -1.93813583, 0.38414849, -0.96691032, array([ -1.24837616, -1.93813583, 0.38414849, -0.96691032,
0.87234927, -0.16350831, -3.44490913, -20.11086514, 0.87234927, -0.16350831, -3.44490913, -20.11086514,
-1.36722804, -5.24544971, 15.12059665, 19.06142734]), -1.36722804, -5.24544971, 15.12059665, 19.06142734]),
array([ -1.2514841 , -1.95826747, 0.38261606, -0.97225864, array([ -1.2514841 , -1.95826747, 0.38261606, -0.97225864,
0.8873738 , -0.1444917 , -3.10793712, -20.13164088, 0.8873738 , -0.1444917 , -3.10793712, -20.13164088,
-1.53243505, -5.34831717, 15.02453213, 19.0166119 ]), -1.53243505, -5.34831717, 15.02453213, 19.0166119 ]),
array([ -1.25426264, -1.97841403, 0.38092538, -0.97770581, array([ -1.25426264, -1.97841403, 0.38092538, -0.97770581,
0.90230142, -0.12552069, -2.77854031, -20.14656341, 0.90230142, -0.12552069, -2.77854031, -20.14656341,
-1.69067268, -5.44716933, 14.92761622, 18.97100742]), -1.69067268, -5.44716933, 14.92761622, 18.97100742]),
array([ -1.25671899, -1.99856995, 0.37908257, -0.98324744, array([ -1.25671899, -1.99856995, 0.37908257, -0.98324744,
0.91713134, -0.10659509, -2.45635351, -20.1559159 , 0.91713134, -0.10659509, -2.45635351, -20.1559159 ,
-1.84281361, -5.54163269, 14.82992569, 18.92559948]), -1.84281361, -5.54163269, 14.82992569, 18.92559948]),
array([ -1.25886003, -2.01872994, 0.37709295, -0.98887887, array([ -1.25886003, -2.01872994, 0.37709295, -0.98887887,
0.93186289, -0.08771376, -2.14103949, -20.15999097, 0.93186289, -0.08771376, -2.14103949, -20.15999097,
-1.9896174 , -5.63142495, 14.73154248, 18.8813322 ]), -1.9896174 , -5.63142495, 14.73154248, 18.8813322 ]),
array([ -1.26069236, -2.03888902, 0.37496127, -0.99459523, array([ -1.26069236, -2.03888902, 0.37496127, -0.99459523,
0.94649544, -0.06887467, -1.83232414, -20.15908584, 0.94649544, -0.06887467, -1.83232414, -20.15908584,
-2.13168562, -5.71635894, 14.63255587, 18.83908447]), -2.13168562, -5.71635894, 14.63255587, 18.83908447]),
array([ -1.26222238, -2.05904252, 0.37269183, -1.00039157, array([ -1.26222238, -2.05904252, 0.37269183, -1.00039157,
0.96102851, -0.05007503, -1.53001768, -20.15349756, 0.96102851, -0.05007503, -1.53001768, -20.15349756,
-2.26943774, -5.7963416 , 14.53306378, 18.79964764]), -2.26943774, -5.7963416 , 14.53306378, 18.79964764]),
array([ -1.2634564 , -2.07918604, 0.37028872, -1.00626294, array([ -1.2634564 , -2.07918604, 0.37028872, -1.00626294,
0.97546168, -0.03131132, -1.23402265, -20.14351867, 0.97546168, -0.03131132, -1.23402265, -20.14351867,
-2.40310664, -5.87136831, 14.43317325, 18.76370626]), -2.40310664, -5.87136831, 14.43317325, 18.76370626]),
array([-1.26440073e+00, -2.09931547e+00, 3.67755973e-01, -1.01220445e+00, array([-1.26440073e+00, -2.09931547e+00, 3.67755973e-01, -1.01220445e+00,
9.89794680e-01, -1.25794977e-02, -9.44331072e-01, -2.01294334e+01, 9.89794680e-01, -1.25794977e-02, -9.44331072e-01, -2.01294334e+01,
-2.53275045e+00, -5.94151295e+00, 1.43330003e+01, 1.87318229e+01]), -2.53275045e+00, -5.94151295e+00, 1.43330003e+01, 1.87318229e+01]),
array([-1.26506174e+00, -2.11942699e+00, 3.65097696e-01, -1.01821136e+00, array([-1.26506174e+00, -2.11942699e+00, 3.65097696e-01, -1.01821136e+00,
1.00402735e+00, 6.12493056e-03, -6.61013126e-01, -2.01115143e+01, 1.00402735e+00, 6.12493056e-03, -6.61013126e-01, -2.01115143e+01,
-2.65827691e+00, -6.00691509e+00, 1.42326691e+01, 1.87044283e+01]), -2.65827691e+00, -6.00691509e+00, 1.42326691e+01, 1.87044283e+01]),
array([ -1.26544594, -2.13951701, 0.36231822, -1.02427913, array([ -1.26544594, -2.13951701, 0.36231822, -1.02427913,
1.01815966, 0.02480675, -0.38420035, -20.09001993, 1.01815966, 0.02480675, -0.38420035, -20.09001993,
-2.77947572, -6.06776526, 14.13231072, 18.68181609]), -2.77947572, -6.06776526, 14.13231072, 18.68181609]),
array([ -1.26556001, -2.1595822 , 0.35942217, -1.03040342, array([ -1.26556001, -2.1595822 , 0.35942217, -1.03040342,
1.03219172, 0.04347089, -0.11406597, -20.06519276, 1.03219172, 0.04347089, -0.11406597, -20.06519276,
-2.89605471, -6.12428974, 14.03206177, 18.66414403]), -2.89605471, -6.12428974, 14.03206177, 18.66414403]),
array([ -1.26541081, -2.17961946, 0.35641449, -1.03658015, array([ -1.26541081, -2.17961946, 0.35641449, -1.03658015,
1.04612378, 0.06212233, 0.14919527, -20.03725823, 1.04612378, 0.06212233, 0.14919527, -20.03725823,
-3.00767606, -6.1767359 , 13.93206243, 18.65143881]), -3.00767606, -6.1767359 , 13.93206243, 18.65143881]),
array([ -1.26500543, -2.19962588, 0.3533005 , -1.04280551, array([ -1.26500543, -2.19962588, 0.3533005 , -1.04280551,
1.05995624, 0.08076594, 0.40538612, -20.00642415, 1.05995624, 0.08076594, 0.40538612, -20.00642415,
-3.11398983, -6.22535906, 13.83245488, 18.64360584]), -3.11398983, -6.22535906, 13.83245488, 18.64360584]),
array([ -1.2643511 , -2.21959876, 0.35008584, -1.04907592, array([ -1.2643511 , -2.21959876, 0.35008584, -1.04907592,
1.07368962, 0.09940638, 0.65432327, -19.97288092, 1.07368962, 0.09940638, 0.65432327, -19.97288092,
-3.21466262, -6.27041147, 13.73338158, 18.64044195]), -3.21466262, -6.27041147, 13.73338158, 18.64044195]),
array([ -1.26345525, -2.23953556, 0.34677644, -1.05538806, array([ -1.26345525, -2.23953556, 0.34677644, -1.05538806,
1.0873246 , 0.11804803, 0.89585072, -19.93680205, 1.0873246 , 0.11804803, 0.89585072, -19.93680205,
-3.3094005 , -6.31213366, 13.63498368, 18.6416506 ]), -3.3094005 , -6.31213366, 13.63498368, 18.6416506 ]),
array([ -1.2623254 , -2.25943391, 0.34337847, -1.06173881, array([ -1.2623254 , -2.25943391, 0.34337847, -1.06173881,
1.100862 , 0.13669489, 1.12984965, -19.8983452 , 1.100862 , 0.13669489, 1.12984965, -19.8983452 ,
-3.39796566, -6.35074834, 13.53739967, 18.64685834]), -3.39796566, -6.35074834, 13.53739967, 18.64685834]),
array([ -1.26096916, -2.27929156, 0.33989828, -1.06812526, array([ -1.26096916, -2.27929156, 0.33989828, -1.06812526,
1.11430277, 0.15535052, 1.3562449 , -19.85765344, 1.11430277, 0.15535052, 1.3562449 , -19.85765344,
-3.48018701, -6.38645661, 13.44076412, 18.65563192]), -3.48018701, -6.38645661, 13.44076412, 18.65563192]),
array([ -1.25939415, -2.29910642, 0.33634232, -1.0745447 , array([ -1.25939415, -2.29910642, 0.33634232, -1.0745447 ,
1.12764797, 0.17401801, 1.57500838, -19.81485677, 1.12764797, 0.17401801, 1.57500838, -19.81485677,
-3.5559654 , -6.41943623, 13.3452067 , 18.66749508]), -3.5559654 , -6.41943623, 13.3452067 , 18.66749508]),
array([ -1.25760799, -2.31887649, 0.33271704, -1.08099454, array([ -1.25760799, -2.31887649, 0.33271704, -1.08099454,
1.14089883, 0.19269996, 1.78615991, -19.77007365, 1.14089883, 0.19269996, 1.78615991, -19.77007365,
-3.62527424, -6.44984163, 13.25085141, 18.68194461]), -3.62527424, -6.44984163, 13.25085141, 18.68194461]),
array([ -1.25561823, -2.33859991, 0.32902889, -1.08747235, array([ -1.25561823, -2.33859991, 0.32902889, -1.08747235,
1.15405664, 0.21139842, 1.98976583, -19.72341265, 1.15405664, 0.21139842, 1.98976583, -19.72341265,
-3.6881565 , -6.47780513, 13.1578159 , 18.698465 ]), -3.6881565 , -6.47780513, 13.1578159 , 18.698465 ]),
array([ -1.25343229, -2.35827488, 0.32528417, -1.09397579, array([ -1.25343229, -2.35827488, 0.32528417, -1.09397579,
1.16712285, 0.23011496, 2.18593611, -19.674974 , 1.16712285, 0.23011496, 2.18593611, -19.674974 ,
-3.74471902, -6.50343914, 13.06621108, 18.71654157]), -3.74471902, -6.50343914, 13.06621108, 18.71654157]),
array([ -1.25105747, -2.37789973, 0.32148904, -1.10050262, array([ -1.25105747, -2.37789973, 0.32148904, -1.10050262,
1.18009899, 0.24885064, 2.37482023, -19.62485108, 1.18009899, 0.24885064, 2.37482023, -19.62485108,
-3.79512507, -6.52683884, 12.97614085, 18.73567178]), -3.79512507, -6.52683884, 12.97614085, 18.73567178]),
array([ -1.24850087, -2.39747286, 0.31764946, -1.10705071, array([ -1.24850087, -2.39747286, 0.31764946, -1.10705071,
1.1929867 , 0.26760601, 2.55660244, -19.57313177, 1.1929867 , 0.26760601, 2.55660244, -19.57313177,
-3.83958583, -6.54808516, 12.88770189, 18.75537462]), -3.83958583, -6.54808516, 12.88770189, 18.75537462]),
array([ -1.24576937, -2.41699276, 0.31377111, -1.11361796, array([ -1.24576937, -2.41699276, 0.31377111, -1.11361796,
1.20578768, 0.28638121, 2.73149658, -19.51989969, 1.20578768, 0.28638121, 2.73149658, -19.51989969,
-3.87835145, -6.56724772, 12.80098371, 18.77519819]), -3.87835145, -6.56724772, 12.80098371, 18.77519819]),
array([ -1.24286963, -2.436458 , 0.3098594 , -1.12020234, array([ -1.24286963, -2.436458 , 0.3098594 , -1.12020234,
1.21850375, 0.30517593, 2.89974092, -19.46523526, 1.21850375, 0.30517593, 2.89974092, -19.46523526,
-3.91170226, -6.58438765, 12.71606873, 18.79472548]), -3.91170226, -6.58438765, 12.71606873, 18.79472548]),
array([ -1.23980804, -2.45586721, 0.30591946, -1.12680191, array([ -1.23980804, -2.45586721, 0.30591946, -1.12680191,
1.23113678, 0.32398951, 3.06159304, -19.40921658, 1.23113678, 0.32398951, 3.06159304, -19.40921658,
-3.93994035, -6.5995601 , 12.6330324 , 18.81357849]), -3.93994035, -6.5995601 , 12.6330324 , 18.81357849]),
array([ -1.23659071, -2.47521913, 0.30195608, -1.13341472, array([ -1.23659071, -2.47521913, 0.30195608, -1.13341472,
1.24368872, 0.34282093, 3.21732509, -19.35192021, 1.24368872, 0.34282093, 3.21732509, -19.35192021,
-3.96338187, -6.61281643, 12.5519435 , 18.83142087]), -3.96338187, -6.61281643, 12.5519435 , 18.83142087]),
array([ -1.23322349, -2.49451256, 0.29797373, -1.14003893, array([ -1.23322349, -2.49451256, 0.29797373, -1.14003893,
1.25616159, 0.36166889, 3.36721935, -19.29342174, 1.25616159, 0.36166889, 3.36721935, -19.29342174,
-3.98235019, -6.62420597, 12.47286442, 18.84795923]), -3.98235019, -6.62420597, 12.47286442, 18.84795923]),
array([ -1.22971193, -2.51374635, 0.29397656, -1.1466727 , array([ -1.22971193, -2.51374635, 0.29397656, -1.1466727 ,
1.26855744, 0.38053184, 3.5115643 , -19.23379624, 1.26855744, 0.38053184, 3.5115643 , -19.23379624,
-3.9971699 , -6.63377742, 12.39585149, 18.86294337]), -3.9971699 , -6.63377742, 12.39585149, 18.86294337]),
array([ -1.22606128, -2.53291947, 0.2899684 , -1.15331428, array([ -1.22606128, -2.53291947, 0.2899684 , -1.15331428,
1.2808784 , 0.399408 , 3.65065117, -19.1731186 , 1.2808784 , 0.399408 , 3.65065117, -19.1731186 ,
-4.00816184, -6.64157989, 12.32095538, 18.87616553]), -4.00816184, -6.64157989, 12.32095538, 18.87616553]),
array([ -1.22227651, -2.55203093, 0.28595276, -1.15996195, array([ -1.22227651, -2.55203093, 0.28595276, -1.15996195,
1.29312662, 0.41829546, 3.78477093, -19.11146372, 1.29312662, 0.41829546, 3.78477093, -19.11146372,
-4.01563895, -6.64766359, 12.24822142, 18.88745888]), -4.01563895, -6.64766359, 12.24822142, 18.88745888]),
array([ -1.21836229, -2.57107984, 0.28193286, -1.16661403, array([ -1.21836229, -2.57107984, 0.28193286, -1.16661403,
1.30530431, 0.43719216, 3.91421178, -19.04890664, 1.30530431, 0.43719216, 3.91421178, -19.04890664,
-4.01990294, -6.65208027, 12.17769006, 18.89669544]), -4.01990294, -6.65208027, 12.17769006, 18.89669544]),
array([ -1.21432304, -2.59006536, 0.27791162, -1.17326891, array([ -1.21432304, -2.59006536, 0.27791162, -1.17326891,
1.3174137 , 0.45609594, 4.03925703, -18.98552259, 1.3174137 , 0.45609594, 4.03925703, -18.98552259,
-4.02124183, -6.65488332, 12.10939719, 18.9037835 ]), -4.02124183, -6.65488332, 12.10939719, 18.9037835 ]),
array([ -1.21016285, -2.60898675, 0.27389169, -1.17992504, array([ -1.21016285, -2.60898675, 0.27389169, -1.17992504,
1.32945708, 0.4750046 , 4.16018341, -18.9213869 , 1.32945708, 0.4750046 , 4.16018341, -18.9213869 ,
-4.01992803, -6.65612782, 12.0433745 , 18.90866477]), -4.01992803, -6.65612782, 12.0433745 , 18.90866477]),
array([ -1.20588559, -2.62784333, 0.26987547, -1.18658091, array([ -1.20588559, -2.62784333, 0.26987547, -1.18658091,
1.34143673, 0.49391592, 4.27725975, -18.85657495, 1.34143673, 0.49391592, 4.27725975, -18.85657495,
-4.01621711, -6.65587029, 11.97964984, 18.91131125]), -4.01621711, -6.65587029, 11.97964984, 18.91131125]),
array([ -1.20149485, -2.64663449, 0.26586512, -1.19323508, array([ -1.20149485, -2.64663449, 0.26586512, -1.19323508,
1.35335498, 0.51282764, 4.39074595, -18.79116201, 1.35335498, 0.51282764, 4.39074595, -18.79116201,
-4.01034702, -6.65416841, 11.91824749, 18.91172209]), -4.01034702, -6.65416841, 11.91824749, 18.91172209]),
array([ -1.19699395, -2.66535971, 0.26186259, -1.19988616, array([ -1.19699395, -2.66535971, 0.26186259, -1.19988616,
1.36521416, 0.53173756, 4.50089224, -18.72522307, 1.36521416, 0.53173756, 4.50089224, -18.72522307,
-4.00253776, -6.65108065, 11.85918848, 18.90992031]), -4.00253776, -6.65108065, 11.85918848, 18.90992031]),
array([ -1.19238602, -2.68401854, 0.2578696 , -1.20653282, array([ -1.19238602, -2.68401854, 0.2578696 , -1.20653282,
1.37701666, 0.55064351, 4.6079387 , -18.65883264, 1.37701666, 0.55064351, 4.6079387 , -18.65883264,
-3.99299133, -6.64666583, 11.80249073, 18.90594966]), -3.99299133, -6.64666583, 11.80249073, 18.90594966]),
array([ -1.1876739 , -2.70261061, 0.2538877 , -1.21317381, array([ -1.1876739 , -2.70261061, 0.2538877 , -1.21317381,
1.38876482, 0.56954338, 4.71211493, -18.59206458, 1.38876482, 0.56954338, 4.71211493, -18.59206458,
-3.981892 , -6.6409827 , 11.74816933, 18.89987148]), -3.981892 , -6.6409827 , 11.74816933, 18.89987148]),
array([ -1.18286026, -2.7211356 , 0.2499183 , -1.2198079 , array([ -1.18286026, -2.7211356 , 0.2499183 , -1.2198079 ,
1.40046106, 0.58843514, 4.81363995, -18.52499181, 1.40046106, 0.58843514, 4.81363995, -18.52499181,
-3.96940678, -6.63408944, 11.69623664, 18.8917618 ]), -3.96940678, -6.63408944, 11.69623664, 18.8917618 ]),
array([ -1.17794754, -2.73959329, 0.24596261, -1.22643394, array([ -1.17794754, -2.73959329, 0.24596261, -1.22643394,
1.41210776, 0.60731685, 4.91272219, -18.45768616, 1.41210776, 0.60731685, 4.91272219, -18.45768616,
-3.95568604, -6.62604325, 11.64670241, 18.8817085 ]), -3.95568604, -6.62604325, 11.64670241, 18.8817085 ]),
array([ -1.17293798, -2.7579835 , 0.24202175, -1.23305084, array([ -1.17293798, -2.7579835 , 0.24202175, -1.23305084,
1.42370734, 0.62618666, 5.00955965, -18.39021811, 1.42370734, 0.62618666, 5.00955965, -18.39021811,
-3.94086424, -6.61689993, 11.59957387, 18.86980877]), -3.94086424, -6.61689993, 11.59957387, 18.86980877]),
array([ -1.16783364, -2.77630616, 0.23809669, -1.23965755, array([ -1.16783364, -2.77630616, 0.23809669, -1.23965755,
1.43526219, 0.64504283, 5.10434009, -18.32265663, 1.43526219, 0.64504283, 5.10434009, -18.32265663,
-3.92506073, -6.60671355, 11.55485574, 18.85616668]), -3.92506073, -6.60671355, 11.55485574, 18.85616668]),
array([ -1.1626364 , -2.79456123, 0.2341883 , -1.24625309, array([ -1.1626364 , -2.79456123, 0.2341883 , -1.24625309,
1.44677474, 0.66388372, 5.19724136, -18.25506895, 1.44677474, 0.66388372, 5.19724136, -18.25506895,
-3.90838059, -6.59553602, 11.5125503 , 18.84089104]), -3.90838059, -6.59553602, 11.5125503 , 18.84089104]),
array([ -1.15734797, -2.81274875, 0.23029739, -1.25283651, array([ -1.15734797, -2.81274875, 0.23029739, -1.25283651,
1.4582474 , 0.68270781, 5.28843167, -18.18752042, 1.4582474 , 0.68270781, 5.28843167, -18.18752042,
-3.89091552, -6.58341689, 11.47265732, 18.82409345]), -3.89091552, -6.58341689, 11.47265732, 18.82409345]),
array([ -1.1519699 , -2.83086882, 0.22642464, -1.25940691, array([ -1.1519699 , -2.83086882, 0.22642464, -1.25940691,
1.46968258, 0.7015137 , 5.37807002, -18.1200743 , 1.46968258, 0.7015137 , 5.37807002, -18.1200743 ,
-3.87274469, -6.57040307, 11.43517406, 18.80588657]), -3.87274469, -6.57040307, 11.43517406, 18.80588657]),
array([ -1.14650359, -2.84892162, 0.22257071, -1.26596345, array([ -1.14650359, -2.84892162, 0.22257071, -1.26596345,
1.48108267, 0.72030008, 5.46630662, -18.0527917 , 1.48108267, 0.72030008, 5.46630662, -18.0527917 ,
-3.85393559, -6.55653861, 11.40009521, 18.78638261]), -3.85393559, -6.55653861, 11.40009521, 18.78638261]),
array([ -1.14095031, -2.86690735, 0.21873616, -1.27250531, array([ -1.14095031, -2.86690735, 0.21873616, -1.27250531,
1.49245008, 0.73906577, 5.55328326, -17.98573138, 1.49245008, 0.73906577, 5.55328326, -17.98573138,
-3.83454486, -6.54186459, 11.36741283, 18.76569202]), -3.83454486, -6.54186459, 11.36741283, 18.76569202]),
array([ -1.13531117, -2.8848263 , 0.21492155, -1.27903173, array([ -1.13531117, -2.8848263 , 0.21492155, -1.27903173,
1.5037872 , 0.75780969, 5.63913374, -17.91894971, 1.5037872 , 0.75780969, 5.63913374, -17.91894971,
-3.81461906, -6.52641898, 11.33711629, 18.74392241]), -3.81461906, -6.52641898, 11.33711629, 18.74392241]),
array([ -1.12958719, -2.9026788 , 0.21112735, -1.28554197, array([ -1.12958719, -2.9026788 , 0.21112735, -1.28554197,
1.51509639, 0.77653087, 5.72398434, -17.85250058, 1.51509639, 0.77653087, 5.72398434, -17.85250058,
-3.79419544, -6.51023656, 11.3091922 , 18.7211776 ]), -3.79419544, -6.51023656, 11.3091922 , 18.7211776 ]),
array([ -1.12377923, -2.92046523, 0.20735405, -1.29203532, array([ -1.12377923, -2.92046523, 0.20735405, -1.29203532,
1.52638002, 0.79522843, 5.80795417, -17.78643535, 1.52638002, 0.79522843, 5.80795417, -17.78643535,
-3.77330263, -6.49334892, 11.28362432, 18.69755689]), -3.77330263, -6.49334892, 11.28362432, 18.69755689]),
array([ -1.11788808, -2.93818604, 0.20360209, -1.2985111 , array([ -1.11788808, -2.93818604, 0.20360209, -1.2985111 ,
1.53764041, 0.81390158, 5.89115562, -17.72080278, 1.53764041, 0.81390158, 5.89115562, -17.72080278,
-3.75196134, -6.47578441, 11.26039356, 18.67315448]), -3.75196134, -6.47578441, 11.26039356, 18.67315448]),
array([ -1.11191438, -2.95584169, 0.1998719 , -1.30496867, array([ -1.11191438, -2.95584169, 0.1998719 , -1.30496867,
1.54887989, 0.83254964, 5.97369474, -17.65564908, 1.54887989, 0.83254964, 5.97369474, -17.65564908,
-3.73018491, -6.45756819, 11.23947785, 18.64805907]), -3.73018491, -6.45756819, 11.23947785, 18.64805907]),
array([ -1.10585871, -2.9734327 , 0.19616392, -1.31140739, array([ -1.10585871, -2.9734327 , 0.19616392, -1.31140739,
1.56010074, 0.85117199, 6.05567159, -17.59101786, 1.56010074, 0.85117199, 6.05567159, -17.59101786,
-3.70797996, -6.43872226, 11.22085217, 18.62235351]), -3.70797996, -6.43872226, 11.22085217, 18.62235351]),
array([ -1.09972153, -2.99095965, 0.19247857, -1.31782666, array([ -1.09972153, -2.99095965, 0.19247857, -1.31782666,
1.57130523, 0.86976811, 6.13718062, -17.52695019, 1.57130523, 0.86976811, 6.13718062, -17.52695019,
-3.6853469 , -6.41926552, 11.2044885 , 18.59611466]), -3.6853469 , -6.41926552, 11.2044885 , 18.59611466]),
array([ -1.09350322, -3.00842314, 0.18881629, -1.32422587, array([ -1.09350322, -3.00842314, 0.18881629, -1.32422587,
1.58249558, 0.88833752, 6.21831098, -17.46348462, 1.58249558, 0.88833752, 6.21831098, -17.46348462,
-3.66228045, -6.39921388, 11.19035585, 18.56941335]), -3.66228045, -6.39921388, 11.19035585, 18.56941335]),
array([ -1.08720407, -3.0258238 , 0.18517752, -1.33060445, array([ -1.08720407, -3.0258238 , 0.18517752, -1.33060445,
1.593674 , 0.90687984, 6.29914682, -17.40065727, 1.593674 , 0.90687984, 6.29914682, -17.40065727,
-3.6387701 , -6.37858033, 11.17842023, 18.5423144 ]), -3.6387701 , -6.37858033, 11.17842023, 18.5423144 ]),
array([ -1.08082431, -3.0431623 , 0.18156272, -1.33696183, array([ -1.08082431, -3.0431623 , 0.18156272, -1.33696183,
1.60484265, 0.92539471, 6.37976763, -17.33850185, 1.60484265, 0.92539471, 6.37976763, -17.33850185,
-3.61480056, -6.35737503, 11.16864477, 18.51487679]), -3.61480056, -6.35737503, 11.16864477, 18.51487679]),
array([ -1.07436406, -3.06043935, 0.17797237, -1.34329743, array([ -1.07436406, -3.06043935, 0.17797237, -1.34329743,
1.61600364, 0.94388187, 6.46024845, -17.27704981, 1.61600364, 0.94388187, 6.46024845, -17.27704981,
-3.59035221, -6.33560544, 11.1609897 , 18.48715385]), -3.59035221, -6.33560544, 11.1609897 , 18.48715385]),
array([ -1.0678234 , -3.07765568, 0.17440697, -1.34961071, array([ -1.0678234 , -3.07765568, 0.17440697, -1.34961071,
1.62715905, 0.96234106, 6.54066014, -17.21633042, 1.62715905, 0.96234106, 6.54066014, -17.21633042,
-3.56540147, -6.31327642, 11.15541256, 18.45919359]), -3.56540147, -6.31327642, 11.15541256, 18.45919359]),
array([ -1.06120233, -3.09481205, 0.17086705, -1.3559011 , array([ -1.06120233, -3.09481205, 0.17086705, -1.3559011 ,
1.63831092, 0.9807721 , 6.62106961, -17.15637088, 1.63831092, 0.9807721 , 6.62106961, -17.15637088,
-3.5399212 , -6.29039036, 11.15186821, 18.43103903]), -3.5399212 , -6.29039036, 11.15186821, 18.43103903]),
array([ -1.05450079, -3.11190924, 0.16735317, -1.36216805, array([ -1.05450079, -3.11190924, 0.16735317, -1.36216805,
1.64946123, 0.99917483, 6.70154 , -17.09719645, 1.64946123, 0.99917483, 6.70154 , -17.09719645,
-3.51388106, -6.26694726, 11.15030906, 18.40272869]), -3.51388106, -6.26694726, 11.15030906, 18.40272869]),
array([ -1.04771866, -3.12894808, 0.16386592, -1.36841099, array([ -1.04771866, -3.12894808, 0.16386592, -1.36841099,
1.66061191, 1.01754913, 6.78213092, -17.03883061, 1.66061191, 1.01754913, 6.78213092, -17.03883061,
-3.48724788, -6.24294485, 11.15068521, 18.37429703]), -3.48724788, -6.24294485, 11.15068521, 18.37429703]),
array([ -1.04085576, -3.14592937, 0.16040593, -1.37462937, array([ -1.04085576, -3.14592937, 0.16040593, -1.37462937,
1.67176486, 1.0358949 , 6.86289857, -16.98129521, 1.67176486, 1.0358949 , 6.86289857, -16.98129521,
-3.45998602, -6.21837871, 11.15294467, 18.34577503]), -3.45998602, -6.21837871, 11.15294467, 18.34577503]),
array([ -1.03391186, -3.16285398, 0.15697388, -1.38082261, array([ -1.03391186, -3.16285398, 0.15697388, -1.38082261,
1.68292189, 1.05421209, 6.94389588, -16.92461062, 1.68292189, 1.05421209, 6.94389588, -16.92461062,
-3.43205769, -6.19324235, 11.1570336 , 18.31719076]), -3.43205769, -6.19324235, 11.1570336 , 18.31719076]),
array([ -1.02688669, -3.17972278, 0.15357045, -1.38699014, array([ -1.02688669, -3.17972278, 0.15357045, -1.38699014,
1.69408479, 1.07250066, 7.02517272, -16.86879592, 1.69408479, 1.07250066, 7.02517272, -16.86879592,
-3.40342332, -6.16752728, 11.16289653, 18.2885701 ]), -3.40342332, -6.16752728, 11.16289653, 18.2885701 ]),
array([ -1.01977991, -3.19653665, 0.15019641, -1.39313136, array([ -1.01977991, -3.19653665, 0.15019641, -1.39313136,
1.70525526, 1.0907606 , 7.10677596, -16.8138691 , 1.70525526, 1.0907606 , 7.10677596, -16.8138691 ,
-3.37404187, -6.14122316, 11.17047667, 18.25993737]), -3.37404187, -6.14122316, 11.17047667, 18.25993737]),
array([ -1.01259116, -3.21329649, 0.14685254, -1.39924568, array([ -1.01259116, -3.21329649, 0.14685254, -1.39924568,
1.71643498, 1.10899192, 7.18874958, -16.75984723, 1.71643498, 1.10899192, 7.18874958, -16.75984723,
-3.34387118, -6.11431781, 11.17971622, 18.23131618]), -3.34387118, -6.11431781, 11.17971622, 18.23131618]),
array([ -1.00532003, -3.23000324, 0.14353967, -1.40533248, array([ -1.00532003, -3.23000324, 0.14353967, -1.40533248,
1.72762554, 1.12719465, 7.27113481, -16.70674672, 1.72762554, 1.12719465, 7.27113481, -16.70674672,
-3.31286833, -6.08679731, 11.19055668, 18.2027302 ]), -3.31286833, -6.08679731, 11.19055668, 18.2027302 ]),
array([ -0.99796606, -3.24665782, 0.14025868, -1.41139112, array([ -0.99796606, -3.24665782, 0.14025868, -1.41139112,
1.73882848, 1.14536885, 7.35397018, -16.6545835 , 1.73882848, 1.14536885, 7.35397018, -16.6545835 ,
-3.28098991, -6.05864606, 11.20293923, 18.17420408]), -3.28098991, -6.05864606, 11.20293923, 18.17420408]),
array([ -0.99052877, -3.2632612 , 0.13701049, -1.41742097, array([ -0.99052877, -3.2632612 , 0.13701049, -1.41742097,
1.75004528, 1.16351461, 7.43729159, -16.6033733 , 1.75004528, 1.16351461, 7.43729159, -16.6033733 ,
-3.24819243, -6.02984688, 11.21680509, 18.14576441]), -3.24819243, -6.02984688, 11.21680509, 18.14576441]),
array([ -0.98300764, -3.27981433, 0.13379606, -1.42342135, array([ -0.98300764, -3.27981433, 0.13379606, -1.42342135,
1.76127738, 1.18163206, 7.52113242, -16.55313187, 1.76127738, 1.18163206, 7.52113242, -16.55313187,
-3.21443259, -6.00038103, 11.23209592, 18.11744073]), -3.21443259, -6.00038103, 11.23209592, 18.11744073]),
array([ -0.97540211, -3.2963182 , 0.13061639, -1.42939158, array([ -0.97540211, -3.2963182 , 0.13061639, -1.42939158,
1.77252613, 1.19972132, 7.60552354, -16.50387529, 1.77252613, 1.19972132, 7.60552354, -16.50387529,
-3.17966763, -5.97022829, 11.24875428, 18.08926667]), -3.17966763, -5.97022829, 11.24875428, 18.08926667]),
array([ -0.96771162, -3.31277382, 0.12747253, -1.43533095, array([ -0.96771162, -3.31277382, 0.12747253, -1.43533095,
1.78379286, 1.2177826 , 7.69049341, -16.45562022, 1.78379286, 1.2177826 , 7.69049341, -16.45562022,
-3.14385564, -5.93936709, 11.26672403, 18.06128114]), -3.14385564, -5.93936709, 11.26672403, 18.06128114]),
array([ -0.95993555, -3.32918221, 0.12436558, -1.44123872, array([ -0.95993555, -3.32918221, 0.12436558, -1.44123872,
1.79507881, 1.23581613, 7.77606807, -16.40838423, 1.79507881, 1.23581613, 7.77606807, -16.40838423,
-3.10695584, -5.90777456, 11.28595087, 18.03352962]), -3.10695584, -5.90777456, 11.28595087, 18.03352962]),
array([ -0.95207328, -3.34554439, 0.12129665, -1.44711415, array([ -0.95207328, -3.34554439, 0.12129665, -1.44711415,
1.80638519, 1.2538222 , 7.86227126, -16.36218613, 1.80638519, 1.2538222 , 7.86227126, -16.36218613,
-3.06892885, -5.87542671, 11.30638281, 18.00606558]), -3.06892885, -5.87542671, 11.30638281, 18.00606558]),
array([ -0.94412415, -3.36186144, 0.11826691, -1.45295645, array([ -0.94412415, -3.36186144, 0.11826691, -1.45295645,
1.81771316, 1.27180115, 7.94912436, -16.31704629, 1.81771316, 1.27180115, 7.94912436, -16.31704629,
-3.02973695, -5.84229863, 11.3279708 , 17.97895201]), -3.02973695, -5.84229863, 11.3279708 , 17.97895201]),
array([ -0.93608751, -3.37813443, 0.11527757, -1.45876481, array([ -0.93608751, -3.37813443, 0.11527757, -1.45876481,
1.82906383, 1.28975341, 8.03664652, -16.27298705, 1.82906383, 1.28975341, 8.03664652, -16.27298705,
-2.98934424, -5.80836474, 11.35066929, 17.95226302]), -2.98934424, -5.80836474, 11.35066929, 17.95226302]),
array([ -0.92796265, -3.39436446, 0.11232985, -1.46453841, array([ -0.92796265, -3.39436446, 0.11232985, -1.46453841,
1.84043827, 1.3076795 , 8.12485463, -16.23003307, 1.84043827, 1.3076795 , 8.12485463, -16.23003307,
-2.94771675, -5.7735992 , 11.37443694, 17.9260857 ]), -2.94771675, -5.7735992 , 11.37443694, 17.9260857 ]),
array([ -0.91974889, -3.41055267, 0.10942503, -1.47027639, array([ -0.91974889, -3.41055267, 0.10942503, -1.47027639,
1.8518375 , 1.32558002, 8.21376336, -16.18821182, 1.8518375 , 1.32558002, 8.21376336, -16.18821182,
-2.90482249, -5.73797646, 11.39923741, 17.90052201]), -2.90482249, -5.73797646, 11.39923741, 17.90052201]),
array([ -0.91144551, -3.42670023, 0.1065644 , -1.47597786, array([ -0.91144551, -3.42670023, 0.1065644 , -1.47597786,
1.86326254, 1.34345571, 8.30338521, -16.14755395, 1.86326254, 1.34345571, 8.30338521, -16.14755395,
-2.86063128, -5.70147199, 11.42504029, 17.8756909 ]), -2.86063128, -5.70147199, 11.42504029, 17.8756909 ]),
array([ -0.90305177, -3.44280832, 0.10374928, -1.48164192, array([ -0.90305177, -3.44280832, 0.10374928, -1.48164192,
1.87471437, 1.36130744, 8.39373051, -16.10809382, 1.87471437, 1.36130744, 8.39373051, -16.10809382,
-2.8151145 , -5.66406342, 11.45182213, 17.85173058]), -2.8151145 , -5.66406342, 11.45182213, 17.85173058]),
array([ -0.89456697, -3.45887819, 0.10098104, -1.48726766, array([ -0.89456697, -3.45887819, 0.10098104, -1.48726766,
1.88619393, 1.37913624, 8.48480745, -16.06987003, 1.88619393, 1.37913624, 8.48480745, -16.06987003,
-2.76824449, -5.62573198, 11.47956782, 17.82880102]), -2.76824449, -5.62573198, 11.47956782, 17.82880102]),
array([ -0.88599034, -3.47491112, 0.09826104, -1.49285412, array([ -0.88599034, -3.47491112, 0.09826104, -1.49285412,
1.89770221, 1.39694333, 8.57662212, -16.03292592, 1.89770221, 1.39694333, 8.57662212, -16.03292592,
-2.7199937 , -5.58646462, 11.50827215, 17.80708664]), -2.7199937 , -5.58646462, 11.50827215, 17.80708664]),
array([ -0.87732117, -3.49090843, 0.09559071, -1.49840038, array([ -0.87732117, -3.49090843, 0.09559071, -1.49840038,
1.90924015, 1.41473013, 8.6691785 , -15.9973102 , 1.90924015, 1.41473013, 8.6691785 , -15.9973102 ,
-2.67033329, -5.54625688, 11.53794192, 17.7867992 ]), -2.67033329, -5.54625688, 11.53794192, 17.7867992 ]),
array([ -0.86855869, -3.5068715 , 0.09297148, -1.50390549, array([ -0.86855869, -3.5068715 , 0.09297148, -1.50390549,
1.92080875, 1.43249831, 8.76247853, -15.96307757, 1.92080875, 1.43249831, 8.76247853, -15.96307757,
-2.61923116, -5.5051169 , 11.56859856, 17.76818098]), -2.61923116, -5.5051169 , 11.56859856, 17.76818098]),
array([ -0.85970217, -3.52280179, 0.09040483, -1.50936856, array([ -0.85970217, -3.52280179, 0.09040483, -1.50936856,
1.93240903, 1.45024982, 8.85652211, -15.93028941, 1.93240903, 1.45024982, 8.85652211, -15.93028941,
-2.56664909, -5.46307088, 11.6002816 , 17.75150821]), -2.56664909, -5.46307088, 11.6002816 , 17.75150821]),
array([ -0.85075086, -3.53870081, 0.08789229, -1.51478874, array([ -0.85075086, -3.53870081, 0.08789229, -1.51478874,
1.94404208, 1.46798691, 8.95130716, -15.89901454, 1.94404208, 1.46798691, 8.95130716, -15.89901454,
-2.51253873, -5.42017068, 11.63305319, 17.73709481]), -2.51253873, -5.42017068, 11.63305319, 17.73709481]),
array([ -0.84170403, -3.55457014, 0.08543546, -1.52016524, array([ -0.84170403, -3.55457014, 0.08543546, -1.52016524,
1.95570909, 1.48571221, 9.04682971, -15.86933005, 1.95570909, 1.48571221, 9.04682971, -15.86933005,
-2.45683595, -5.3765041 , 11.66700415, 17.72529648]), -2.45683595, -5.3765041 , 11.66700415, 17.72529648]),
array([ -0.83256094, -3.57041146, 0.083036 , -1.52549745, array([ -0.83256094, -3.57041146, 0.083036 , -1.52549745,
1.96741135, 1.50342872, 9.14308404, -15.84132222, 1.96741135, 1.50342872, 9.14308404, -15.84132222,
-2.39945305, -5.3322091 , 11.70226202, 17.71651514]), -2.39945305, -5.3322091 , 11.70226202, 17.71651514]),
array([ -0.82332088, -3.58622655, 0.08069573, -1.53078494, array([ -0.82332088, -3.58622655, 0.08069573, -1.53078494,
1.97915035, 1.52113993, 9.24006289, -15.81508767, 1.97915035, 1.52113993, 9.24006289, -15.81508767,
-2.34026801, -5.28749312, 11.73900192, 17.71120395]), -2.34026801, -5.28749312, 11.73900192, 17.71120395]),
array([ -0.81398312, -3.60201728, 0.07841662, -1.5360276 , array([ -0.81398312, -3.60201728, 0.07841662, -1.5360276 ,
1.99092781, 1.5388498 , 9.33775791, -15.79073465, 1.99092781, 1.5388498 , 9.33775791, -15.79073465,
-2.27910963, -5.24265947, 11.77746107, 17.7098728 ]), -2.27910963, -5.24265947, 11.77746107, 17.7098728 ]),
array([ -0.80454696, -3.61778567, 0.07620089, -1.54122574, array([ -0.80454696, -3.61778567, 0.07620089, -1.54122574,
2.00274577, 1.5565629 , 9.43616034, -15.76838471, 2.00274577, 1.5565629 , 9.43616034, -15.76838471,
-2.21573713, -5.19814334, 11.81795841, 17.71309463]), -2.21573713, -5.19814334, 11.81795841, 17.71309463]),
array([ -0.7950117 , -3.63353384, 0.07405108, -1.5463803 , array([ -0.7950117 , -3.63353384, 0.07405108, -1.5463803 ,
2.01460669, 1.57428441, 9.53526215, -15.74817491, 2.01460669, 1.57428441, 9.53526215, -15.74817491,
-2.14981217, -5.15456068, 11.86092106, 17.72151277]), -2.14981217, -5.15456068, 11.86092106, 17.72151277]),
array([ -0.78537664, -3.6492641 , 0.07197021, -1.55149308, array([ -0.78537664, -3.6492641 , 0.07197021, -1.55149308,
2.02651361, 1.59202026, 9.63505797, -15.73026065, 2.02651361, 1.59202026, 9.63505797, -15.73026065,
-2.08086044, -5.11277477, 11.90692001, 17.73584957]), -2.08086044, -5.11277477, 11.90692001, 17.73584957]),
array([ -0.7756411 , -3.66497892, 0.069962 , -1.55656707, array([ -0.7756411 , -3.66497892, 0.069962 , -1.55656707,
2.03847033, 1.60977718, 9.73554816, -15.71481977, 2.03847033, 1.60977718, 9.73554816, -15.71481977,
-2.00821903, -5.07398638, 11.95671807, 17.75691702]), -2.00821903, -5.07398638, 11.95671807, 17.75691702]),
array([ -0.76580435, -3.68068098, 0.06803103, -1.56160692, array([ -0.76580435, -3.68068098, 0.06803103, -1.56160692,
2.05048166, 1.62756281, 9.83674367, -15.70205807, 2.05048166, 1.62756281, 9.83674367, -15.70205807,
-1.93096444, -5.03985592, 12.01133467, 17.78562993]), -1.93096444, -5.03985592, 12.01133467, 17.78562993]),
array([ -0.75586568, -3.6963732 , 0.06618322, -1.56661959, array([ -0.75586568, -3.6963732 , 0.06618322, -1.56661959,
2.0625538 , 1.64538583, 9.93867362, -15.69221705, 2.0625538 , 1.64538583, 9.93867362, -15.69221705,
-1.84781445, -5.01266849, 12.07213285, 17.82302266]), -1.84781445, -5.01266849, 12.07213285, 17.82302266]),
array([ -0.74582428, -3.71205878, 0.06442622, -1.57161515, array([ -0.74582428, -3.71205878, 0.06442622, -1.57161515,
2.07469473, 1.6632561 , 10.04139669, -15.68558442, 2.07469473, 1.6632561 , 10.04139669, -15.68558442,
-1.75699514, -4.99555599, 12.14093657, 17.87027064]), -1.75699514, -4.99555599, 12.14093657, 17.87027064]),
array([ -0.73567926, -3.72774129, 0.06277016, -1.57660794, array([ -0.73567926, -3.72774129, 0.06277016, -1.57660794,
2.08691492, 1.68118482, 10.14501794, -15.68250784, 2.08691492, 1.68118482, 10.14501794, -15.68250784,
-1.65606265, -4.99279451, 12.22018868, 17.928718 ]), -1.65606265, -4.99279451, 12.22018868, 17.928718 ]),
array([ -0.72542955, -3.7434247 , 0.06122849, -1.58161814, array([ -0.72542955, -3.7434247 , 0.06122849, -1.58161814,
2.09922809, 1.69918473, 10.24971283, -15.68341159, 2.09922809, 1.69918473, 10.24971283, -15.68341159,
-1.54166879, -5.01019887, 12.31316445, 17.99991234]), -1.54166879, -5.01019887, 12.31316445, 17.99991234]),
array([ -0.71507379, -3.75911352, 0.05981923, -1.58667378, array([ -0.71507379, -3.75911352, 0.05981923, -1.58667378,
2.11165235, 1.71727038, 10.35576069, -15.68881446, 2.11165235, 1.71727038, 10.35576069, -15.68881446,
-1.40926265, -5.05563633, 12.42425945, 18.08564747]), -1.40926265, -5.05563633, 12.42425945, 18.08564747]),
array([ -0.7046102 , -3.77481286, 0.0585665 , -1.59181345, array([ -0.7046102 , -3.77481286, 0.0585665 , -1.59181345,
2.12421172, 1.73545839, 10.46359109, -15.69934335, 2.12421172, 1.73545839, 10.46359109, -15.69934335,
-1.25273017, -5.1396722 , 12.55937331, 18.18801368]), -1.25273017, -5.1396722 , 12.55937331, 18.18801368]),
array([ -0.69403635, -3.79052859, 0.0575025 , -1.59708977, array([ -0.69403635, -3.79052859, 0.0575025 , -1.59708977,
2.13693812, 1.75376785, 10.57385272, -15.71573049, 2.13693812, 1.75376785, 10.57385272, -15.71573049,
-1.06399374, -5.27632381, 12.72640075, 18.30945497]), -1.06399374, -5.27632381, 12.72640075, 18.30945497]),
array([ -0.6833488 , -3.80626735, 0.0566699 , -1.60257361, array([ -0.6833488 , -3.80626735, 0.0566699 , -1.60257361,
2.14987393, 1.77222068, 10.6875413 , -15.73876472, 2.14987393, 1.77222068, 10.6875413 , -15.73876472,
-0.83260015, -5.48383705, 12.93581111, 18.4528369 ]), -0.83260015, -5.48383705, 12.93581111, 18.4528369 ]),
array([ -0.67254248, -3.82203647, 0.0561248 , -1.60835918, array([ -0.67254248, -3.82203647, 0.0561248 , -1.60835918,
2.1630753 , 1.79084223, 10.80632893, -15.76911665, 2.1630753 , 1.79084223, 10.80632893, -15.76911665,
-0.54510808, -5.78557097, 13.20136469, 18.62154833]), -0.54510808, -5.78557097, 13.20136469, 18.62154833]),
array([ -0.66160891, -3.8378433 , 0.05594214, -1.61457256, array([ -0.66160891, -3.8378433 , 0.05594214, -1.61457256,
2.17661774, 1.80966195, 10.933567 , -15.80682908, 2.17661774, 1.80966195, 10.933567 , -15.80682908,
-0.18265352, -6.21337902, 13.5424454 , 18.81972159]), -0.18265352, -6.21337902, 13.5424454 , 18.81972159]),
array([ -0.65053258, -3.85369364, 0.05622943, -1.62139983, array([ -0.65053258, -3.85369364, 0.05622943, -1.62139983,
2.1906196 , 1.82871416, 11.07632757, -15.8503412 , 2.1906196 , 1.82871416, 11.07632757, -15.8503412 ,
0.28729204, -6.82727353, 14.00185471, 19.05221265])], 0.28729204, -6.82727353, 14.00185471, 19.05221265])],
[array([ -52.33562191, -66.65932781, -26.90708972, -54.25815874, [array([ -52.33562191, -66.65932781, -26.90708972, -54.25815874,
-83.01253149, -142.47197924]), -83.01253149, -142.47197924]),
array([ -49.86179662, -65.06231854, -27.64420269, -51.10486444, array([ -49.86179662, -65.06231854, -27.64420269, -51.10486444,
-71.45190134, -118.53929599]), -71.45190134, -118.53929599]),
array([-47.64325056, -63.10105583, -28.06060798, -47.70654668, array([-47.64325056, -63.10105583, -28.06060798, -47.70654668,
-61.31702629, -97.58708553]), -61.31702629, -97.58708553]),
array([-45.56654598, -60.85340585, -28.16723897, -44.19986009, array([-45.56654598, -60.85340585, -28.16723897, -44.19986009,
-52.41615179, -79.28037558]), -52.41615179, -79.28037558]),
array([-43.5533942 , -58.38464846, -27.98535504, -40.68187455, array([-43.5533942 , -58.38464846, -27.98535504, -40.68187455,
-44.5910181 , -63.32305895]), -44.5910181 , -63.32305895]),
array([-41.55253999, -55.74874417, -27.54244134, -37.22064912, array([-41.55253999, -55.74874417, -27.54244134, -37.22064912,
-37.70931187, -49.4521516 ]), -37.70931187, -49.4521516 ]),
array([-39.53326917, -52.98995659, -26.8694662 , -33.86302897, array([-39.53326917, -52.98995659, -26.8694662 , -33.86302897,
-31.65893967, -37.43323756]), -31.65893967, -37.43323756]),
array([-37.48021354, -50.14452614, -25.99898374, -30.64038825, array([-37.48021354, -50.14452614, -25.99898374, -30.64038825,
-26.34370869, -27.05682698]), -26.34370869, -27.05682698]),
array([-35.38919921, -47.24222532, -24.96377625, -27.57285112, array([-35.38919921, -47.24222532, -24.96377625, -27.57285112,
-21.68008726, -18.13540619]), -21.68008726, -18.13540619]),
array([-33.26394021, -44.3077121 , -23.79585628, -24.67238537, array([-33.26394021, -44.3077121 , -23.79585628, -24.67238537,
-17.59478591, -10.50100696]), -17.59478591, -10.50100696]),
array([-31.11342238, -41.36165172, -22.52572398, -21.94506203, array([-31.11342238, -41.36165172, -22.52572398, -21.94506203,
-14.02295518, -4.00316399]), -14.02295518, -4.00316399]),
array([-28.94985488, -38.42160913, -21.18181895, -19.39270023, array([-28.94985488, -38.42160913, -21.18181895, -19.39270023,
-10.90684046, 1.49283681]), -10.90684046, 1.49283681]),
array([-26.78709075, -35.50273314, -19.79013033, -17.0140609 , array([-26.78709075, -35.50273314, -19.79013033, -17.0140609 ,
-8.19477088, 6.10748969]), -8.19477088, 6.10748969]),
array([-24.6394361 , -32.61826193, -18.37394185, -14.80571151, array([-24.6394361 , -32.61826193, -18.37394185, -14.80571151,
-5.84038873, 9.94843066]), -5.84038873, 9.94843066]),
array([-22.52078023, -29.77988263, -16.95369419, -12.76265275, array([-22.52078023, -29.77988263, -16.95369419, -12.76265275,
-3.80204939, 13.11166458]), -3.80204939, 13.11166458]),
array([-20.44398951, -26.9979774 , -15.54694908, -10.87877448, array([-20.44398951, -26.9979774 , -15.54694908, -10.87877448,
-2.04234062, 15.68268195]), -2.04234062, 15.68268195]),
array([-18.4205151 , -24.28178479, -14.16844005, -9.14719019, array([-18.4205151 , -24.28178479, -14.16844005, -9.14719019,
-0.52768431, 17.73748202]), -0.52768431, 17.73748202]),
array([-16.46017149, -21.63950173, -12.83019387, -7.56048578, array([-16.46017149, -21.63950173, -12.83019387, -7.56048578,
0.77200481, 19.3435133 ]), 0.77200481, 19.3435133 ]),
array([-14.57104783, -19.0783465 , -11.54170724, -6.11090824, array([-14.57104783, -19.0783465 , -11.54170724, -6.11090824,
1.88362105, 20.5605387 ]), 1.88362105, 20.5605387 ]),
array([-12.75951961, -16.60459861, -10.31016309, -4.7905123 , array([-12.75951961, -16.60459861, -10.31016309, -4.7905123 ,
2.8311416 , 21.4414305 ]), 2.8311416 , 21.4414305 ]),
array([-11.03033258, -14.22362748, -9.14067205, -3.59127709, array([-11.03033258, -14.22362748, -9.14067205, -3.59127709,
3.63587957, 22.03289885]), 3.63587957, 22.03289885]),
array([ -9.38673544, -11.93991811, -8.03652625, -2.50520137, array([ -9.38673544, -11.93991811, -8.03652625, -2.50520137,
4.31672034, 22.37615666]), 4.31672034, 22.37615666]),
array([-7.83064227, -9.75709893, -6.99945418, -1.52438245, 4.89034364, array([-7.83064227, -9.75709893, -6.99945418, -1.52438245, 4.89034364,
22.50752391]), 22.50752391]),
array([-6.3628091 , -7.67797481, -6.02986803, -0.64108225, 5.37143238, array([-6.3628091 , -7.67797481, -6.02986803, -0.64108225, 5.37143238,
22.45897404]), 22.45897404]),
array([-4.98301325, -5.70456636, -5.12709645, 0.15221735, 5.77286871, array([-4.98301325, -5.70456636, -5.12709645, 0.15221735, 5.77286871,
22.25862563]), 22.25862563]),
array([-3.69022646, -3.83815544, -4.28959828, 0.86276875, 6.10591744, array([-3.69022646, -3.83815544, -4.28959828, 0.86276875, 6.10591744,
21.93118274]), 21.93118274]),
array([-2.48277623, -2.07933617, -3.5151544 , 1.49752152, 6.38039668, array([-2.48277623, -2.07933617, -3.5151544 , 1.49752152, 6.38039668,
21.49832753]), 21.49832753]),
array([-1.35849143, -0.42807007, -2.8010364 , 2.06309341, 6.60483582, array([-1.35849143, -0.42807007, -2.8010364 , 2.06309341, 6.60483582,
20.97906899]), 20.97906899]),
array([-0.31483034, 1.11625604, -2.14415207, 2.56574884, 6.78662097, array([-0.31483034, 1.11625604, -2.14415207, 2.56574884, 6.78662097,
20.39005174]), 20.39005174]),
array([ 0.65100957, 2.55477087, -1.54116861, 3.01138451, 6.93212802, array([ 0.65100957, 2.55477087, -1.54116861, 3.01138451, 6.93212802,
19.74582872]), 19.74582872]),
array([ 1.54199953, 3.88905959, -0.98861517, 3.4055213 , 7.04684374, array([ 1.54199953, 3.88905959, -0.98861517, 3.4055213 , 7.04684374,
19.05910174]), 19.05910174]),
array([ 2.36120424, 5.12110591, -0.48296658, 3.75330205, 7.13547542, array([ 2.36120424, 5.12110591, -0.48296658, 3.75330205, 7.13547542,
18.34093334]), 18.34093334]),
array([ 3.11172176, 6.25323631, -0.02071061, 4.05949428, 7.20204958, array([ 3.11172176, 6.25323631, -0.02071061, 4.05949428, 7.20204958,
17.60093346]), 17.60093346]),
array([ 3.79663696, 7.28806726, 0.40159934, 4.32849729, 7.25000052, array([ 3.79663696, 7.28806726, 0.40159934, 4.32849729, 7.25000052,
16.84742402]), 16.84742402]),
array([ 4.4189866 , 8.22845579, 0.78730369, 4.5643528 , 7.28224917, array([ 4.4189866 , 8.22845579, 0.78730369, 4.5643528 , 7.28224917,
16.08758417]), 16.08758417]),
array([ 4.98173437, 9.07745379, 1.13960644, 4.77075851, 7.30127324, array([ 4.98173437, 9.07745379, 1.13960644, 4.77075851, 7.30127324,
15.32757869]), 15.32757869]),
array([ 5.48775411, 9.83826632, 1.4615535 , 4.95108379, 7.30916915, array([ 5.48775411, 9.83826632, 1.4615535 , 4.95108379, 7.30916915,
14.57267175]), 14.57267175]),
array([ 5.93981979, 10.51421394, 1.75601782, 5.1083869 , 7.30770656, array([ 5.93981979, 10.51421394, 1.75601782, 5.1083869 , 7.30770656,
13.82732793]), 13.82732793]),
array([ 6.34060067, 11.10869891, 2.02569021, 5.24543335, 7.29837613, array([ 6.34060067, 11.10869891, 2.02569021, 5.24543335, 7.29837613,
13.09530212]), 13.09530212]),
array([ 6.69266075, 11.62517528, 2.27307448, 5.36471461, 7.28243126, array([ 6.69266075, 11.62517528, 2.27307448, 5.36471461, 7.28243126,
12.37971969]), 12.37971969]),
array([ 6.99846117, 12.06712268, 2.50048601, 5.46846703, 7.26092422, array([ 6.99846117, 12.06712268, 2.50048601, 5.46846703, 7.26092422,
11.68314815]), 11.68314815]),
array([ 7.26036495, 12.43802341, 2.71005309, 5.55869048, 7.23473748, array([ 7.26036495, 12.43802341, 2.71005309, 5.55869048, 7.23473748,
11.00766133]), 11.00766133]),
array([ 7.48064319, 12.74134284, 2.90372017, 5.63716654, 7.2046106 , array([ 7.48064319, 12.74134284, 2.90372017, 5.63716654, 7.2046106 ,
10.35489687]), 10.35489687]),
array([ 7.66148224, 12.98051268, 3.08325269, 5.70547593, 7.17116326, array([ 7.66148224, 12.98051268, 3.08325269, 5.70547593, 7.17116326,
9.72610785]), 9.72610785]),
array([ 7.80499133, 13.15891688, 3.25024301, 5.76501508, 7.13491483, array([ 7.80499133, 13.15891688, 3.25024301, 5.76501508, 7.13491483,
9.12220918]), 9.12220918]),
array([ 7.91321031, 13.27988003, 3.40611719, 5.81701182, 7.09630093, array([ 7.91321031, 13.27988003, 3.40611719, 5.81701182, 7.09630093,
8.54381922]), 8.54381922]),
array([ 7.98811719, 13.34665779, 3.5521423 , 5.86253999, 7.05568739, array([ 7.98811719, 13.34665779, 3.5521423 , 5.86253999, 7.05568739,
7.99129718]), 7.99129718]),
array([ 8.03163528, 13.36242931, 3.68943415, 5.90253304, 7.01338186, array([ 8.03163528, 13.36242931, 3.68943415, 5.90253304, 7.01338186,
7.46477671]), 7.46477671]),
array([ 8.04563976, 13.33029133, 3.81896535, 5.93779668, 6.96964341, array([ 8.04563976, 13.33029133, 3.81896535, 5.93779668, 6.96964341,
6.96419602]), 6.96419602]),
array([ 8.03196357, 13.25325369, 3.94157341, 5.96902045, 6.92469051, array([ 8.03196357, 13.25325369, 3.94157341, 5.96902045, 6.92469051,
6.48932488]), 6.48932488]),
array([ 7.9924025 , 13.13423616, 4.0579691 , 5.99678842, 6.87870749, array([ 7.9924025 , 13.13423616, 4.0579691 , 5.99678842, 6.87870749,
6.03978875]), 6.03978875]),
array([ 7.92871958, 12.97606636, 4.16874473, 6.02158903, 6.83184975, array([ 7.92871958, 12.97606636, 4.16874473, 6.02158903, 6.83184975,
5.61509041]), 5.61509041]),
array([ 7.84264851, 12.78147854, 4.27438249, 6.04382405, 6.78424799, array([ 7.84264851, 12.78147854, 4.27438249, 6.04382405, 6.78424799,
5.21462918]), 5.21462918]),
array([ 7.73589637, 12.55311324, 4.37526282, 6.0638169 , 6.73601154, array([ 7.73589637, 12.55311324, 4.37526282, 6.0638169 , 6.73601154,
4.83771816]), 4.83771816]),
array([ 7.61014546, 12.29351747, 4.47167264, 6.08182024, 6.68723103, array([ 7.61014546, 12.29351747, 4.47167264, 6.08182024, 6.68723103,
4.4835994 ]), 4.4835994 ]),
array([ 7.46705445, 12.00514545, 4.56381362, 6.09802302, 6.63798043, array([ 7.46705445, 12.00514545, 4.56381362, 6.09802302, 6.63798043,
4.15145759]), 4.15145759]),
array([ 7.30825872, 11.69035982, 4.65181027, 6.11255694, 6.58831875, array([ 7.30825872, 11.69035982, 4.65181027, 6.11255694, 6.58831875,
3.84043199]), 3.84043199]),
array([ 7.13537007, 11.35143303, 4.73571802, 6.12550256, 6.53829127, array([ 7.13537007, 11.35143303, 4.73571802, 6.12550256, 6.53829127,
3.54962717]), 3.54962717]),
array([ 6.9499758 , 10.99054909, 4.81553115, 6.13689489, 6.48793059, array([ 6.9499758 , 10.99054909, 4.81553115, 6.13689489, 6.48793059,
3.2781224 ]), 3.2781224 ]),
array([ 6.75363732, 10.60980538, 4.89119051, 6.14672866, 6.43725748, array([ 6.75363732, 10.60980538, 4.89119051, 6.14672866, 6.43725748,
3.02498004]), 3.02498004]),
array([ 6.54788813, 10.21121463, 4.96259118, 6.15496333, 6.38628163, array([ 6.54788813, 10.21121463, 4.96259118, 6.15496333, 6.38628163,
2.78925294]), 2.78925294]),
array([6.3342316 , 9.79670696, 5.02958987, 6.16152774, 6.33500222, array([6.3342316 , 9.79670696, 5.02958987, 6.16152774, 6.33500222,
2.56999094]), 2.56999094]),
array([6.11413827, 9.36813186, 5.09201213, 6.16632454, 6.28340854, array([6.11413827, 9.36813186, 5.09201213, 6.16632454, 6.28340854,
2.36624668]), 2.36624668]),
array([5.88904299, 8.92726026, 5.14965924, 6.16923438, 6.23148063, array([5.88904299, 8.92726026, 5.14965924, 6.16923438, 6.23148063,
2.17708075]), 2.17708075]),
array([5.6603419 , 8.47578651, 5.20231494, 6.17011992, 6.17918975, array([5.6603419 , 8.47578651, 5.20231494, 6.17011992, 6.17918975,
2.00156622]), 2.00156622]),
array([5.42938926, 8.01533035, 5.24975175, 6.16882955, 6.12649907, array([5.42938926, 8.01533035, 5.24975175, 6.16882955, 6.12649907,
1.83879274]), 1.83879274]),
array([5.19749431, 7.54743885, 5.29173699, 6.16520097, 6.07336427, array([5.19749431, 7.54743885, 5.29173699, 6.16520097, 6.07336427,
1.68787012]), 1.68787012]),
array([4.96591821, 7.07358822, 5.32803847, 6.15906455, 6.01973415, array([4.96591821, 7.07358822, 5.32803847, 6.15906455, 6.01973415,
1.54793161]), 1.54793161]),
array([4.73587101, 6.59518573, 5.35842971, 6.15024646, 5.96555132, array([4.73587101, 6.59518573, 5.35842971, 6.15024646, 5.96555132,
1.4181368 ]), 1.4181368 ]),
array([4.50850887, 6.11357145, 5.38269484, 6.13857161, 5.91075284, array([4.50850887, 6.11357145, 5.38269484, 6.13857161, 5.91075284,
1.29767421]), 1.29767421]),
array([4.28493147, 5.63002003, 5.40063304, 6.12386633, 5.85527093, array([4.28493147, 5.63002003, 5.40063304, 6.12386633, 5.85527093,
1.18576374]), 1.18576374]),
array([4.06617971, 5.1457425 , 5.4120625 , 6.10596088, 5.79903357, array([4.06617971, 5.1457425 , 5.4120625 , 6.10596088, 5.79903357,
1.08165873]), 1.08165873]),
array([3.85323366, 4.66188801, 5.41682403, 6.08469166, 5.74196516, array([3.85323366, 4.66188801, 5.41682403, 6.08469166, 5.74196516,
0.98464792]), 0.98464792]),
array([3.64701095, 4.17954563, 5.41478413, 6.05990319, 5.68398705, array([3.64701095, 4.17954563, 5.41478413, 6.05990319, 5.68398705,
0.89405723]), 0.89405723]),
array([3.44836539, 3.69974607, 5.40583761, 6.03144986, 5.62501811, array([3.44836539, 3.69974607, 5.40583761, 6.03144986, 5.62501811,
0.80925126]), 0.80925126]),
array([3.25808605, 3.22346359, 5.38990983, 5.99919739, 5.5649751 , array([3.25808605, 3.22346359, 5.38990983, 5.99919739, 5.5649751 ,
0.72963479]), 0.72963479]),
array([3.07689666, 2.75161777, 5.36695843, 5.963024 , 5.50377309, array([3.07689666, 2.75161777, 5.36695843, 5.963024 , 5.50377309,
0.65465391]), 0.65465391]),
array([2.90545542, 2.28507539, 5.33697462, 5.92282138, 5.44132566, array([2.90545542, 2.28507539, 5.33697462, 5.92282138, 5.44132566,
0.58379718]), 0.58379718]),
array([2.74435512, 1.82465233, 5.29998414, 5.87849529, 5.37754504, array([2.74435512, 1.82465233, 5.29998414, 5.87849529, 5.37754504,
0.51659649]), 0.51659649]),
array([2.59412369, 1.37111547, 5.25604769, 5.82996596, 5.31234215, array([2.59412369, 1.37111547, 5.25604769, 5.82996596, 5.31234215,
0.45262783]), 0.45262783]),
array([2.455225 , 0.92518457, 5.20526106, 5.7771682 , 5.24562645, array([2.455225 , 0.92518457, 5.20526106, 5.7771682 , 5.24562645,
0.39151182]), 0.39151182]),
array([2.32806001, 0.48753425, 5.1477549 , 5.72005122, 5.17730577, array([2.32806001, 0.48753425, 5.1477549 , 5.72005122, 5.17730577,
0.33291412]), 0.33291412]),
array([2.21296823, 0.05879575, 5.08369405, 5.6585782 , 5.10728585, array([2.21296823, 0.05879575, 5.08369405, 5.6585782 , 5.10728585,
0.27654558]), 0.27654558]),
array([ 2.11022937, -0.36044114, 5.01327666, 5.59272568, 5.03546994, array([ 2.11022937, -0.36044114, 5.01327666, 5.59272568, 5.03546994,
0.22216224]), 0.22216224]),
array([ 2.02006529, -0.76962634, 4.93673287, 5.52248256, 4.96175816, array([ 2.02006529, -0.76962634, 4.93673287, 5.52248256, 4.96175816,
0.1695651 ]), 0.1695651 ]),
array([ 1.9426421 , -1.16824779, 4.85432333, 5.44784904, 4.8860468 , array([ 1.9426421 , -1.16824779, 4.85432333, 5.44784904, 4.8860468 ,
0.11859959]), 0.11859959]),
array([ 1.87807247, -1.55582988, 4.76633734, 5.36883526, 4.80822753, array([ 1.87807247, -1.55582988, 4.76633734, 5.36883526, 4.80822753,
0.06915493]), 0.06915493]),
array([ 1.82641807, -1.93193194, 4.67309075, 5.28545979, 4.7281866 , array([ 1.82641807, -1.93193194, 4.67309075, 5.28545979, 4.7281866 ,
0.02116307]), 0.02116307]),
array([ 1.78769208, -2.2961469 , 4.57492363, 5.19774795, 4.64580389, array([ 1.78769208, -2.2961469 , 4.57492363, 5.19774795, 4.64580389,
-0.02540251]), -0.02540251]),
array([ 1.76186189, -2.64810013, 4.47219767, 5.10573001, 4.5609521 , array([ 1.76186189, -2.64810013, 4.47219767, 5.10573001, 4.5609521 ,
-0.07052837]), -0.07052837]),
array([ 1.74885176, -2.98744831, 4.36529337, 5.00943931, 4.47349586, array([ 1.74885176, -2.98744831, 4.36529337, 5.00943931, 4.47349586,
-0.11416299]), -0.11416299]),
array([ 1.74854557, -3.31387854, 4.25460703, 4.90891029, 4.38329101, array([ 1.74854557, -3.31387854, 4.25460703, 4.90891029, 4.38329101,
-0.15621897]), -0.15621897]),
array([ 1.76078957, -3.62710753, 4.14054746, 4.80417657, 4.29018395, array([ 1.76078957, -3.62710753, 4.14054746, 4.80417657, 4.29018395,
-0.19657552]), -0.19657552]),
array([ 1.78539513, -3.92688085, 4.02353256, 4.69526902, 4.19401125, array([ 1.78539513, -3.92688085, 4.02353256, 4.69526902, 4.19401125,
-0.23508148]), -0.23508148]),
array([ 1.82214137, -4.21297232, 3.90398574, 4.58221402, 4.09459948, array([ 1.82214137, -4.21297232, 3.90398574, 4.58221402, 4.09459948,
-0.27155856]), -0.27155856]),
array([ 1.87077783, -4.48518333, 3.78233212, 4.46503185, 3.99176538, array([ 1.87077783, -4.48518333, 3.78233212, 4.46503185, 3.99176538,
-0.30580508]), -0.30580508]),
array([ 1.93102694, -4.74334218, 3.65899463, 4.34373536, 3.88531646, array([ 1.93102694, -4.74334218, 3.65899463, 4.34373536, 3.88531646,
-0.33760019]), -0.33760019]),
array([ 2.0025863 , -4.98730328, 3.53439006, 4.21832906, 3.77505213, array([ 2.0025863 , -4.98730328, 3.53439006, 4.21832906, 3.77505213,
-0.36670842]), -0.36670842]),
array([ 2.0851309 , -5.21694618, 3.40892502, 4.08880864, 3.66076534, array([ 2.0851309 , -5.21694618, 3.40892502, 4.08880864, 3.66076534,
-0.39288483]), -0.39288483]),
array([ 2.17831489, -5.43217434, 3.28299196, 3.9551611 , 3.54224502, array([ 2.17831489, -5.43217434, 3.28299196, 3.9551611 , 3.54224502,
-0.41588051]), -0.41588051]),
array([ 2.28177313, -5.63291357, 3.15696529, 3.81736561, 3.41927926, array([ 2.28177313, -5.63291357, 3.15696529, 3.81736561, 3.41927926,
-0.43544873]), -0.43544873]),
array([ 2.39512225, -5.81911007, 3.03119767, 3.67539521, 3.29165931, array([ 2.39512225, -5.81911007, 3.03119767, 3.67539521, 3.29165931,
-0.45135138]), -0.45135138]),
array([ 2.51796124, -5.99072798, 2.90601666, 3.52921956, 3.15918463, array([ 2.51796124, -5.99072798, 2.90601666, 3.52921956, 3.15918463,
-0.463366 ]), -0.463366 ]),
array([ 2.64987133, -6.14774646, 2.78172186, 3.37880871, 3.02166895, array([ 2.64987133, -6.14774646, 2.78172186, 3.37880871, 3.02166895,
-0.47129322]), -0.47129322]),
array([ 2.79041519, -6.29015628, 2.65858257, 3.22413823, 2.87894737, array([ 2.79041519, -6.29015628, 2.65858257, 3.22413823, 2.87894737,
-0.47496445]), -0.47496445]),
array([ 2.93913519, -6.4179559 , 2.53683639, 3.06519564, 2.73088464, array([ 2.93913519, -6.4179559 , 2.53683639, 3.06519564, 2.73088464,
-0.47425003]), -0.47425003]),
array([ 3.09555063, -6.53114718, 2.41668874, 2.90198828, 2.57738443, array([ 3.09555063, -6.53114718, 2.41668874, 2.90198828, 2.57738443,
-0.46906734]), -0.46906734]),
array([ 3.25915386, -6.6297309 , 2.29831367, 2.73455263, 2.41839969, array([ 3.25915386, -6.6297309 , 2.29831367, 2.73455263, 2.41839969,
-0.45938907]), -0.45938907]),
array([ 3.4294051 , -6.71370216, 2.18185605, 2.56296509, 2.25394385, array([ 3.4294051 , -6.71370216, 2.18185605, 2.56296509, 2.25394385,
-0.44525122]), -0.44525122]),
array([ 3.60572597, -6.78304607, 2.06743549, 2.38735399, 2.08410272, array([ 3.60572597, -6.78304607, 2.06743549, 2.38735399, 2.08410272,
-0.4267606 ]), -0.4267606 ]),
array([ 3.78749167, -6.83773403, 1.95515193, 2.20791269, 1.90904669, array([ 3.78749167, -6.83773403, 1.95515193, 2.20791269, 1.90904669,
-0.40410168]), -0.40410168]),
array([ 3.97402193, -6.87772092, 1.84509329, 2.02491349, 1.72904296, array([ 3.97402193, -6.87772092, 1.84509329, 2.02491349, 1.72904296,
-0.37754224]), -0.37754224]),
array([ 4.16457088, -6.90294374, 1.73734487, 1.8387216 , 1.54446718, array([ 4.16457088, -6.90294374, 1.73734487, 1.8387216 , 1.54446718,
-0.34743757]), -0.34743757]),
array([ 4.35831631, -6.91332201, 1.63200064, 1.64980888, 1.35581392, array([ 4.35831631, -6.91332201, 1.63200064, 1.64980888, 1.35581392,
-0.31423263]), -0.31423263]),
array([ 4.55434867, -6.90876048, 1.52917599, 1.45876616, 1.16370522, array([ 4.55434867, -6.90876048, 1.52917599, 1.45876616, 1.16370522,
-0.27846184]), -0.27846184]),
array([ 4.75166081, -6.88915435, 1.42902147, 1.26631351, 0.96889646, array([ 4.75166081, -6.88915435, 1.42902147, 1.26631351, 0.96889646,
-0.24074598]), -0.24074598]),
array([ 4.94913916, -6.85439735, 1.33173685, 1.07330712, 0.77227859, array([ 4.94913916, -6.85439735, 1.33173685, 1.07330712, 0.77227859,
-0.2017856 ]), -0.2017856 ]),
array([ 5.14555779, -6.80439259, 1.23758446, 0.88074165, 0.57487576, array([ 5.14555779, -6.80439259, 1.23758446, 0.88074165, 0.57487576,
-0.16235082]), -0.16235082]),
array([ 5.33957662, -6.73906614, 1.14690061, 0.6897469 , 0.3778377 , array([ 5.33957662, -6.73906614, 1.14690061, 0.6897469 , 0.3778377 ,
-0.12326703]), -0.12326703]),
array([ 5.52974541, -6.65838282, 1.06010364, 0.50157746, 0.18242577, array([ 5.52974541, -6.65838282, 1.06010364, 0.50157746, 0.18242577,
-0.08539643]), -0.08539643]),
array([ 5.71451513, -6.56236356, 0.97769687, 0.31759443, -0.01000771, array([ 5.71451513, -6.56236356, 0.97769687, 0.31759443, -0.01000771,
-0.04961559]), -0.04961559]),
array([ 5.89225835, -6.45110321, 0.90026481, 0.13923841, -0.19804715, array([ 5.89225835, -6.45110321, 0.90026481, 0.13923841, -0.19804715,
-0.01678936]), -0.01678936]),
array([ 6.06130005, -6.32478781, 0.82846078, -0.03200656, -0.38024844, array([ 6.06130005, -6.32478781, 0.82846078, -0.03200656, -0.38024844,
0.01225827]), 0.01225827]),
array([ 6.21995978, -6.18370961, 0.76298449, -0.19465785, -0.55518021, array([ 6.21995978, -6.18370961, 0.76298449, -0.19465785, -0.55518021,
0.03677506]), 0.03677506]),
array([ 6.3666056 , -6.02827873, 0.70454855, -0.34728707, -0.72147039, array([ 6.3666056 , -6.02827873, 0.70454855, -0.34728707, -0.72147039,
0.05611212]), 0.05611212]),
array([ 6.49971915, -5.85902974, 0.65383341, -0.48857901, -0.87785669, array([ 6.49971915, -5.85902974, 0.65383341, -0.48857901, -0.87785669,
0.06975437]), 0.06975437]),
array([ 6.61797022, -5.67662234, 0.61143158, -0.61739433, -1.02323851, array([ 6.61797022, -5.67662234, 0.61143158, -0.61739433, -1.02323851,
0.07734801]), 0.07734801]),
array([ 6.72029774, -5.48183525, 0.57778294, -0.73283268, -1.15672779, array([ 6.72029774, -5.48183525, 0.57778294, -0.73283268, -1.15672779,
0.07872325]), 0.07872325]),
array([ 6.80599254, -5.27555318, 0.55310472, -0.83429208, -1.27769542, array([ 6.80599254, -5.27555318, 0.55310472, -0.83429208, -1.27769542,
0.0739103 ]), 0.0739103 ]),
array([ 6.87477581, -5.05874743, 0.53732127, -0.92152034, -1.38581001, array([ 6.87477581, -5.05874743, 0.53732127, -0.92152034, -1.38581001,
0.0631472 ]), 0.0631472 ]),
array([ 6.92686606, -4.8324514 , 0.5300001 , -0.9946536 , -1.48106546, array([ 6.92686606, -4.8324514 , 0.5300001 , -0.9946536 , -1.48106546,
0.04687834]), 0.04687834]),
array([ 6.96302632, -4.59773271, 0.53030213, -1.0542378 , -1.56379424, array([ 6.96302632, -4.59773271, 0.53030213, -1.0542378 , -1.56379424,
0.02574323]), 0.02574323]),
array([ 6.98458379e+00, -4.35566458e+00, 5.36954030e-01, -1.10122923e+00, array([ 6.98458379e+00, -4.35566458e+00, 5.36954030e-01, -1.10122923e+00,
-1.63466406e+00, 5.55777308e-04]), -1.63466406e+00, 5.55777308e-04]),
array([ 6.99341481, -4.10729885, 0.54825028, -1.13697179, -1.69465618, array([ 6.99341481, -4.10729885, 0.54825028, -1.13697179, -1.69465618,
-0.0277251 ]), -0.0277251 ]),
array([ 6.9918907 , -3.85364338, 0.56209038, -1.16315014, -1.7450254 , array([ 6.9918907 , -3.85364338, 0.56209038, -1.16315014, -1.7450254 ,
-0.0580318 ]), -0.0580318 ]),
array([ 6.98278309, -3.59564593, 0.57605378, -1.18172008, -1.78724302, array([ 6.98278309, -3.59564593, 0.57605378, -1.18172008, -1.78724302,
-0.08922936]), -0.08922936]),
array([ 6.96913209, -3.334186 , 0.58751072, -1.1948195 , -1.82292561, array([ 6.96913209, -3.334186 , 0.58751072, -1.1948195 , -1.82292561,
-0.12015933]), -0.12015933]),
array([ 6.95408484, -3.07007503, 0.59376269, -1.20466555, -1.85375422, array([ 6.95408484, -3.07007503, 0.59376269, -1.20466555, -1.85375422,
-0.14968391]), -0.14968391]),
array([ 6.94071673, -2.80406442, 0.59220157, -1.21344511, -1.88138957, array([ 6.94071673, -2.80406442, 0.59220157, -1.21344511, -1.88138957,
-0.17672812]), -0.17672812]),
array([ 6.93185053, -2.53685974, 0.58047294, -1.22320684, -1.90738942, array([ 6.93185053, -2.53685974, 0.58047294, -1.22320684, -1.90738942,
-0.20031814]), -0.20031814]),
array([ 6.92989007, -2.26913873, 0.55662783, -1.23576312, -1.93313458, array([ 6.92989007, -2.26913873, 0.55662783, -1.23576312, -1.93313458,
-0.21961442]), -0.21961442]),
array([ 6.93668419, -2.00157024, 0.51924695, -1.25260927, -1.95976886, array([ 6.93668419, -2.00157024, 0.51924695, -1.25260927, -1.95976886,
-0.23393853]), -0.23393853]),
array([ 6.95343388, -1.73483135, 0.46752496, -1.27486597, -1.98815736, array([ 6.95343388, -1.73483135, 0.46752496, -1.27486597, -1.98815736,
-0.24279306]), -0.24279306]),
array([ 6.98065011, -1.46962003, 0.4013067 , -1.30324835, -2.01886515, array([ 6.98065011, -1.46962003, 0.4013067 , -1.30324835, -2.01886515,
-0.24587415]), -0.24587415]),
array([ 7.01816458, -1.2066619 , 0.32107317, -1.33806248, -2.05215693, array([ 7.01816458, -1.2066619 , 0.32107317, -1.33806248, -2.05215693,
-0.24307645]), -0.24307645]),
array([ 7.06518905, -0.94670995, 0.22788113, -1.37922765, -2.08801567, array([ 7.06518905, -0.94670995, 0.22788113, -1.37922765, -2.08801567,
-0.23449049]), -0.23449049]),
array([ 7.12041449, -0.69053767, 0.12326497, -1.42632031, -2.12617722, array([ 7.12041449, -0.69053767, 0.12326497, -1.42632031, -2.12617722,
-0.22039253]), -0.22039253]),
array([ 7.1821374 , -0.43892647, 0.00911335, -1.47863432, -2.16617627, array([ 7.1821374 , -0.43892647, 0.00911335, -1.47863432, -2.16617627,
-0.20122747]), -0.20122747]),
array([ 7.24839949, -0.19264898, -0.11246603, -1.53525094, -2.20739892, array([ 7.24839949, -0.19264898, -0.11246603, -1.53525094, -2.20739892,
-0.17758551]), -0.17758551]),
array([ 7.31712741, 0.04754974, -0.23928018, -1.59511251, -2.24913712, array([ 7.31712741, 0.04754974, -0.23928018, -1.59511251, -2.24913712,
-0.15017381]), -0.15017381]),
array([ 7.38626102, 0.28097116, -0.36917222, -1.65709394, -2.29064067, array([ 7.38626102, 0.28097116, -0.36917222, -1.65709394, -2.29064067,
-0.11978457]), -0.11978457]),
array([ 7.45386196, 0.50698071, -0.50012241, -1.7200674 , -2.33116375, array([ 7.45386196, 0.50698071, -0.50012241, -1.7200674 , -2.33116375,
-0.08726132]), -0.08726132]),
array([ 7.51819755, 0.72502225, -0.63032438, -1.78295708, -2.37000356, array([ 7.51819755, 0.72502225, -0.63032438, -1.78295708, -2.37000356,
-0.05346534]), -0.05346534]),
array([ 7.57779833, 0.93462871, -0.75823523, -1.84478211, -2.4065301 , array([ 7.57779833, 0.93462871, -0.75823523, -1.84478211, -2.4065301 ,
-0.01924376]), -0.01924376]),
array([ 7.63149017, 1.13542865, -0.882601 , -1.90468702, -2.4402067 , array([ 7.63149017, 1.13542865, -0.882601 , -1.90468702, -2.4402067 ,
0.01459886]), 0.01459886]),
array([ 7.67840396, 1.32714856, -1.00246077, -1.96196028, -2.47060205, array([ 7.67840396, 1.32714856, -1.00246077, -1.96196028, -2.47060205,
0.04732453]), 0.04732453]),
array([ 7.71796697, 1.50961148, -1.1171336 , -2.01604208, -2.49739449, array([ 7.71796697, 1.50961148, -1.1171336 , -2.01604208, -2.49739449,
0.07828052]), 0.07828052]),
array([ 7.74988042, 1.68273238, -1.22619326, -2.06652322, -2.52037009, array([ 7.74988042, 1.68273238, -1.22619326, -2.06652322, -2.52037009,
0.10691244]), 0.10691244]),
array([ 7.77408785, 1.84651103, -1.32943503, -2.11313677, -2.53941586, array([ 7.77408785, 1.84651103, -1.32943503, -2.11313677, -2.53941586,
0.13277187]), 0.13277187]),
array([ 7.79073818, 2.00102316, -1.4268386 , -2.15574481, -2.55450954, array([ 7.79073818, 2.00102316, -1.4268386 , -2.15574481, -2.55450954,
0.1555189 ]), 0.1555189 ]),
array([ 7.80014695, 2.1464105 , -1.5185303 , -2.19432179, -2.56570724, array([ 7.80014695, 2.1464105 , -1.5185303 , -2.19432179, -2.56570724,
0.17492016]), 0.17492016]),
array([ 7.8027582 , 2.28287039, -1.60474691, -2.22893615, -2.57313002, array([ 7.8027582 , 2.28287039, -1.60474691, -2.22893615, -2.57313002,
0.1908433 ]), 0.1908433 ]),
array([ 7.79910886, 2.41064538, -1.68580281, -2.25973165, -2.57695032, array([ 7.79910886, 2.41064538, -1.68580281, -2.25973165, -2.57695032,
0.20324858]), 0.20324858]),
array([ 7.78979686, 2.53001328, -1.76206127, -2.28690918, -2.57737892, array([ 7.78979686, 2.53001328, -1.76206127, -2.28690918, -2.57737892,
0.21217853]), 0.21217853]),
array([ 7.77545352, 2.64127789, -1.83391036, -2.31070997, -2.57465291, array([ 7.77545352, 2.64127789, -1.83391036, -2.31070997, -2.57465291,
0.21774645]), 0.21774645]),
array([ 7.75672042, 2.7447606 , -1.90174354, -2.33140053, -2.56902489, array([ 7.75672042, 2.7447606 , -1.90174354, -2.33140053, -2.56902489,
0.22012428]), 0.22012428]),
array([ 7.73423073, 2.84079302, -1.96594454, -2.34925967, -2.56075374, array([ 7.73423073, 2.84079302, -1.96594454, -2.34925967, -2.56075374,
0.21953063]), 0.21953063]),
array([ 7.70859457, 2.92971056, -2.02687623, -2.36456763, -2.55009688, array([ 7.70859457, 2.92971056, -2.02687623, -2.36456763, -2.55009688,
0.21621917]), 0.21621917]),
array([ 7.68038806, 3.01184708, -2.08487291, -2.37759735, -2.53730403, array([ 7.68038806, 3.01184708, -2.08487291, -2.37759735, -2.53730403,
0.21046789]), 0.21046789]),
array([ 7.65014557, 3.08753046, -2.14023544, -2.38860775, -2.52261241, array([ 7.65014557, 3.08753046, -2.14023544, -2.38860775, -2.52261241,
0.20256934]), 0.20256934]),
array([ 7.61835462, 3.15707908, -2.19322873, -2.39783872, -2.50624323, array([ 7.61835462, 3.15707908, -2.19322873, -2.39783872, -2.50624323,
0.19282203]), 0.19282203]),
array([ 7.585453 , 3.22079917, -2.24408111, -2.40550785, -2.48839933, array([ 7.585453 , 3.22079917, -2.24408111, -2.40550785, -2.48839933,
0.18152297]), 0.18152297]),
array([ 7.55182771, 3.27898277, -2.29298504, -2.41180844, -2.46926384, array([ 7.55182771, 3.27898277, -2.29298504, -2.41180844, -2.46926384,
0.16896155]), 0.16896155]),
array([ 7.51781523, 3.33190642, -2.34009894, -2.41690868, -2.44899961, array([ 7.51781523, 3.33190642, -2.34009894, -2.41690868, -2.44899961,
0.15541443]), 0.15541443]),
array([ 7.48370293, 3.37983037, -2.38554968, -2.42095179, -2.42774946, array([ 7.48370293, 3.37983037, -2.38554968, -2.42095179, -2.42774946,
0.14114163]), 0.14114163]),
array([ 7.44973117, 3.42299822, -2.42943559, -2.42405688, -2.40563681, array([ 7.44973117, 3.42299822, -2.42943559, -2.42405688, -2.40563681,
0.12638359]), 0.12638359]),
array([ 7.41609605, 3.46163697, -2.47182966, -2.42632033, -2.38276689, array([ 7.41609605, 3.46163697, -2.47182966, -2.42632033, -2.38276689,
0.11135912]), 0.11135912]),
array([ 7.38295241, 3.49595737, -2.51278289, -2.42781766, -2.35922815, array([ 7.38295241, 3.49595737, -2.51278289, -2.42781766, -2.35922815,
0.09626413]), 0.09626413]),
array([ 7.35041715, 3.52615445, -2.55232757, -2.42860559, -2.33509393, array([ 7.35041715, 3.52615445, -2.55232757, -2.42860559, -2.33509393,
0.08127107]), 0.08127107]),
array([ 7.31857256, 3.55240836, -2.59048052, -2.42872426, -2.3104242 , array([ 7.31857256, 3.55240836, -2.59048052, -2.42872426, -2.3104242 ,
0.06652895]), 0.06652895]),
array([ 7.28746963, 3.57488518, -2.62724598, -2.42819957, -2.28526743, array([ 7.28746963, 3.57488518, -2.62724598, -2.42819957, -2.28526743,
0.05216377]), 0.05216377]),
array([ 7.25713136, 3.59373796, -2.66261848, -2.42704538, -2.25966237, array([ 7.25713136, 3.59373796, -2.66261848, -2.42704538, -2.25966237,
0.03827945]), 0.03827945]),
array([ 7.22755588, 3.60910765, -2.69658527, -2.4252658 , -2.2336398 , array([ 7.22755588, 3.60910765, -2.69658527, -2.4252658 , -2.2336398 ,
0.0249589 ]), 0.0249589 ]),
array([ 7.1987194 , 3.6211242 , -2.72912859, -2.42285721, -2.20722423, array([ 7.1987194 , 3.6211242 , -2.72912859, -2.42285721, -2.20722423,
0.01226551]), 0.01226551]),
array([ 7.17057903e+00, 3.62990755e+00, -2.76022761e+00, -2.41981019e+00, array([ 7.17057903e+00, 3.62990755e+00, -2.76022761e+00, -2.41981019e+00,
-2.18043539e+00, 2.44639452e-04]), -2.18043539e+00, 2.44639452e-04]),
array([ 7.14307531, 3.63556857, -2.78986012, -2.41611129, -2.15328967, array([ 7.14307531, 3.63556857, -2.78986012, -2.41611129, -2.15328967,
-0.01107473]), -0.01107473]),
array([ 7.11613457, 3.63821002, -2.81800395, -2.41174457, -2.12580133, array([ 7.11613457, 3.63821002, -2.81800395, -2.41174457, -2.12580133,
-0.02167824]), -0.02167824]),
array([ 7.08967107, 3.63792742, -2.84463815, -2.40669295, -2.0979836 , array([ 7.08967107, 3.63792742, -2.84463815, -2.40669295, -2.0979836 ,
-0.03156447]), -0.03156447]),
array([ 7.06358894, 3.6348098 , -2.86974393, -2.40093938, -2.06984958, array([ 7.06358894, 3.6348098 , -2.86974393, -2.40093938, -2.06984958,
-0.0407432 ]), -0.0407432 ]),
array([ 7.03778386, 3.62894043, -2.8933054 , -2.39446783, -2.041413 , array([ 7.03778386, 3.62894043, -2.8933054 , -2.39446783, -2.041413 ,
-0.04923377]), -0.04923377]),
array([ 7.01214456, 3.62039744, -2.91531013, -2.38726401, -2.01268885, array([ 7.01214456, 3.62039744, -2.91531013, -2.38726401, -2.01268885,
-0.05706344]), -0.05706344]),
array([ 6.98655419, 3.6092544 , -2.93574946, -2.37931603, -1.98369376, array([ 6.98655419, 3.6092544 , -2.93574946, -2.37931603, -1.98369376,
-0.06426588]), -0.06426588]),
array([ 6.96089142, 3.59558075, -2.95461882, -2.37061484, -1.95444638, array([ 6.96089142, 3.59558075, -2.95461882, -2.37061484, -1.95444638,
-0.07087977]), -0.07087977]),
array([ 6.93503142, 3.57944223, -2.97191772, -2.36115447, -1.92496753, array([ 6.93503142, 3.57944223, -2.97191772, -2.36115447, -1.92496753,
-0.0769474 ]), -0.0769474 ]),
array([ 6.9088467 , 3.56090119, -2.98764979, -2.35093227, -1.89528025, array([ 6.9088467 , 3.56090119, -2.98764979, -2.35093227, -1.89528025,
-0.08251349]), -0.08251349]),
array([ 6.88220779, 3.54001688, -3.00182265, -2.33994887, -1.86540979, array([ 6.88220779, 3.54001688, -3.00182265, -2.33994887, -1.86540979,
-0.08762401]), -0.08762401]),
array([ 6.85498381, 3.51684565, -3.01444772, -2.32820818, -1.83538349, array([ 6.85498381, 3.51684565, -3.01444772, -2.32820818, -1.83538349,
-0.09232516]), -0.09232516]),
array([ 6.82704292, 3.49144108, -3.02553994, -2.31571721, -1.80523053, array([ 6.82704292, 3.49144108, -3.02553994, -2.31571721, -1.80523053,
-0.0966624 ]), -0.0966624 ]),
array([ 6.79825267, 3.46385414, -3.0351175 , -2.30248584, -1.7749817 , array([ 6.79825267, 3.46385414, -3.0351175 , -2.30248584, -1.7749817 ,
-0.10067963]), -0.10067963]),
array([ 6.76848026, 3.43413325, -3.04320144, -2.28852653, -1.74466904, array([ 6.76848026, 3.43413325, -3.04320144, -2.28852653, -1.74466904,
-0.10441836]), -0.10441836]),
array([ 6.73759276, 3.40232429, -3.04981537, -2.27385399, -1.71432547, array([ 6.73759276, 3.40232429, -3.04981537, -2.27385399, -1.71432547,
-0.10791702]), -0.10791702]),
array([ 6.70545722, 3.36847069, -3.05498498, -2.25848479, -1.68398443, array([ 6.70545722, 3.36847069, -3.05498498, -2.25848479, -1.68398443,
-0.11121028]), -0.11121028]),
array([ 6.67194076, 3.33261338, -3.05873774, -2.24243694, -1.65367936, array([ 6.67194076, 3.33261338, -3.05873774, -2.24243694, -1.65367936,
-0.11432853]), -0.11432853]),
array([ 6.63691056, 3.29479078, -3.06110243, -2.22572949, -1.62344332, array([ 6.63691056, 3.29479078, -3.06110243, -2.22572949, -1.62344332,
-0.1172972 ]), -0.1172972 ]),
array([ 6.60023387, 3.25503878, -3.06210881, -2.20838207, -1.59330853, array([ 6.60023387, 3.25503878, -3.06210881, -2.20838207, -1.59330853,
-0.12013634]), -0.12013634]),
array([ 6.56177796, 3.21339071, -3.0617872 , -2.19041444, -1.56330586, array([ 6.56177796, 3.21339071, -3.0617872 , -2.19041444, -1.56330586,
-0.12286004]), -0.12286004]),
array([ 6.52141004, 3.16987732, -3.06016812, -2.17184608, -1.53346441, array([ 6.52141004, 3.16987732, -3.06016812, -2.17184608, -1.53346441,
-0.12547599]), -0.12547599]),
array([ 6.47899715, 3.12452669, -3.05728193, -2.1526957 , -1.50381106, array([ 6.47899715, 3.12452669, -3.05728193, -2.1526957 , -1.50381106,
-0.12798491]), -0.12798491]),
array([ 6.43440602, 3.07736426, -3.05315853, -2.13298089, -1.47437 , array([ 6.43440602, 3.07736426, -3.05315853, -2.13298089, -1.47437 ,
-0.13038011]), -0.13038011]),
array([ 6.38750293, 3.02841274, -3.04782698, -2.11271766, -1.44516235, array([ 6.38750293, 3.02841274, -3.04782698, -2.11271766, -1.44516235,
-0.13264689]), -0.13264689]),
array([ 6.33815354, 2.9776921 , -3.04131523, -2.09192006, -1.4162057 , array([ 6.33815354, 2.9776921 , -3.04131523, -2.09192006, -1.4162057 ,
-0.13476202]), -0.13476202]),
array([ 6.28622267, 2.92521956, -3.03364984, -2.07059983, -1.38751375, array([ 6.28622267, 2.92521956, -3.03364984, -2.07059983, -1.38751375,
-0.13669314]), -0.13669314]),
array([ 6.2315741 , 2.87100953, -3.02485566, -2.04876608, -1.35909593, array([ 6.2315741 , 2.87100953, -3.02485566, -2.04876608, -1.35909593,
-0.13839805]), -0.13839805]),
array([ 6.1740703 , 2.81507362, -3.01495558, -2.02642492, -1.33095701, array([ 6.1740703 , 2.81507362, -3.01495558, -2.02642492, -1.33095701,
-0.13982403]), -0.13982403]),
array([ 6.11357212, 2.7574206 , -3.00397025, -2.00357923, -1.3030968 , array([ 6.11357212, 2.7574206 , -3.00397025, -2.00357923, -1.3030968 ,
-0.14090704]), -0.14090704]),
array([ 6.0499385 , 2.69805643, -2.99191782, -1.98022842, -1.27550979, array([ 6.0499385 , 2.69805643, -2.99191782, -1.98022842, -1.27550979,
-0.14157084]), -0.14157084]),
array([ 5.98302601, 2.6369842 , -2.9788136 , -1.95636817, -1.2481848 , array([ 5.98302601, 2.6369842 , -2.9788136 , -1.95636817, -1.2481848 ,
-0.14172605]), -0.14172605]),
array([ 5.91268841, 2.57420417, -2.96466977, -1.93199036, -1.2211047 , array([ 5.91268841, 2.57420417, -2.96466977, -1.93199036, -1.2211047 ,
-0.14126906]), -0.14126906]),
array([ 5.83877612, 2.50971375, -2.94949495, -1.9070829 , -1.194246 , array([ 5.83877612, 2.50971375, -2.94949495, -1.9070829 , -1.194246 ,
-0.14008089]), -0.14008089]),
array([ 5.76113551, 2.44350746, -2.93329382, -1.88162977, -1.16757857, array([ 5.76113551, 2.44350746, -2.93329382, -1.88162977, -1.16757857,
-0.13802588]), -0.13802588]),
array([ 5.67960814, 2.375577 , -2.9160665 , -1.85561107, -1.14106512, array([ 5.67960814, 2.375577 , -2.9160665 , -1.85561107, -1.14106512,
-0.13495032]), -0.13495032]),
array([ 5.59402975, 2.30591118, -2.89780788, -1.82900322, -1.11466083, array([ 5.59402975, 2.30591118, -2.89780788, -1.82900322, -1.11466083,
-0.13068087]), -0.13068087]),
array([ 5.50422913, 2.23449589, -2.87850674, -1.80177934, -1.08831271, array([ 5.50422913, 2.23449589, -2.87850674, -1.80177934, -1.08831271,
-0.12502289]), -0.12502289]),
array([ 5.41002664, 2.16131412, -2.85814457, -1.77390989, -1.06195892, array([ 5.41002664, 2.16131412, -2.85814457, -1.77390989, -1.06195892,
-0.11775858]), -0.11775858]),
array([ 5.31123248, 2.0863458 , -2.83669407, -1.7453635 , -1.03552781, array([ 5.31123248, 2.0863458 , -2.83669407, -1.7453635 , -1.03552781,
-0.10864502]), -0.10864502]),
array([ 5.20764456, 2.00956776, -2.81411711, -1.71610838, -1.00893678, array([ 5.20764456, 2.00956776, -2.81411711, -1.71610838, -1.00893678,
-0.09741197]), -0.09741197]),
array([ 5.0990458 , 1.9309534 , -2.79036211, -1.68611415, -0.98209066, array([ 5.0990458 , 1.9309534 , -2.79036211, -1.68611415, -0.98209066,
-0.08375949]), -0.08375949]),
array([ 4.98520101, 1.85047235, -2.76536047, -1.65535454, -0.95487959, array([ 4.98520101, 1.85047235, -2.76536047, -1.65535454, -0.95487959,
-0.06735541]), -0.06735541]),
array([ 4.86585291, 1.76808977, -2.73902177, -1.62381106, -0.92717618, array([ 4.86585291, 1.76808977, -2.73902177, -1.62381106, -0.92717618,
-0.04783259]), -0.04783259]),
array([ 4.74071739, 1.68376521, -2.71122737, -1.59147818, -0.89883163, array([ 4.74071739, 1.68376521, -2.71122737, -1.59147818, -0.89883163,
-0.02478587]), -0.02478587]),
array([ 4.60947781e+00, 1.59745075e+00, -2.68182175e+00, -1.55837035e+00, array([ 4.60947781e+00, 1.59745075e+00, -2.68182175e+00, -1.55837035e+00,
-8.69670515e-01, 2.23110239e-03]), -8.69670515e-01, 2.23110239e-03]),
array([ 4.47177814, 1.50908799, -2.65060074, -1.52453167, -0.83948367, array([ 4.47177814, 1.50908799, -2.65060074, -1.52453167, -0.83948367,
0.0337094 ]), 0.0337094 ]),
array([ 4.32721496, 1.41860308, -2.61729554, -1.49004898, -0.80801854, array([ 4.32721496, 1.41860308, -2.61729554, -1.49004898, -0.80801854,
0.07018862]), 0.07018862]),
array([ 4.1753282 , 1.325899 , -2.58155094, -1.45506975, -0.7749661 , array([ 4.1753282 , 1.325899 , -2.58155094, -1.45506975, -0.7749661 ,
0.11226097]), 0.11226097]),
array([ 4.01559077, 1.2308432 , -2.5428955 , -1.41982605, -0.73994301, array([ 4.01559077, 1.2308432 , -2.5428955 , -1.41982605, -0.73994301,
0.16057584]), 0.16057584]),
array([ 3.8473974 , 1.13324856, -2.50070069, -1.38466702, -0.70246751, array([ 3.8473974 , 1.13324856, -2.50070069, -1.38466702, -0.70246751,
0.2158447 ]), 0.2158447 ]),
array([ 3.67005332, 1.03284432, -2.45412485, -1.35010217, -0.66192663, array([ 3.67005332, 1.03284432, -2.45412485, -1.35010217, -0.66192663,
0.27884666]), 0.27884666]),
array([ 3.48276368, 0.92923281, -2.40203646, -1.3168596 , -0.61753192, array([ 3.48276368, 0.92923281, -2.40203646, -1.3168596 , -0.61753192,
0.35043464]), 0.35043464]),
array([ 3.28462528, 0.82182713, -2.34291 , -1.28596362, -0.56825955, array([ 3.28462528, 0.82182713, -2.34291 , -1.28596362, -0.56825955,
0.43154267]), 0.43154267]),
array([ 3.07462255, 0.70976532, -2.27468664, -1.25883928, -0.51276978, array([ 3.07462255, 0.70976532, -2.27468664, -1.25883928, -0.51276978,
0.52319461]), 0.52319461]),
array([ 2.85163103, 0.59180017, -2.19459421, -1.237454 , -0.44929893, array([ 2.85163103, 0.59180017, -2.19459421, -1.237454 , -0.44929893,
0.62651555]), 0.62651555]),
array([ 2.61443471, 0.46617382, -2.09892828, -1.22451277, -0.37551555, array([ 2.61443471, 0.46617382, -2.09892828, -1.22451277, -0.37551555,
0.74274775]), 0.74274775]),
array([ 2.36177336, 0.33050882, -1.98281654, -1.22373052, -0.2883301 , array([ 2.36177336, 0.33050882, -1.98281654, -1.22373052, -0.2883301 ,
0.87327516]), 0.87327516]),
array([ 2.0924633 , 0.18179214, -1.84002523, -1.24020707, -0.18364463, array([ 2.0924633 , 0.18179214, -1.84002523, -1.24020707, -0.18364463,
1.01966444]), 1.01966444]),
array([ 1.80570754, 0.01661621, -1.66290677, -1.28089393, -0.05602076, array([ 1.80570754, 0.01661621, -1.66290677, -1.28089393, -0.05602076,
1.18373752]), 1.18373752]),
array([ 1.50191892, -0.16796766, -1.44255224, -1.35498021, 0.10178605, array([ 1.50191892, -0.16796766, -1.44255224, -1.35498021, 0.10178605,
1.36770709]), 1.36770709]),
array([ 1.18503942, -0.37207516, -1.16881095, -1.4736232 , 0.29960962, array([ 1.18503942, -0.37207516, -1.16881095, -1.4736232 , 0.29960962,
1.57444144]), 1.57444144]),
array([ 0.86953931, -0.58633231, -0.82798614, -1.64831962, 0.55190896, array([ 0.86953931, -0.58633231, -0.82798614, -1.64831962, 0.55190896,
1.80801137]), 1.80801137]),
array([ 0.60030872, -0.77390263, -0.38975414, -1.89159215, 0.88828811, array([ 0.60030872, -0.77390263, -0.38975414, -1.89159215, 0.88828811,
2.07472138]), 2.07472138]),
array([ 0.4764655 , -0.84946206, 0.22134384, -2.23923687, 1.44338066, array([ 0.4764655 , -0.84946206, 0.22134384, -2.23923687, 1.44338066,
2.37952862])], 2.37952862])],
True) True)
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
from crocoddyl.diagnostic import displayTrajectory from crocoddyl.diagnostic import displayTrajectory
displayTrajectory(robot, ddp.xs, runningModel.timeStep) displayTrajectory(robot, ddp.xs, runningModel.timeStep)
``` ```
%% Output %% Output
/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/diagnostic.py:75: DeprecatedWarning: Call to deprecated function initDisplay. Use initViewer /home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/diagnostic.py:75: DeprecatedWarning: Call to deprecated function initDisplay. Use initViewer
robot.initDisplay(loadModel=True) robot.initDisplay(loadModel=True)
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
``` ```
%% Cell type:code id: tags: %% Cell type:code id: tags:
``` python ``` python
``` ```
......
...@@ -302,7 +302,7 @@ ...@@ -302,7 +302,7 @@
"name": "python", "name": "python",
"nbconvert_exporter": "python", "nbconvert_exporter": "python",
"pygments_lexer": "ipython2", "pygments_lexer": "ipython2",
"version": "2.7.12" "version": "2.7.16"
} }
}, },
"nbformat": 4, "nbformat": 4,
......
This diff is collapsed.
source diff could not be displayed: it is too large. Options to address this: view the blob.
File added
kinton_description/meshes/arm/dynamixel/BrazoHinton_Dynamixel_PiezasIrir.png

210 KiB

File added
File added
File added
File added
File added
File added
File added
File added
File added
File added
This diff is collapsed.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment