diff --git a/crocoddyl/__init__.py b/crocoddyl/__init__.py
index f128f612dffc99a6ca82388db41d6eab477dcb7f..ecca59a228e0eca8b602c8cb1b3442cc7442c218 100644
--- a/crocoddyl/__init__.py
+++ b/crocoddyl/__init__.py
@@ -3,7 +3,7 @@ from .action import (ActionDataAbstract, ActionDataLQR, ActionDataNumDiff, Actio
 from .activation import (ActivationDataInequality, ActivationDataQuad, ActivationDataSmoothAbs,
                          ActivationDataWeightedQuad, ActivationModelInequality, ActivationModelQuad,
                          ActivationModelSmoothAbs, ActivationModelWeightedQuad)
-from .actuation import ActuationDataFreeFloating, ActuationDataFull, ActuationModelFreeFloating, ActuationModelFull
+from .actuation import ActuationDataFreeFloating, ActuationDataFull, ActuationModelFreeFloating, ActuationModelFull, ActuationModelUAM
 from .box_ddp import SolverBoxDDP
 from .box_kkt import SolverBoxKKT
 from .callbacks import CallbackDDPLogger, CallbackDDPVerbose, CallbackSolverDisplay, CallbackSolverTimer
@@ -23,12 +23,13 @@ from .differential_action import (DifferentialActionDataAbstract, DifferentialAc
                                   DifferentialActionModelLQR, DifferentialActionModelNumDiff)
 from .fddp import SolverFDDP
 from .floating_contact import DifferentialActionDataFloatingInContact, DifferentialActionModelFloatingInContact
+from .flying import DifferentialActionModelUAM, DifferentialActionDataUAM
 from .impact import (ActionDataImpact, ActionModelImpact, CostModelImpactCoM, CostModelImpactWholeBody, ImpulseData6D,
                      ImpulseDataPinocchio, ImpulseModel3D, ImpulseModel6D, ImpulseModelMultiple, ImpulseModelPinocchio)
 from .integrated_action import (IntegratedActionDataEuler, IntegratedActionDataRK4, IntegratedActionModelEuler,
                                 IntegratedActionModelRK4)
 from .kkt import SolverKKT
-from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs
+from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs, loadKinton, loadKintonArm
 from .shooting import ShootingProblem
 from .solver import SolverAbstract
 from .state import StateAbstract, StateNumDiff, StatePinocchio, StateVector
diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py
index 3e416ec2e7a4596043407d362a6ad85d20b7302f..dac17e43c6694b652c3e926aff87a55eab5e107d 100644
--- a/crocoddyl/actuation.py
+++ b/crocoddyl/actuation.py
@@ -2,6 +2,44 @@ import warnings
 
 import numpy as np
 
+class ActuationModelUAM:
+    '''
+    This model transforms an actuation u into a joint torque tau.
+    We implement here the simplest model: tau = S.T*u, where S is constant.
+    '''
+
+    def __init__(self, pinocchioModel):
+        self.pinocchio = pinocchioModel
+        if (pinocchioModel.joints[1].shortname() != 'JointModelFreeFlyer'):
+            warnings.warn('Strange that the first joint is not a freeflyer')
+        self.nq = pinocchioModel.nq
+        self.nv = pinocchioModel.nv
+        self.nx = self.nq + self.nv
+        self.ndx = self.nv * 2
+        self.nu = self.nv - 2
+
+    def calc(self, data, x, u):
+        data.a[2:] = u
+        return data.a
+
+    def calcDiff(self, data, x, u, recalc=True):
+        if recalc:
+            self.calc(data, x, u)
+        return data.a
+
+    def createData(self, pinocchioData):
+        return ActuationDataUAM(self, pinocchioData)
+
+
+class ActuationDataUAM:
+    def __init__(self, model, pinocchioData):
+        self.pinocchio = pinocchioData
+        ndx, nv, nu = model.ndx, model.nv, model.nu
+        self.a = np.zeros(nv)  # result of calc
+        self.A = np.zeros([nv, ndx + nu])  # result of calcDiff
+        self.Ax = self.A[:, :ndx]
+        self.Au = self.A[:, ndx:]
+        np.fill_diagonal(self.Au[2:, :], 1)
 
 class ActuationModelFreeFloating:
     '''
diff --git a/crocoddyl/flying.py b/crocoddyl/flying.py
new file mode 100644
index 0000000000000000000000000000000000000000..3a10c3e48fee2ec830d267c848e842695224ca22
--- /dev/null
+++ b/crocoddyl/flying.py
@@ -0,0 +1,79 @@
+import numpy as np
+import pinocchio
+
+from .differential_action import DifferentialActionDataAbstract, DifferentialActionModelAbstract
+from .state import StatePinocchio
+from .utils import a2m, m2a
+
+
+class DifferentialActionModelUAM(DifferentialActionModelAbstract):
+    def __init__(self, pinocchioModel, actuationModel, costModel):
+        DifferentialActionModelAbstract.__init__(self, pinocchioModel.nq, pinocchioModel.nv, actuationModel.nu)
+        self.DifferentialActionDataType = DifferentialActionDataUAM
+        self.pinocchio = pinocchioModel
+        self.State = StatePinocchio(self.pinocchio)
+        self.actuation = actuationModel
+        self.costs = costModel
+
+    @property
+    def ncost(self):
+        return self.costs.ncost
+
+    def calc(self, data, x, u=None):
+        if u is None:
+            u = self.unone
+        nq, nv = self.nq, self.nv
+        q = a2m(x[:nq])
+        v = a2m(x[-nv:])
+
+        data.tauq[:] = self.actuation.calc(data.actuation, x, u)
+
+        pinocchio.computeAllTerms(self.pinocchio, data.pinocchio, q, v)
+        data.M = data.pinocchio.M
+        data.Minv = np.linalg.inv(data.M)
+        # print data.Minv
+        # print data.tauq
+        # print data.pinocchio.nle
+        data.xout[:] = data.Minv * (a2m(data.tauq) - data.pinocchio.nle).flat
+
+        # --- Cost
+        pinocchio.forwardKinematics(self.pinocchio, data.pinocchio, q, v)
+        pinocchio.updateFramePlacements(self.pinocchio, data.pinocchio)
+        data.cost = self.costs.calc(data.costs, x, u)
+        return data.xout, data.cost
+
+    def calcDiff(self, data, x, u=None, recalc=True):
+        if u is None:
+            u = self.unone
+        if recalc:
+            xout, cost = self.calc(data, x, u)
+        nq, nv = self.nq, self.nv
+        q = a2m(x[:nq])
+        v = a2m(x[-nv:])
+        a = a2m(data.xout)
+
+        dtau_dx = data.actuation.Ax
+        dtau_du = data.actuation.Au
+
+        pinocchio.computeRNEADerivatives(self.pinocchio, data.pinocchio, q, v, a)
+        data.Fx[:, :nv] = -np.dot(data.Minv, data.pinocchio.dtau_dq)
+        data.Fx[:, nv:] = -np.dot(data.Minv, data.pinocchio.dtau_dv)
+        data.Fx += np.dot(data.Minv, dtau_dx)
+        data.Fu[:, :] = np.dot(data.Minv, dtau_du)
+        # Cost
+        pinocchio.computeJointJacobians(self.pinocchio, data.pinocchio, q)
+        pinocchio.updateFramePlacements(self.pinocchio, data.pinocchio)
+        self.costs.calcDiff(data.costs, x, u, recalc=False)
+        return data.xout, data.cost
+
+class DifferentialActionDataUAM(DifferentialActionDataAbstract):
+    def __init__(self, model):
+        self.pinocchio = model.pinocchio.createData()
+        self.actuation = model.actuation.createData(self.pinocchio)
+        costData = model.costs.createData(self.pinocchio)
+        # print self.costs.Lu
+        DifferentialActionDataAbstract.__init__(self, model, costData)
+
+        nv = model.nv
+        self.tauq = np.zeros(nv)
+        self.xout = np.zeros(nv)
diff --git a/crocoddyl/robots.py b/crocoddyl/robots.py
index 4b4c3774ac88074735f4d7d1283737f2721899d8..00d0e0c23aa07e04446fdb522b51d5be62881fea 100644
--- a/crocoddyl/robots.py
+++ b/crocoddyl/robots.py
@@ -125,3 +125,17 @@ def loadHyQ(modelPath='/opt/openrobots/share/example-robot-data'):
     robot.q0[2] = 0.57750958
     robot.model.referenceConfigurations["half_sitting"] = robot.q0
     return robot
+
+def loadKinton(modelPath='/opt/openrobots/share/example-robot-data'):
+    URDF_FILENAME = "kinton_arm.urdf"
+    URDF_SUBPATH = "/kinton_description/urdf/" + URDF_FILENAME
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
+    robot.q0.flat[7:] = [0, 0, 0, 0, 0, 0]
+    robot.model.referenceConfigurations["initial_pose"] = robot.q0
+    return robot
+
+def loadKintonArm(modelPath='/opt/openrobots/share/example-robot-data'):
+    URDF_FILENAME = "kinton_arm.urdf"
+    URDF_SUBPATH = "/kinton_description/urdf/" + URDF_FILENAME
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
+    return robot
diff --git a/examples/kinton_flying.py b/examples/kinton_flying.py
new file mode 100644
index 0000000000000000000000000000000000000000..975a6fd8350235cd169093f0cf7bc43611af9e04
--- /dev/null
+++ b/examples/kinton_flying.py
@@ -0,0 +1,79 @@
+from crocoddyl import *
+import pinocchio as pin
+import numpy as np
+from crocoddyl.diagnostic import displayTrajectory
+
+# LOAD ROBOT
+robot = loadKinton()
+robot.initDisplay(loadModel=True)
+robot.display(robot.q0)
+
+robot.framesForwardKinematics(robot.q0)
+
+# DEFINE TARGET POSITION
+target_pos  = np.array([0,0,3])
+target_quat = pin.Quaternion(0, 0, 0, 1)
+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
+actModel = ActuationModelUAM(robot.model)
+
+# 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()
+
+
+stateWeights = np.array([0] * 3 + [500.] * 3 + [0.01] * (robot.model.nv - 2) + [10] * robot.model.nv)
+goalTrackingCost = CostModelFramePlacement(robot.model,
+                                           frame=robot.model.getFrameId(frameName),
+                                           ref=SE3ref,
+                                           nu =actModel.nu)
+xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=actModel.nu)
+uRegCost = CostModelControl(robot.model, nu=robot.model.nv-2)
+
+# Then let's add the running and terminal cost functions
+runningCostModel.addCost(name="pos", weight=1e-3, cost=goalTrackingCost)
+runningCostModel.addCost(name="regx", weight=1e-7, cost=xRegCost)
+runningCostModel.addCost(name="regu", weight=1e-7, cost=uRegCost)
+terminalCostModel.addCost(name="pos", weight=50, cost=goalTrackingCost)
+
+# DIFFERENTIAL ACTION MODEL
+runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))
+terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))
+
+# DEFINING THE SHOOTING PROBLEM & SOLVING
+
+# Defining the time duration for running action models and the terminal one
+dt = 1e-3
+runningModel.timeStep = dt
+
+# For this optimal control problem, we define 250 knots (or running action
+# models) plus a terminal knot
+T = 250
+q0 = [0., 0., 0., 0., 0., 0.]
+q0 = robot.model.referenceConfigurations["initial_pose"]
+
+x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])
+problem = ShootingProblem(x0, [runningModel] * T, terminalModel)
+
+# Creating the DDP solver for this OC problem, defining a logger
+ddp = SolverDDP(problem)
+ddp.callback = [CallbackDDPVerbose()]
+ddp.callback.append(CallbackDDPLogger())
+
+# Solving it with the DDP algorithm
+ddp.solve()
+
+displayTrajectory(robot, ddp.xs, runningModel.timeStep)
diff --git a/examples/notebooks/kinton_fixed_base.ipynb b/examples/notebooks/kinton_fixed_base.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..a5905634d6a2ef8914c18b5722e278e6ed8c1dd6
--- /dev/null
+++ b/examples/notebooks/kinton_fixed_base.ipynb
@@ -0,0 +1,1419 @@
+{
+ "cells": [
+  {
+   "cell_type": "code",
+   "execution_count": 1,
+   "metadata": {},
+   "outputs": [
+    {
+     "name": "stdout",
+     "output_type": "stream",
+     "text": [
+      "6\n"
+     ]
+    }
+   ],
+   "source": [
+    "from crocoddyl import *\n",
+    "import pinocchio as pin\n",
+    "import numpy as np\n",
+    "\n",
+    "robot = loadKintonArm()\n",
+    "robot.initDisplay(loadModel=True)\n",
+    "robot.display(robot.q0)\n",
+    "\n",
+    "robot.framesForwardKinematics(robot.q0)\n",
+    "\n",
+    "# Create a cost model per the running and terminal action model.\n",
+    "runningCostModel = CostModelSum(robot.model)\n",
+    "terminalCostModel = CostModelSum(robot.model)\n",
+    "\n",
+    "print robot.model.nv"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 2,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "target_pos  = np.array([-0.1,-0.05,-0.15])\n",
+    "target_quat = pin.Quaternion(.4, .02, -.5, .7)\n",
+    "target_quat.normalize()\n",
+    "\n",
+    "# Plot goal frame\n",
+    "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)\n",
+    "robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])\n",
+    "robot.viewer.gui.refresh()"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 3,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# Note that we need to include a cost model (i.e. set of cost functions) in\n",
+    "# order to fully define the action model for our optimal control problem.\n",
+    "# For this particular example, we formulate three running-cost functions:\n",
+    "# goal-tracking cost, state and control regularization; and one terminal-cost:\n",
+    "# goal cost. First, let's create the common cost functions\n",
+    "frameName = 'link6'\n",
+    "state = StatePinocchio(robot.model)\n",
+    "SE3ref = pin.SE3()\n",
+    "SE3ref.translation = target_pos.reshape(3,1)\n",
+    "SE3ref.rotation = target_quat.matrix()\n",
+    "\n",
+    "goalTrackingCost = CostModelFramePlacement(robot.model, nu=robot.model.nv, frame=robot.model.getFrameId(frameName), ref=SE3ref)\n",
+    "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=robot.model.nv)\n",
+    "uRegCost = CostModelControl(robot.model, nu=robot.model.nv)\n",
+    "\n",
+    "# Then let's add the running and terminal cost functions\n",
+    "runningCostModel.addCost(name=\"pos\", weight=1e-3, cost=goalTrackingCost)\n",
+    "runningCostModel.addCost(name=\"regx\", weight=1e-7, cost=xRegCost)\n",
+    "runningCostModel.addCost(name=\"regu\", weight=1e-7, cost=uRegCost)\n",
+    "terminalCostModel.addCost(name=\"pos\", weight=50, cost=goalTrackingCost)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 4,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/plain": [
+       "([array([0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.]),\n",
+       "  array([-8.56312177e-04,  1.89532152e-03,  2.73421184e-03,  1.40535055e-04,\n",
+       "         -6.80910601e-03, -1.47306350e-02, -8.56312177e-01,  1.89532152e+00,\n",
+       "          2.73421184e+00,  1.40535055e-01, -6.80910601e+00, -1.47306350e+01]),\n",
+       "  array([-2.54926553e-03,  5.12874409e-03,  7.81062478e-03, -3.01186931e-05,\n",
+       "         -1.90322663e-02, -4.14852078e-02, -1.69295335e+00,  3.23342257e+00,\n",
+       "          5.07641293e+00, -1.70653748e-01, -1.22231603e+01, -2.67545728e+01]),\n",
+       "  array([-5.08231018e-03,  9.22720244e-03,  1.48413991e-02, -8.04175234e-04,\n",
+       "         -3.54988967e-02, -7.79179637e-02, -2.53304466e+00,  4.09845835e+00,\n",
+       "          7.03077430e+00, -7.74056541e-01, -1.64666304e+01, -3.64327559e+01]),\n",
+       "  array([-8.46800128e-03,  1.37903845e-02,  2.34569133e-02, -2.35975061e-03,\n",
+       "         -5.52243122e-02, -1.22000964e-01, -3.38569110e+00,  4.56318206e+00,\n",
+       "          8.61551424e+00, -1.55557537e+00, -1.97254155e+01, -4.40830008e+01]),\n",
+       "  array([-1.27186474e-02,  1.84809680e-02,  3.33145786e-02, -4.79397616e-03,\n",
+       "         -7.73790286e-02, -1.71986456e-01, -4.25064615e+00,  4.69058353e+00,\n",
+       "          9.85766525e+00, -2.43422556e+00, -2.21547164e+01, -4.99854912e+01]),\n",
+       "  array([-1.78404033e-02,  2.30163561e-02,  4.41040294e-02, -8.14709277e-03,\n",
+       "         -1.01264181e-01, -2.26373762e-01, -5.12175590e+00,  4.53538811e+00,\n",
+       "          1.07894509e+01, -3.35311661e+00, -2.38851526e+01, -5.43873060e+01]),\n",
+       "  array([-2.38298841e-02,  2.71617013e-02,  5.55497401e-02, -1.24199321e-02,\n",
+       "         -1.26291684e-01, -2.83879975e-01, -5.98948076e+00,  4.14534516e+00,\n",
+       "          1.14457107e+01, -4.27283935e+00, -2.50275032e+01, -5.75062132e+01]),\n",
+       "  array([-3.06726033e-02,  3.07239957e-02,  6.74117742e-02, -1.75865554e-02,\n",
+       "         -1.51968056e-01, -3.43413880e-01, -6.84271922e+00,  3.56229443e+00,\n",
+       "          1.18620341e+01, -5.16662324e+00, -2.56763713e+01, -5.95339055e+01]),\n",
+       "  array([-3.83427059e-02,  3.35470230e-02,  7.94851689e-02, -2.36033530e-02,\n",
+       "         -1.77881070e-01, -4.04052690e-01, -7.67010261e+00,  2.82302730e+00,\n",
+       "          1.20733947e+01, -6.01679762e+00, -2.59130143e+01, -6.06388091e+01]),\n",
+       "  array([-4.68035939e-02,  3.55069954e-02,  9.15983289e-02, -3.04155662e-02,\n",
+       "         -2.03688603e-01, -4.65021251e-01, -8.46088799e+00,  1.95997236e+00,\n",
+       "          1.21131600e+01, -6.81221321e+00, -2.58075331e+01, -6.09685612e+01]),\n",
+       "  array([-5.60091391e-02,  3.65087333e-02,  1.03610720e-01, -3.79619363e-02,\n",
+       "         -2.29109180e-01, -5.25673474e-01, -9.20554513e+00,  1.00173792e+00,\n",
+       "          1.20123911e+01, -7.54637012e+00, -2.54205768e+01, -6.06522231e+01]),\n",
+       "  array([-6.59052492e-02,  3.64822755e-02,  1.15410099e-01, -4.61780004e-02,\n",
+       "         -2.53913861e-01, -5.85475750e-01, -9.89611015e+00, -2.64577972e-02,\n",
+       "          1.17993788e+01, -8.21606409e+00, -2.48046815e+01, -5.98022757e+01]),\n",
+       "  array([-7.64316113e-02,  3.53798340e-02,  1.26909472e-01, -5.49984119e-02,\n",
+       "         -2.77919200e-01, -6.43992178e-01, -1.05263621e+01, -1.10244147e+00,\n",
+       "          1.14993727e+01, -8.82041147e+00, -2.40053389e+01, -5.85164289e+01]),\n",
+       "  array([-8.75234771e-02,  3.31730321e-02,  1.38043940e-01, -6.43585617e-02,\n",
+       "         -3.00981066e-01, -7.00871445e-01, -1.10918658e+01, -2.20680192e+00,\n",
+       "          1.11344687e+01, -9.36014983e+00, -2.30618659e+01, -5.68792667e+01]),\n",
+       "  array([-9.91133938e-02,  2.98503805e-02,  1.48767566e-01, -7.41956993e-02,\n",
+       "         -3.22989193e-01, -7.55835190e-01, -1.15899167e+01, -3.32265166e+00,\n",
+       "          1.07236258e+01, -9.83713756e+00, -2.20081270e+01, -5.49637450e+01]),\n",
+       "  array([-1.11132809e-01,  2.54149615e-02,  1.59050350e-01, -8.44496956e-02,\n",
+       "         -3.43862344e-01, -8.08667742e-01, -1.20194151e+01, -4.43541893e+00,\n",
+       "          1.02827840e+01, -1.02539963e+01, -2.08731508e+01, -5.28325516e+01]),\n",
+       "  array([-1.23513502e-01,  1.98823017e-02,  1.68875407e-01, -9.50635507e-02,\n",
+       "         -3.63544010e-01, -8.59207080e-01, -1.23806934e+01, -5.53265979e+00,\n",
+       "          9.82505690e+00, -1.06138552e+01, -1.96816663e+01, -5.05393383e+01]),\n",
+       "  array([-1.36188819e-01,  1.32784184e-02,  1.78236385e-01, -1.05983717e-01,\n",
+       "         -3.81998590e-01, -9.07336913e-01, -1.26753164e+01, -6.60388340e+00,\n",
+       "          9.36097833e+00, -1.09201664e+01, -1.84545794e+01, -4.81298329e+01]),\n",
+       "  array([-1.49094686e-01,  5.63803259e-03,  1.87135165e-01, -1.17160289e-01,\n",
+       "         -3.99207991e-01, -9.52979751e-01, -1.29058673e+01, -7.64038576e+00,\n",
+       "          8.89877975e+00, -1.11765718e+01, -1.72094018e+01, -4.56428385e+01]),\n",
+       "  array([-1.62170422e-01, -2.99705683e-03,  1.95579848e-01, -1.28547092e-01,\n",
+       "         -4.15168633e-01, -9.96090877e-01, -1.30757358e+01, -8.63508942e+00,\n",
+       "          8.44468278e+00, -1.13868033e+01, -1.59606421e+01, -4.31111258e+01]),\n",
+       "  array([-1.75359335e-01, -1.25794448e-02,  2.03583039e-01, -1.40101702e-01,\n",
+       "         -4.29888797e-01, -1.03665310e+00, -1.31889131e+01, -9.58238800e+00,\n",
+       "          8.00319163e+00, -1.15546094e+01, -1.47201632e+01, -4.05622272e+01]),\n",
+       "  array([-1.88609140e-01, -2.30574403e-02,  2.11160414e-01, -1.51785399e-01,\n",
+       "         -4.43386307e-01, -1.07467224e+00, -1.32498049e+01, -1.04779954e+01,\n",
+       "          7.57737427e+00, -1.16836977e+01, -1.34975104e+01, -3.80191388e+01]),\n",
+       "  array([-2.01872203e-01, -3.43762410e-02,  2.18329538e-01, -1.63563090e-01,\n",
+       "         -4.55686519e-01, -1.11017318e+00, -1.32630632e+01, -1.13188007e+01,\n",
+       "          7.16912438e+00, -1.17776903e+01, -1.23002120e+01, -3.55009380e+01]),\n",
+       "  array([ -0.21510564,  -0.04647897,   0.22510894,  -0.17540318,\n",
+       "          -0.46682057,  -1.14319651, -13.23344193, -12.10272852,\n",
+       "           6.77939849, -11.84008895, -11.13405288, -33.02332443]),\n",
+       "  array([ -0.22827132,  -0.05930758,   0.23151736,  -0.18727743,\n",
+       "          -0.4768239 ,  -1.1737956 , -13.16567615, -12.82860748,\n",
+       "           6.40842551, -11.87424711, -10.00332469, -30.59909137]),\n",
+       "  array([ -0.24133571,  -0.07280362,   0.23757325,  -0.19916077,\n",
+       "          -0.48573495,  -1.20203413, -13.06438462, -13.4960463 ,\n",
+       "           6.0558876 , -11.8833484 ,  -8.91105036, -28.23853502]),\n",
+       "  array([ -0.2542697 ,  -0.08690894,   0.24329432,  -0.21103116,\n",
+       "          -0.49359413,  -1.22798394, -12.93399439, -14.10531885,\n",
+       "           5.72107287, -11.87039025,  -7.85918639, -25.94980885]),\n",
+       "  array([ -0.26704839,  -0.1015662 ,   0.24869732,  -0.22286934,\n",
+       "          -0.50044294,  -1.25172317, -12.77868549, -14.65725873,\n",
+       "           5.40300168, -11.83817235,  -6.84880291, -23.73922952]),\n",
+       "  array([ -0.27965074,  -0.11671936,   0.25379785,  -0.23465863,\n",
+       "          -0.50632318,  -1.27333471, -12.6023533 , -15.15316343,\n",
+       "           5.10052876, -11.78928931,  -5.88024295, -21.61154057]),\n",
+       "  array([ -0.29205932,  -0.13231407,   0.25861028,  -0.24638475,\n",
+       "          -0.51127644,  -1.29290485, -12.40858594, -15.59470826,\n",
+       "           4.81242403, -11.72612727,  -4.95326222, -19.57013972]),\n",
+       "  array([ -0.30425998,  -0.14829794,   0.26314771,  -0.25803562,\n",
+       "          -0.51534359,  -1.31052213, -12.20065427, -15.98386974,\n",
+       "           4.53743491, -11.65086397,  -4.06715096, -17.61727455]),\n",
+       "  array([ -0.31624149,  -0.1646208 ,   0.26742205,  -0.26960109,\n",
+       "          -0.51856443,  -1.32627634, -11.98151204, -16.32285807,\n",
+       "           4.27433311, -11.56547179,  -3.22083904, -15.75421143]),\n",
+       "  array([ -0.32799529,  -0.18123486,   0.27144399,  -0.28107281,\n",
+       "          -0.52097742,  -1.34025772, -11.7538038 , -16.61405829,\n",
+       "           4.02194851, -11.47172349,  -2.4129861 , -13.98138136]),\n",
+       "  array([ -0.33951517,  -0.19809484,   0.27522319,  -0.29244401,\n",
+       "          -0.52261948,  -1.35255622, -11.51987881, -16.85997941,\n",
+       "           3.77919261, -11.37120003,  -1.6420579 , -12.29850626]),\n",
+       "  array([ -0.35079698,  -0.21515805,   0.27876826,  -0.30370931,\n",
+       "          -0.52352587,  -1.36326093, -11.28180904, -17.06321082,\n",
+       "           3.54507366, -11.26530018,  -0.90639058, -10.70470859]),\n",
+       "  array([ -0.36183839,  -0.23238443,   0.28208697,  -0.31486456,\n",
+       "          -0.52373011,  -1.37245954, -11.04140998, -17.22638542,\n",
+       "           3.31870542, -11.15525131,  -0.20424393,  -9.19860674]),\n",
+       "  array([ -0.37263866,  -0.24973658,   0.28518628,  -0.32590669,\n",
+       "          -0.52326396,  -1.38023794, -10.80026286, -17.35214865,\n",
+       "           3.09931088, -11.04212114,   0.46615488,  -7.77839827]),\n",
+       "  array([ -0.38319839,  -0.26717972,   0.2880725 ,  -0.33683352,\n",
+       "          -0.52215738,  -1.38667987, -10.55973759, -17.44313278,\n",
+       "           2.88622244, -10.92682999,   1.10657594,  -6.44193265]),\n",
+       "  array([ -0.39351941,  -0.28468165,   0.29075138,  -0.34764368,\n",
+       "          -0.52043862,  -1.39186665, -10.32101545, -17.50193583,\n",
+       "           2.67887935, -10.81016323,   1.71875861,  -5.18677509]),\n",
+       "  array([ -0.40360452,  -0.30221276,   0.2932282 ,  -0.35833646,\n",
+       "          -0.51813423,  -1.39587691, -10.08511111, -17.53110454,\n",
+       "           2.4768233 , -10.69278365,   2.30438977,  -4.01026241]),\n",
+       "  array([ -0.41345741,  -0.31974588,   0.29550789,  -0.36891171,\n",
+       "          -0.51526914,  -1.39878646,  -9.85289355, -17.53312077,\n",
+       "           2.27969282, -10.57524351,   2.86508752,  -2.90955215]),\n",
+       "  array([ -0.42308252,  -0.33725627,   0.29759511,  -0.3793697 ,\n",
+       "          -0.51186675,  -1.40066813,  -9.62510553, -17.51039097,\n",
+       "           2.08721677, -10.45799618,   3.40238942,  -1.88166562]),\n",
+       "  array([ -0.4324849 ,  -0.35472151,   0.29949432,  -0.38971111,\n",
+       "          -0.50794901,  -1.40159165,  -9.40238156, -17.46523805,\n",
+       "           1.8992075 , -10.34140712,   3.9177446 ,  -0.92352558]),\n",
+       "  array([ -0.44167016,  -0.3721214 ,   0.30120987,  -0.39993687,\n",
+       "          -0.5035365 ,  -1.40162364,  -9.18526418, -17.39989559,\n",
+       "           1.71555366, -10.22576415,   4.41250911,  -0.03198926]),\n",
+       "  array([ -0.45064438,  -0.38943791,   0.30274609,  -0.41004816,\n",
+       "          -0.49864856,  -1.40082752,  -8.97421853, -17.31650363,\n",
+       "           1.53621308, -10.11128696,   4.88794389,   0.79612301]),\n",
+       "  array([ -0.45941403,  -0.40665501,   0.30410729,  -0.4200463 ,\n",
+       "          -0.49330334,  -1.39926351,  -8.76964528, -17.21710619,\n",
+       "           1.36120565,  -9.99813587,   5.3452149 ,   1.56400283]),\n",
+       "  array([ -0.46798592,  -0.42375866,   0.3052979 ,  -0.42993272,\n",
+       "          -0.48751795,  -1.39698868,  -8.57189195, -17.10364986,\n",
+       "           1.19060638,  -9.88641969,   5.785395  ,   2.27483231]),\n",
+       "  array([ -0.47636718,  -0.44073664,   0.30632244,  -0.43970892,\n",
+       "          -0.48130848,  -1.39405692,  -8.3812626 , -16.9779835 ,\n",
+       "           1.02453858,  -9.7762029 ,   6.20946714,   2.93176567]),\n",
+       "  array([ -0.48456521,  -0.4575785 ,   0.3071856 ,  -0.44937643,\n",
+       "          -0.47469015,  -1.390519  ,  -8.19802619, -16.84185876,\n",
+       "           0.86316738,  -9.66751201,   6.61832861,   3.5379136 ]),\n",
+       "  array([ -0.49258763,  -0.47427543,   0.3078923 ,  -0.45893677,\n",
+       "          -0.46767735,  -1.38642267,  -8.02242347, -16.69693127,\n",
+       "           0.70669335,  -9.56034122,   7.01279599,   4.09633016]),\n",
+       "  array([ -0.50044231,  -0.4908202 ,   0.30844764,  -0.46839143,\n",
+       "          -0.46028374,  -1.38181267,  -7.85467273, -16.54476232,\n",
+       "           0.55534643,  -9.45465741,   7.39361069,   4.61000189]),\n",
+       "  array([ -0.50813728,  -0.50720702,   0.30885702,  -0.47774183,\n",
+       "          -0.4525223 ,  -1.37673083,  -7.6949744 , -16.38682098,\n",
+       "           0.40938011,  -9.35040457,   7.76144476,   5.08183887]),\n",
+       "  array([ -0.51568079,  -0.5234315 ,   0.30912609,  -0.48698934,\n",
+       "          -0.44440539,  -1.37121616,  -7.54351458, -16.22448659,\n",
+       "           0.26906582,  -9.24750761,   8.11690684,   5.5146676 ]),\n",
+       "  array([ -0.52308126,  -0.53949056,   0.30926078,  -0.49613522,\n",
+       "          -0.43594484,  -1.36530494,  -7.40046775, -16.05905138,\n",
+       "           0.13468759,  -9.14587574,   8.46054817,   5.91122542]),\n",
+       "  array([-5.30347261e-01, -5.55382279e-01,  3.09267313e-01, -5.05180622e-01,\n",
+       "         -4.27151976e-01, -1.35903078e+00, -7.26599866e+00, -1.58917233e+01,\n",
+       "          6.53699818e-03, -9.04540539e+00,  8.79286848e+00,  6.27415632e+00]),\n",
+       "  array([ -0.53748752,  -0.57110591,   0.30915222,  -0.51412661,\n",
+       "          -0.41803765,  -1.35242478,  -7.14026352, -15.72362899,\n",
+       "          -0.11509169,  -8.94598278,   9.1143217 ,   6.60600793]),\n",
+       "  array([ -0.54451093,  -0.58666173,   0.30892232,  -0.52297409,\n",
+       "          -0.40861233,  -1.34551555,  -7.02341061, -15.55581677,\n",
+       "          -0.22990601,  -8.84748612,   9.4253214 ,   6.90922956]),\n",
+       "  array([ -0.55142652,  -0.60205098,   0.3085847 ,  -0.53172388,\n",
+       "          -0.39888609,  -1.33832937,  -6.91558037, -15.38925966,\n",
+       "          -0.33761958,  -8.7497876 ,   9.72624596,   7.18617115]),\n",
+       "  array([ -0.55824342,  -0.61727584,   0.30814674,  -0.54037663,\n",
+       "          -0.38886864,  -1.33089029,  -6.81690514, -15.22485838,\n",
+       "          -0.43795602,  -8.65275509,  10.01744331,   7.439083  ]),\n",
+       "  array([ -0.56497093,  -0.63233929,   0.30761609,  -0.54893289,\n",
+       "          -0.37856941,  -1.32322018,  -6.72750852, -15.06344434,\n",
+       "          -0.53065258,  -8.55625368,  10.29923541,   7.67011608]),\n",
+       "  array([ -0.57161843,  -0.64724507,   0.30700062,  -0.55739303,\n",
+       "          -0.36799749,  -1.31533885,  -6.64750444, -14.90578262,\n",
+       "          -0.61546344,  -8.46014706,  10.57192223,   7.88132295]),\n",
+       "  array([ -0.57819543,  -0.66199764,   0.30630846,  -0.56575733,\n",
+       "          -0.3571617 ,  -1.30726419,  -6.57699617, -14.75257477,\n",
+       "          -0.69216269,  -8.36429872,  10.83578536,   8.07465908]),\n",
+       "  array([ -0.5847115 ,  -0.67660211,   0.30554791,  -0.57402591,\n",
+       "          -0.34607061,  -1.29901221,  -6.51607506, -14.60446164,\n",
+       "          -0.76054691,  -8.26857311,  11.09109123,   8.25198457]),\n",
+       "  array([ -0.59117632,  -0.69106413,   0.30472748,  -0.58219874,\n",
+       "          -0.33473252,  -1.29059714,  -6.46481929, -14.46202614,\n",
+       "          -0.82043742,  -8.1728367 ,  11.33809393,   8.4150661 ]),\n",
+       "  array([ -0.59759962,  -0.70538993,   0.30385579,  -0.5902757 ,\n",
+       "          -0.32315548,  -1.28203156,  -6.42329262, -14.32579581,\n",
+       "          -0.8716822 ,  -8.07695892,  11.57703762,   8.56557919]),\n",
+       "  array([ -0.60399116,  -0.71958617,   0.30294164,  -0.59825652,\n",
+       "          -0.31134732,  -1.27332645,  -6.39154306, -14.19624542,\n",
+       "          -0.91415738,  -7.98081308,  11.80815858,   8.70511053]),\n",
+       "  array([ -0.61036076,  -0.73365997,   0.30199387,  -0.60614079,\n",
+       "          -0.29931563,  -1.26449129,  -6.36960168, -14.07379943,\n",
+       "          -0.94776843,  -7.88427728,  12.03168691,   8.83516047]),\n",
+       "  array([ -0.61671824,  -0.74761881,   0.30102142,  -0.61392803,\n",
+       "          -0.28706778,  -1.25553415,  -6.3574815 , -13.95883437,\n",
+       "          -0.97245098,  -7.78723516,  12.24784788,   8.95714568]),\n",
+       "  array([ -0.62307342,  -0.76147049,   0.30003325,  -0.6216176 ,\n",
+       "          -0.27461092,  -1.24646175,  -6.3551764 , -13.85168117,\n",
+       "          -0.98817127,  -7.6895768 ,  12.45686299,   9.07240169]),\n",
+       "  array([ -0.62943608,  -0.77522312,   0.29903832,  -0.6292088 ,\n",
+       "          -0.26195197,  -1.23727956,  -6.36266027, -13.75262739,\n",
+       "          -0.99492633,  -7.59119936,  12.65895071,   9.18218558]),\n",
+       "  array([ -0.63581597,  -0.78888504,   0.29804558,  -0.63670081,\n",
+       "          -0.24909764,  -1.22799188,  -6.37988614, -13.66191935,\n",
+       "          -0.99274382,  -7.49200791,  12.85432699,   9.28767864]),\n",
+       "  array([ -0.64222275,  -0.8024648 ,   0.2970639 ,  -0.64409273,\n",
+       "          -0.23605444,  -1.21860189,  -6.40678561, -13.57976429,\n",
+       "          -0.98168158,  -7.39191608,  13.04320548,   9.38998897]),\n",
+       "  array([ -0.64866602,  -0.81597113,   0.29610207,  -0.65138357,\n",
+       "          -0.22282864,  -1.20911174,  -6.44326823, -13.50633234,\n",
+       "          -0.96182695,  -7.29084673,  13.22579764,   9.49015406]),\n",
+       "  array([ -0.65515524,  -0.82941289,   0.29516877,  -0.65857231,\n",
+       "          -0.20942633,  -1.19952259,  -6.48922118, -13.44175848,\n",
+       "          -0.93329584,  -7.18873261,  13.40231249,   9.58914333]),\n",
+       "  array([ -0.66169975,  -0.84279904,   0.29427254,  -0.66565782,\n",
+       "          -0.19585337,  -1.18983473,  -6.54450888, -13.38614451,\n",
+       "          -0.89623163,  -7.08551695,  13.57295639,   9.68786058]),\n",
+       "  array([ -0.66830872,  -0.8561386 ,   0.29342174,  -0.67263898,\n",
+       "          -0.18211544,  -1.18004759,  -6.60897287, -13.33956084,\n",
+       "          -0.8508039 ,  -6.98115404,  13.73793249,   9.78714635]),\n",
+       "  array([ -0.67499115,  -0.86944064,   0.29262453,  -0.67951459,\n",
+       "          -0.168218  ,  -1.17015981,  -6.68243165, -13.30204826,\n",
+       "          -0.79720702,  -6.87560983,  13.8974402 ,   9.88778023]),\n",
+       "  array([ -0.68175583,  -0.88271426,   0.29188887,  -0.68628345,\n",
+       "          -0.15416632,  -1.16016932,  -6.76468059, -13.27361976,\n",
+       "          -0.73565866,  -6.76886237,  14.05167446,   9.990483  ]),\n",
+       "  array([ -0.68861133,  -0.89596853,   0.29122247,  -0.69294435,\n",
+       "          -0.1399655 ,  -1.15007341,  -6.85549197, -13.25426213,\n",
+       "          -0.66639828,  -6.66090239,  14.20082496,  10.09591868]),\n",
+       "  array([ -0.69556594,  -0.90921246,   0.29063279,  -0.69949609,\n",
+       "          -0.12562042,  -1.13986871,  -6.95461487, -13.24393758,\n",
+       "          -0.58968554,  -6.5517337 ,  14.34507534,  10.20469651]),\n",
+       "  array([ -0.70262772,  -0.92245505,   0.29012699,  -0.70593746,\n",
+       "          -0.11113582,  -1.12955134,  -7.06177522, -13.24258537,\n",
+       "          -0.50579883,  -6.44137369,  14.48460221,  10.31737269]),\n",
+       "  array([ -0.70980439,  -0.93570517,   0.28971195,  -0.71226731,\n",
+       "          -0.09651625,  -1.11911688,  -7.17667564, -13.25012325,\n",
+       "          -0.41503378,  -6.32985377,  14.61957428,  10.434452  ]),\n",
+       "  array([ -0.71710339,  -0.94897162,   0.28939425,  -0.71848453,\n",
+       "          -0.0817661 ,  -1.1085605 ,  -7.29899532, -13.2664489 ,\n",
+       "          -0.3177019 ,  -6.21721975,  14.75015135,  10.5563893 ]),\n",
+       "  array([ -0.72453178,  -0.96226306,   0.28918012,  -0.72458807,\n",
+       "          -0.06688961,  -1.0978769 ,  -7.42838975, -13.29144137,\n",
+       "          -0.21412938,  -6.10353226,  14.87648338,  10.68359081]),\n",
+       "  array([ -0.73209627,  -0.97558802,   0.28907547,  -0.73057693,\n",
+       "          -0.0518909 ,  -1.08706049,  -7.5644903 , -13.32496232,\n",
+       "          -0.10465604,  -5.98886722,  14.99870949,  10.81641516]),\n",
+       "  array([-7.39803171e-01, -9.88954882e-01,  2.89085833e-01, -7.36450249e-01,\n",
+       "         -3.67739462e-02, -1.07610531e+00, -7.70690368e+00, -1.33668573e+01,\n",
+       "          1.03654748e-02, -5.87331615e+00,  1.51169570e+01,  1.09551743e+01]),\n",
+       "  array([ -0.74765838,  -1.00237184,   0.2892164 ,  -0.74220724,\n",
+       "          -0.02154261,  -1.06500518,  -7.85521117, -13.41695703,\n",
+       "           0.13057031,  -5.75698669,  15.23134061,  11.10013423]),\n",
+       "  array([-7.55667350e-01, -1.01584692e+00,  2.89471985e-01, -7.47847239e-01,\n",
+       "         -6.20064425e-03, -1.05375367e+00, -8.00896769e+00, -1.34750782e+01,\n",
+       "          2.55581661e-01, -5.64000293e+00,  1.53419613e+01,  1.12515153e+01]),\n",
+       "  array([-7.63835051e-01, -1.02938794e+00,  2.89856995e-01, -7.53369745e-01,\n",
+       "          9.24826154e-03, -1.04234417e+00, -8.16770052e+00, -1.35410248e+01,\n",
+       "          3.85010746e-01, -5.52250593e+00,  1.54489058e+01,  1.14094924e+01]),\n",
+       "  array([ -0.77216596,  -1.04300253,   0.29037545,  -0.7587744 ,\n",
+       "           0.02480051,  -1.03076998,  -8.33090785, -13.61458907,\n",
+       "           0.51845642,  -5.40465411,  15.5522455 ,  11.57419512]),\n",
+       "  array([ -0.78066402,  -1.05669808,   0.29103096,  -0.76406102,\n",
+       "           0.04045254,  -1.01902427,  -8.49805702, -13.69555202,\n",
+       "           0.65550439,  -5.28662374,  15.65203609,  11.74570724]),\n",
+       "  array([ -0.7893326 ,  -1.07048177,   0.29182668,  -0.76922963,\n",
+       "           0.05620086,  -1.0071002 ,  -8.6685824 , -13.78368461,\n",
+       "           0.79572601,  -5.16860944,  15.74831676,  11.92406621]),\n",
+       "  array([ -0.79817448,  -1.08436052,   0.29276536,  -0.77428046,\n",
+       "           0.07204197,  -0.99499094,  -8.84188304, -13.87874825,\n",
+       "           0.93867661,  -5.05082459,  15.84110985,  12.1092623 ]),\n",
+       "  array([ -0.8071918 ,  -1.09834101,   0.29384925,  -0.77921396,\n",
+       "           0.08797239,  -0.9826897 ,  -9.01731994, -13.98049544,\n",
+       "           1.08389336,  -4.93350187,  15.93042051,  12.30123763]),\n",
+       "  array([ -0.81638601,  -1.11242968,   0.29508014,  -0.78403085,\n",
+       "           0.10398863,  -0.97018982,  -9.19421298, -14.08867029,\n",
+       "           1.23089264,  -4.81689369,  16.0162365 ,  12.49988475]),\n",
+       "  array([ -0.82575785,  -1.12663269,   0.29645931,  -0.78873212,\n",
+       "           0.12008715,  -0.95748477,  -9.37183768, -14.20300897,\n",
+       "           1.37916686,  -4.70127256,  16.09852823,  12.70504523]),\n",
+       "  array([ -0.83530727,  -1.14095593,   0.29798749,  -0.79331906,\n",
+       "           0.1362644 ,  -0.94456827,  -9.54942153, -14.32323999,\n",
+       "           1.52818082,  -4.58693149,  16.17724894,  12.91650789]),\n",
+       "  array([ -0.84503341,  -1.15540502,   0.29966486,  -0.79779324,\n",
+       "           0.15251674,  -0.93143426,  -9.72614024, -14.44908447,\n",
+       "           1.67736753,  -4.4741842 ,  16.25233514,  13.13400702]),\n",
+       "  array([ -0.85493453,  -1.16998527,   0.30149098,  -0.80215661,\n",
+       "           0.16884045,  -0.91807704,  -9.9011138 , -14.58025626,\n",
+       "           1.82612363,  -4.36336523,  16.32370724,  13.35722043]),\n",
+       "  array([ -0.86500793,  -1.18470173,   0.30346479,  -0.80641144,\n",
+       "           0.18523172,  -0.90449127, -10.07340252, -14.71646196,\n",
+       "           1.97380437,  -4.25482988,  16.39127052,  13.58576756]),\n",
+       "  array([ -0.87524993,  -1.19955913,   0.30558451,  -0.81056039,\n",
+       "           0.20168663,  -0.89067206, -10.24200319, -14.85740083,\n",
+       "           2.11971834,  -4.14895382,  16.45491622,  13.8192076 ]),\n",
+       "  array([ -0.88565578,  -1.2145619 ,   0.30784763,  -0.81460652,\n",
+       "           0.21820116,  -0.87661503, -10.40584554, -15.00276464,\n",
+       "           2.26312208,  -4.04613254,  16.51452315,  14.05703782]),\n",
+       "  array([ -0.89621957,  -1.22971414,   0.31025084,  -0.8185533 ,\n",
+       "           0.23477112,  -0.86231633, -10.56378922, -15.15223736,\n",
+       "           2.4032147 ,  -3.9467803 ,  16.56995935,  14.29869225]),\n",
+       "  array([ -0.90693419,  -1.24501963,   0.31278998,  -0.82240463,\n",
+       "           0.2513922 ,  -0.84777279, -10.71462159, -15.30549477,\n",
+       "           2.53913287,  -3.85132866,  16.62108426,  14.5435408 ]),\n",
+       "  array([ -0.91779125,  -1.26048184,   0.31545992,  -0.82616486,\n",
+       "           0.26805995,  -0.8329819 , -10.85705664, -15.46220406,\n",
+       "           2.66994647,  -3.76022451,  16.66775103,  14.79088897]),\n",
+       "  array([ -0.92878098,  -1.27610386,   0.31825458,  -0.82983878,\n",
+       "           0.28476976,  -0.81794193, -10.98973552, -15.62202322,\n",
+       "           2.79465524,  -3.67392749,  16.70980925,  15.03997855]),\n",
+       "  array([ -0.93989221,  -1.29188846,   0.32116676,  -0.83343169,\n",
+       "           0.30151687,  -0.80265194, -11.11122896, -15.78460053,\n",
+       "           2.91218705,  -3.59290666,  16.74710782,  15.28998925]),\n",
+       "  array([ -0.95111225,  -1.30783803,   0.32418816,  -0.83694933,\n",
+       "           0.31829637,  -0.78711189, -11.22004232, -15.94957391,\n",
+       "           3.02139823,  -3.51763649,  16.77949816,  15.54004168]),\n",
+       "  array([ -0.96242688,  -1.3239546 ,   0.32730924,  -0.84039792,\n",
+       "           0.3351032 ,  -0.77132269, -11.31462365, -16.1165704 ,\n",
+       "           3.12107664,  -3.44859198,  16.8068375 ,  15.78920187]),\n",
+       "  array([ -0.97382025,  -1.34023981,   0.33051919,  -0.84378416,\n",
+       "           0.3519322 ,  -0.75528621, -11.39337534, -16.28520561,\n",
+       "           3.20994822,  -3.38624303,  16.82899234,  16.03648757]),\n",
+       "  array([ -0.98527492,  -1.35669489,   0.33380588,  -0.84711521,\n",
+       "           0.36877804,  -0.73900533, -11.45467004, -16.45508338,\n",
+       "           3.2866876 ,  -3.33104788,  16.84584196,  16.28087642]),\n",
+       "  array([ -0.99677179,  -1.37332069,   0.33715581,  -0.85039865,\n",
+       "           0.38563532,  -0.72248401, -11.49687118, -16.62579552,\n",
+       "           3.34993357,  -3.28344581,  16.85728188,  16.52131626]),\n",
+       "  array([ -1.00829015,  -1.39011761,   0.34055412,  -0.8536425 ,\n",
+       "           0.40249855,  -0.70572728, -11.51835857, -16.79692187,\n",
+       "           3.39830993,  -3.24384918,  16.86322715,  16.75673763]),\n",
+       "  array([ -1.01980771,  -1.40708564,   0.34398457,  -0.85685514,\n",
+       "           0.41936216,  -0.68874121, -11.51755923, -16.96803066,\n",
+       "           3.43045216,  -3.21263479,  16.86361551,  16.9860682 ]),\n",
+       "  array([ -1.03130069,  -1.42422432,   0.34742961,  -0.86004527,\n",
+       "           0.43622057,  -0.67153296, -11.49298346, -17.13867923,\n",
+       "           3.4450402 ,  -3.19013505,  16.85841006,  17.20824929]),\n",
+       "  array([ -1.04274396,  -1.44153273,   0.35087045,  -0.8632219 ,\n",
+       "           0.45306817,  -0.6541107 , -11.44326564, -17.30841513,\n",
+       "           3.44083697,  -3.17662891,  16.84760165,  17.42225374]),\n",
+       "  array([ -1.05411117,  -1.45900951,   0.35428718,  -0.86639424,\n",
+       "           0.46989938,  -0.6364836 , -11.36720908, -17.47677782,\n",
+       "           3.41673229,  -3.17233319,  16.83121066,  17.62710492]),\n",
+       "  array([ -1.065375  ,  -1.47665281,   0.35765897,  -0.86957163,\n",
+       "           0.48670867,  -0.6186617 , -11.26383348, -17.64330072,\n",
+       "           3.37179088,  -3.17739441,  16.80928813,  17.82189591]),\n",
+       "  array([ -1.07650743,  -1.49446033,   0.36096427,  -0.87276351,\n",
+       "           0.50349059,  -0.60065589, -11.13242342, -17.80751385,\n",
+       "           3.30530282,  -3.19188172,  16.78191635,  18.00580825]),\n",
+       "  array([ -1.08748   ,  -1.51242927,   0.36418111,  -0.87597929,\n",
+       "           0.5202398 ,  -0.58247777, -10.97257543, -17.9689469 ,\n",
+       "           3.21683423,  -3.21578135,  16.74920855,  18.17812899]),\n",
+       "  array([ -1.09826424,  -1.53055641,   0.36728738,  -0.87922829,\n",
+       "           0.53695111,  -0.5641395 , -10.78424102, -18.12713283,\n",
+       "           3.10627521,  -3.24899287,  16.71130802,  18.33826537]),\n",
+       "  array([ -1.108832  ,  -1.54883802,   0.37026127,  -0.88251961,\n",
+       "           0.55361949,  -0.54565374, -10.56776264, -18.28161168,\n",
+       "           2.97388186,  -3.29132773,  16.66838638,  18.48575592]),\n",
+       "  array([ -1.1191559 ,  -1.56726995,   0.37308157,  -0.88586212,\n",
+       "           0.57024013,  -0.52703347, -10.32389935, -18.43193482,\n",
+       "           2.8203087 ,  -3.34251034,  16.62064121,  18.62027732]),\n",
+       "  array([ -1.12920974,  -1.58584762,   0.3757282 ,  -0.88926431,\n",
+       "           0.58680843,  -0.50829182, -10.05383925, -18.57766927,\n",
+       "           2.64662803,  -3.4021817 ,  16.568293  ,  18.74164654]),\n",
+       "  array([ -1.13896894,  -1.60456602,   0.37818254,  -0.89273421,\n",
+       "           0.60332001,  -0.489442  ,  -9.75919604, -18.71840214,\n",
+       "           2.45433279,  -3.4699056 ,  16.51158156,  18.84981797]),\n",
+       "  array([ -1.14841093,  -1.62341977,   0.38042786,  -0.89627939,\n",
+       "           0.61977077,  -0.47049713,  -9.44198757, -18.85374498,\n",
+       "           2.24532042,  -3.54517708,  16.45076195,  18.94487593]),\n",
+       "  array([ -1.15751552,  -1.64240311,   0.38244971,  -0.89990682,\n",
+       "           0.63615687,  -0.4514701 ,  -9.1045957 , -18.98333792,\n",
+       "           2.02185592,  -3.62743262,  16.38610011,  19.02702317]),\n",
+       "  array([ -1.16626523,  -1.66150996,   0.38423623,  -0.90362288,\n",
+       "           0.65247474,  -0.43237354,  -8.74970755, -19.10685358,\n",
+       "           1.78651381,  -3.71606143,  16.31786815,  19.09656648]),\n",
+       "  array([ -1.17464547,  -1.68073396,   0.38577833,  -0.9074333 ,\n",
+       "           0.66872108,  -0.41321964,  -8.38023998, -19.22400046,\n",
+       "           1.54210032,  -3.810417  ,  16.24633974,  19.15390072]),\n",
+       "  array([ -1.18264472,  -1.70006849,   0.38706988,  -0.91134313,\n",
+       "           0.68489286,  -0.39402014,  -7.99925041, -19.33452593,\n",
+       "           1.29155856,  -3.90982793,  16.1717854 ,  19.19949292]),\n",
+       "  array([ -1.19025456,  -1.71950671,   0.38810775,  -0.91535674,\n",
+       "           0.70098733,  -0.37478628,  -7.60983853, -19.43821861,\n",
+       "           1.0378616 ,  -4.01360743,  16.09446813,  19.23386774]),\n",
+       "  array([ -1.1974696 ,  -1.73904162,   0.38889165,  -0.9194778 ,\n",
+       "           0.71700197,  -0.35552868,  -7.21504457, -19.5349101 ,\n",
+       "           0.78389951,  -4.12106075,  16.01463933,  19.25759585]),\n",
+       "  array([ -1.20428735,  -1.75866609,   0.38942401,  -0.92370929,\n",
+       "           0.73293451,  -0.33625739,  -6.81775056, -19.62447611,\n",
+       "           0.53236778,  -4.23149029,  15.93253531,  19.2712858 ]),\n",
+       "  array([ -1.21070795,  -1.77837293,   0.38970968,  -0.92805348,\n",
+       "           0.74878288,  -0.31698181,  -6.42059105, -19.706837  ,\n",
+       "           0.28566501,  -4.34419857,  15.84837446,  19.27558001]),\n",
+       "  array([ -1.21673382,  -1.79815489,   0.38975549,  -0.93251197,\n",
+       "           0.76454524,  -0.29771066,  -6.02587943, -19.78195756,\n",
+       "           0.04580761,  -4.45848952,  15.76235521,  19.27115448]),\n",
+       "  array([ -1.22236938,  -1.81800473,   0.38956985,  -0.93708564,\n",
+       "           0.78021989,  -0.27845194,  -5.63555483, -19.84984636,\n",
+       "          -0.1856317 ,  -4.57366904,  15.67465492,  19.25872159]),\n",
+       "  array([ -1.22762053,  -1.83791529,   0.3891623 ,  -0.94177469,\n",
+       "           0.79580532,  -0.2592129 ,  -5.25115301, -19.91055441,\n",
+       "          -0.40755674,  -4.68904599,  15.58542974,  19.23903459]),\n",
+       "  array([ -1.23249434,  -1.85787946,   0.38854295,  -0.94657862,\n",
+       "           0.81130014,  -0.24000001,  -4.87380241, -19.96417331,\n",
+       "          -0.61934952,  -4.80393471,  15.49481548,  19.21289229]),\n",
+       "  array([ -1.23699858,  -1.87789029,   0.38772211,  -0.95149628,\n",
+       "           0.82670307,  -0.22081887,  -4.5042444 , -20.01083296,\n",
+       "          -0.82084119,  -4.91766001,  15.40292944,  19.18114228]),\n",
+       "  array([ -1.24114145,  -1.89794099,   0.38670985,  -0.95652585,\n",
+       "           0.84201294,  -0.20167419,  -4.14287467, -20.05069859,\n",
+       "          -1.01225547,  -5.02956527,  15.30987311,  19.14468112]),\n",
+       "  array([ -1.24493125,  -1.91802496,   0.38551572,  -0.96166487,\n",
+       "           0.85722867,  -0.18256974,  -3.78980067, -20.0839675 ,\n",
+       "          -1.19413068,  -5.1390233 ,  15.21573544,  19.1044503 ]),\n",
+       "  array([ -1.24837616,  -1.93813583,   0.38414849,  -0.96691032,\n",
+       "           0.87234927,  -0.16350831,  -3.44490913, -20.11086514,\n",
+       "          -1.36722804,  -5.24544971,  15.12059665,  19.06142734]),\n",
+       "  array([ -1.2514841 ,  -1.95826747,   0.38261606,  -0.97225864,\n",
+       "           0.8873738 ,  -0.1444917 ,  -3.10793712, -20.13164088,\n",
+       "          -1.53243505,  -5.34831717,  15.02453213,  19.0166119 ]),\n",
+       "  array([ -1.25426264,  -1.97841403,   0.38092538,  -0.97770581,\n",
+       "           0.90230142,  -0.12552069,  -2.77854031, -20.14656341,\n",
+       "          -1.69067268,  -5.44716933,  14.92761622,  18.97100742]),\n",
+       "  array([ -1.25671899,  -1.99856995,   0.37908257,  -0.98324744,\n",
+       "           0.91713134,  -0.10659509,  -2.45635351, -20.1559159 ,\n",
+       "          -1.84281361,  -5.54163269,  14.82992569,  18.92559948]),\n",
+       "  array([ -1.25886003,  -2.01872994,   0.37709295,  -0.98887887,\n",
+       "           0.93186289,  -0.08771376,  -2.14103949, -20.15999097,\n",
+       "          -1.9896174 ,  -5.63142495,  14.73154248,  18.8813322 ]),\n",
+       "  array([ -1.26069236,  -2.03888902,   0.37496127,  -0.99459523,\n",
+       "           0.94649544,  -0.06887467,  -1.83232414, -20.15908584,\n",
+       "          -2.13168562,  -5.71635894,  14.63255587,  18.83908447]),\n",
+       "  array([ -1.26222238,  -2.05904252,   0.37269183,  -1.00039157,\n",
+       "           0.96102851,  -0.05007503,  -1.53001768, -20.15349756,\n",
+       "          -2.26943774,  -5.7963416 ,  14.53306378,  18.79964764]),\n",
+       "  array([ -1.2634564 ,  -2.07918604,   0.37028872,  -1.00626294,\n",
+       "           0.97546168,  -0.03131132,  -1.23402265, -20.14351867,\n",
+       "          -2.40310664,  -5.87136831,  14.43317325,  18.76370626]),\n",
+       "  array([-1.26440073e+00, -2.09931547e+00,  3.67755973e-01, -1.01220445e+00,\n",
+       "          9.89794680e-01, -1.25794977e-02, -9.44331072e-01, -2.01294334e+01,\n",
+       "         -2.53275045e+00, -5.94151295e+00,  1.43330003e+01,  1.87318229e+01]),\n",
+       "  array([-1.26506174e+00, -2.11942699e+00,  3.65097696e-01, -1.01821136e+00,\n",
+       "          1.00402735e+00,  6.12493056e-03, -6.61013126e-01, -2.01115143e+01,\n",
+       "         -2.65827691e+00, -6.00691509e+00,  1.42326691e+01,  1.87044283e+01]),\n",
+       "  array([ -1.26544594,  -2.13951701,   0.36231822,  -1.02427913,\n",
+       "           1.01815966,   0.02480675,  -0.38420035, -20.09001993,\n",
+       "          -2.77947572,  -6.06776526,  14.13231072,  18.68181609]),\n",
+       "  array([ -1.26556001,  -2.1595822 ,   0.35942217,  -1.03040342,\n",
+       "           1.03219172,   0.04347089,  -0.11406597, -20.06519276,\n",
+       "          -2.89605471,  -6.12428974,  14.03206177,  18.66414403]),\n",
+       "  array([ -1.26541081,  -2.17961946,   0.35641449,  -1.03658015,\n",
+       "           1.04612378,   0.06212233,   0.14919527, -20.03725823,\n",
+       "          -3.00767606,  -6.1767359 ,  13.93206243,  18.65143881]),\n",
+       "  array([ -1.26500543,  -2.19962588,   0.3533005 ,  -1.04280551,\n",
+       "           1.05995624,   0.08076594,   0.40538612, -20.00642415,\n",
+       "          -3.11398983,  -6.22535906,  13.83245488,  18.64360584]),\n",
+       "  array([ -1.2643511 ,  -2.21959876,   0.35008584,  -1.04907592,\n",
+       "           1.07368962,   0.09940638,   0.65432327, -19.97288092,\n",
+       "          -3.21466262,  -6.27041147,  13.73338158,  18.64044195]),\n",
+       "  array([ -1.26345525,  -2.23953556,   0.34677644,  -1.05538806,\n",
+       "           1.0873246 ,   0.11804803,   0.89585072, -19.93680205,\n",
+       "          -3.3094005 ,  -6.31213366,  13.63498368,  18.6416506 ]),\n",
+       "  array([ -1.2623254 ,  -2.25943391,   0.34337847,  -1.06173881,\n",
+       "           1.100862  ,   0.13669489,   1.12984965, -19.8983452 ,\n",
+       "          -3.39796566,  -6.35074834,  13.53739967,  18.64685834]),\n",
+       "  array([ -1.26096916,  -2.27929156,   0.33989828,  -1.06812526,\n",
+       "           1.11430277,   0.15535052,   1.3562449 , -19.85765344,\n",
+       "          -3.48018701,  -6.38645661,  13.44076412,  18.65563192]),\n",
+       "  array([ -1.25939415,  -2.29910642,   0.33634232,  -1.0745447 ,\n",
+       "           1.12764797,   0.17401801,   1.57500838, -19.81485677,\n",
+       "          -3.5559654 ,  -6.41943623,  13.3452067 ,  18.66749508]),\n",
+       "  array([ -1.25760799,  -2.31887649,   0.33271704,  -1.08099454,\n",
+       "           1.14089883,   0.19269996,   1.78615991, -19.77007365,\n",
+       "          -3.62527424,  -6.44984163,  13.25085141,  18.68194461]),\n",
+       "  array([ -1.25561823,  -2.33859991,   0.32902889,  -1.08747235,\n",
+       "           1.15405664,   0.21139842,   1.98976583, -19.72341265,\n",
+       "          -3.6881565 ,  -6.47780513,  13.1578159 ,  18.698465  ]),\n",
+       "  array([ -1.25343229,  -2.35827488,   0.32528417,  -1.09397579,\n",
+       "           1.16712285,   0.23011496,   2.18593611, -19.674974  ,\n",
+       "          -3.74471902,  -6.50343914,  13.06621108,  18.71654157]),\n",
+       "  array([ -1.25105747,  -2.37789973,   0.32148904,  -1.10050262,\n",
+       "           1.18009899,   0.24885064,   2.37482023, -19.62485108,\n",
+       "          -3.79512507,  -6.52683884,  12.97614085,  18.73567178]),\n",
+       "  array([ -1.24850087,  -2.39747286,   0.31764946,  -1.10705071,\n",
+       "           1.1929867 ,   0.26760601,   2.55660244, -19.57313177,\n",
+       "          -3.83958583,  -6.54808516,  12.88770189,  18.75537462]),\n",
+       "  array([ -1.24576937,  -2.41699276,   0.31377111,  -1.11361796,\n",
+       "           1.20578768,   0.28638121,   2.73149658, -19.51989969,\n",
+       "          -3.87835145,  -6.56724772,  12.80098371,  18.77519819]),\n",
+       "  array([ -1.24286963,  -2.436458  ,   0.3098594 ,  -1.12020234,\n",
+       "           1.21850375,   0.30517593,   2.89974092, -19.46523526,\n",
+       "          -3.91170226,  -6.58438765,  12.71606873,  18.79472548]),\n",
+       "  array([ -1.23980804,  -2.45586721,   0.30591946,  -1.12680191,\n",
+       "           1.23113678,   0.32398951,   3.06159304, -19.40921658,\n",
+       "          -3.93994035,  -6.5995601 ,  12.6330324 ,  18.81357849]),\n",
+       "  array([ -1.23659071,  -2.47521913,   0.30195608,  -1.13341472,\n",
+       "           1.24368872,   0.34282093,   3.21732509, -19.35192021,\n",
+       "          -3.96338187,  -6.61281643,  12.5519435 ,  18.83142087]),\n",
+       "  array([ -1.23322349,  -2.49451256,   0.29797373,  -1.14003893,\n",
+       "           1.25616159,   0.36166889,   3.36721935, -19.29342174,\n",
+       "          -3.98235019,  -6.62420597,  12.47286442,  18.84795923]),\n",
+       "  array([ -1.22971193,  -2.51374635,   0.29397656,  -1.1466727 ,\n",
+       "           1.26855744,   0.38053184,   3.5115643 , -19.23379624,\n",
+       "          -3.9971699 ,  -6.63377742,  12.39585149,  18.86294337]),\n",
+       "  array([ -1.22606128,  -2.53291947,   0.2899684 ,  -1.15331428,\n",
+       "           1.2808784 ,   0.399408  ,   3.65065117, -19.1731186 ,\n",
+       "          -4.00816184,  -6.64157989,  12.32095538,  18.87616553]),\n",
+       "  array([ -1.22227651,  -2.55203093,   0.28595276,  -1.15996195,\n",
+       "           1.29312662,   0.41829546,   3.78477093, -19.11146372,\n",
+       "          -4.01563895,  -6.64766359,  12.24822142,  18.88745888]),\n",
+       "  array([ -1.21836229,  -2.57107984,   0.28193286,  -1.16661403,\n",
+       "           1.30530431,   0.43719216,   3.91421178, -19.04890664,\n",
+       "          -4.01990294,  -6.65208027,  12.17769006,  18.89669544]),\n",
+       "  array([ -1.21432304,  -2.59006536,   0.27791162,  -1.17326891,\n",
+       "           1.3174137 ,   0.45609594,   4.03925703, -18.98552259,\n",
+       "          -4.02124183,  -6.65488332,  12.10939719,  18.9037835 ]),\n",
+       "  array([ -1.21016285,  -2.60898675,   0.27389169,  -1.17992504,\n",
+       "           1.32945708,   0.4750046 ,   4.16018341, -18.9213869 ,\n",
+       "          -4.01992803,  -6.65612782,  12.0433745 ,  18.90866477]),\n",
+       "  array([ -1.20588559,  -2.62784333,   0.26987547,  -1.18658091,\n",
+       "           1.34143673,   0.49391592,   4.27725975, -18.85657495,\n",
+       "          -4.01621711,  -6.65587029,  11.97964984,  18.91131125]),\n",
+       "  array([ -1.20149485,  -2.64663449,   0.26586512,  -1.19323508,\n",
+       "           1.35335498,   0.51282764,   4.39074595, -18.79116201,\n",
+       "          -4.01034702,  -6.65416841,  11.91824749,  18.91172209]),\n",
+       "  array([ -1.19699395,  -2.66535971,   0.26186259,  -1.19988616,\n",
+       "           1.36521416,   0.53173756,   4.50089224, -18.72522307,\n",
+       "          -4.00253776,  -6.65108065,  11.85918848,  18.90992031]),\n",
+       "  array([ -1.19238602,  -2.68401854,   0.2578696 ,  -1.20653282,\n",
+       "           1.37701666,   0.55064351,   4.6079387 , -18.65883264,\n",
+       "          -3.99299133,  -6.64666583,  11.80249073,  18.90594966]),\n",
+       "  array([ -1.1876739 ,  -2.70261061,   0.2538877 ,  -1.21317381,\n",
+       "           1.38876482,   0.56954338,   4.71211493, -18.59206458,\n",
+       "          -3.981892  ,  -6.6409827 ,  11.74816933,  18.89987148]),\n",
+       "  array([ -1.18286026,  -2.7211356 ,   0.2499183 ,  -1.2198079 ,\n",
+       "           1.40046106,   0.58843514,   4.81363995, -18.52499181,\n",
+       "          -3.96940678,  -6.63408944,  11.69623664,  18.8917618 ]),\n",
+       "  array([ -1.17794754,  -2.73959329,   0.24596261,  -1.22643394,\n",
+       "           1.41210776,   0.60731685,   4.91272219, -18.45768616,\n",
+       "          -3.95568604,  -6.62604325,  11.64670241,  18.8817085 ]),\n",
+       "  array([ -1.17293798,  -2.7579835 ,   0.24202175,  -1.23305084,\n",
+       "           1.42370734,   0.62618666,   5.00955965, -18.39021811,\n",
+       "          -3.94086424,  -6.61689993,  11.59957387,  18.86980877]),\n",
+       "  array([ -1.16783364,  -2.77630616,   0.23809669,  -1.23965755,\n",
+       "           1.43526219,   0.64504283,   5.10434009, -18.32265663,\n",
+       "          -3.92506073,  -6.60671355,  11.55485574,  18.85616668]),\n",
+       "  array([ -1.1626364 ,  -2.79456123,   0.2341883 ,  -1.24625309,\n",
+       "           1.44677474,   0.66388372,   5.19724136, -18.25506895,\n",
+       "          -3.90838059,  -6.59553602,  11.5125503 ,  18.84089104]),\n",
+       "  array([ -1.15734797,  -2.81274875,   0.23029739,  -1.25283651,\n",
+       "           1.4582474 ,   0.68270781,   5.28843167, -18.18752042,\n",
+       "          -3.89091552,  -6.58341689,  11.47265732,  18.82409345]),\n",
+       "  array([ -1.1519699 ,  -2.83086882,   0.22642464,  -1.25940691,\n",
+       "           1.46968258,   0.7015137 ,   5.37807002, -18.1200743 ,\n",
+       "          -3.87274469,  -6.57040307,  11.43517406,  18.80588657]),\n",
+       "  array([ -1.14650359,  -2.84892162,   0.22257071,  -1.26596345,\n",
+       "           1.48108267,   0.72030008,   5.46630662, -18.0527917 ,\n",
+       "          -3.85393559,  -6.55653861,  11.40009521,  18.78638261]),\n",
+       "  array([ -1.14095031,  -2.86690735,   0.21873616,  -1.27250531,\n",
+       "           1.49245008,   0.73906577,   5.55328326, -17.98573138,\n",
+       "          -3.83454486,  -6.54186459,  11.36741283,  18.76569202]),\n",
+       "  array([ -1.13531117,  -2.8848263 ,   0.21492155,  -1.27903173,\n",
+       "           1.5037872 ,   0.75780969,   5.63913374, -17.91894971,\n",
+       "          -3.81461906,  -6.52641898,  11.33711629,  18.74392241]),\n",
+       "  array([ -1.12958719,  -2.9026788 ,   0.21112735,  -1.28554197,\n",
+       "           1.51509639,   0.77653087,   5.72398434, -17.85250058,\n",
+       "          -3.79419544,  -6.51023656,  11.3091922 ,  18.7211776 ]),\n",
+       "  array([ -1.12377923,  -2.92046523,   0.20735405,  -1.29203532,\n",
+       "           1.52638002,   0.79522843,   5.80795417, -17.78643535,\n",
+       "          -3.77330263,  -6.49334892,  11.28362432,  18.69755689]),\n",
+       "  array([ -1.11788808,  -2.93818604,   0.20360209,  -1.2985111 ,\n",
+       "           1.53764041,   0.81390158,   5.89115562, -17.72080278,\n",
+       "          -3.75196134,  -6.47578441,  11.26039356,  18.67315448]),\n",
+       "  array([ -1.11191438,  -2.95584169,   0.1998719 ,  -1.30496867,\n",
+       "           1.54887989,   0.83254964,   5.97369474, -17.65564908,\n",
+       "          -3.73018491,  -6.45756819,  11.23947785,  18.64805907]),\n",
+       "  array([ -1.10585871,  -2.9734327 ,   0.19616392,  -1.31140739,\n",
+       "           1.56010074,   0.85117199,   6.05567159, -17.59101786,\n",
+       "          -3.70797996,  -6.43872226,  11.22085217,  18.62235351]),\n",
+       "  array([ -1.09972153,  -2.99095965,   0.19247857,  -1.31782666,\n",
+       "           1.57130523,   0.86976811,   6.13718062, -17.52695019,\n",
+       "          -3.6853469 ,  -6.41926552,  11.2044885 ,  18.59611466]),\n",
+       "  array([ -1.09350322,  -3.00842314,   0.18881629,  -1.32422587,\n",
+       "           1.58249558,   0.88833752,   6.21831098, -17.46348462,\n",
+       "          -3.66228045,  -6.39921388,  11.19035585,  18.56941335]),\n",
+       "  array([ -1.08720407,  -3.0258238 ,   0.18517752,  -1.33060445,\n",
+       "           1.593674  ,   0.90687984,   6.29914682, -17.40065727,\n",
+       "          -3.6387701 ,  -6.37858033,  11.17842023,  18.5423144 ]),\n",
+       "  array([ -1.08082431,  -3.0431623 ,   0.18156272,  -1.33696183,\n",
+       "           1.60484265,   0.92539471,   6.37976763, -17.33850185,\n",
+       "          -3.61480056,  -6.35737503,  11.16864477,  18.51487679]),\n",
+       "  array([ -1.07436406,  -3.06043935,   0.17797237,  -1.34329743,\n",
+       "           1.61600364,   0.94388187,   6.46024845, -17.27704981,\n",
+       "          -3.59035221,  -6.33560544,  11.1609897 ,  18.48715385]),\n",
+       "  array([ -1.0678234 ,  -3.07765568,   0.17440697,  -1.34961071,\n",
+       "           1.62715905,   0.96234106,   6.54066014, -17.21633042,\n",
+       "          -3.56540147,  -6.31327642,  11.15541256,  18.45919359]),\n",
+       "  array([ -1.06120233,  -3.09481205,   0.17086705,  -1.3559011 ,\n",
+       "           1.63831092,   0.9807721 ,   6.62106961, -17.15637088,\n",
+       "          -3.5399212 ,  -6.29039036,  11.15186821,  18.43103903]),\n",
+       "  array([ -1.05450079,  -3.11190924,   0.16735317,  -1.36216805,\n",
+       "           1.64946123,   0.99917483,   6.70154   , -17.09719645,\n",
+       "          -3.51388106,  -6.26694726,  11.15030906,  18.40272869]),\n",
+       "  array([ -1.04771866,  -3.12894808,   0.16386592,  -1.36841099,\n",
+       "           1.66061191,   1.01754913,   6.78213092, -17.03883061,\n",
+       "          -3.48724788,  -6.24294485,  11.15068521,  18.37429703]),\n",
+       "  array([ -1.04085576,  -3.14592937,   0.16040593,  -1.37462937,\n",
+       "           1.67176486,   1.0358949 ,   6.86289857, -16.98129521,\n",
+       "          -3.45998602,  -6.21837871,  11.15294467,  18.34577503]),\n",
+       "  array([ -1.03391186,  -3.16285398,   0.15697388,  -1.38082261,\n",
+       "           1.68292189,   1.05421209,   6.94389588, -16.92461062,\n",
+       "          -3.43205769,  -6.19324235,  11.1570336 ,  18.31719076]),\n",
+       "  array([ -1.02688669,  -3.17972278,   0.15357045,  -1.38699014,\n",
+       "           1.69408479,   1.07250066,   7.02517272, -16.86879592,\n",
+       "          -3.40342332,  -6.16752728,  11.16289653,  18.2885701 ]),\n",
+       "  array([ -1.01977991,  -3.19653665,   0.15019641,  -1.39313136,\n",
+       "           1.70525526,   1.0907606 ,   7.10677596, -16.8138691 ,\n",
+       "          -3.37404187,  -6.14122316,  11.17047667,  18.25993737]),\n",
+       "  array([ -1.01259116,  -3.21329649,   0.14685254,  -1.39924568,\n",
+       "           1.71643498,   1.10899192,   7.18874958, -16.75984723,\n",
+       "          -3.34387118,  -6.11431781,  11.17971622,  18.23131618]),\n",
+       "  array([ -1.00532003,  -3.23000324,   0.14353967,  -1.40533248,\n",
+       "           1.72762554,   1.12719465,   7.27113481, -16.70674672,\n",
+       "          -3.31286833,  -6.08679731,  11.19055668,  18.2027302 ]),\n",
+       "  array([ -0.99796606,  -3.24665782,   0.14025868,  -1.41139112,\n",
+       "           1.73882848,   1.14536885,   7.35397018, -16.6545835 ,\n",
+       "          -3.28098991,  -6.05864606,  11.20293923,  18.17420408]),\n",
+       "  array([ -0.99052877,  -3.2632612 ,   0.13701049,  -1.41742097,\n",
+       "           1.75004528,   1.16351461,   7.43729159, -16.6033733 ,\n",
+       "          -3.24819243,  -6.02984688,  11.21680509,  18.14576441]),\n",
+       "  array([ -0.98300764,  -3.27981433,   0.13379606,  -1.42342135,\n",
+       "           1.76127738,   1.18163206,   7.52113242, -16.55313187,\n",
+       "          -3.21443259,  -6.00038103,  11.23209592,  18.11744073]),\n",
+       "  array([ -0.97540211,  -3.2963182 ,   0.13061639,  -1.42939158,\n",
+       "           1.77252613,   1.19972132,   7.60552354, -16.50387529,\n",
+       "          -3.17966763,  -5.97022829,  11.24875428,  18.08926667]),\n",
+       "  array([ -0.96771162,  -3.31277382,   0.12747253,  -1.43533095,\n",
+       "           1.78379286,   1.2177826 ,   7.69049341, -16.45562022,\n",
+       "          -3.14385564,  -5.93936709,  11.26672403,  18.06128114]),\n",
+       "  array([ -0.95993555,  -3.32918221,   0.12436558,  -1.44123872,\n",
+       "           1.79507881,   1.23581613,   7.77606807, -16.40838423,\n",
+       "          -3.10695584,  -5.90777456,  11.28595087,  18.03352962]),\n",
+       "  array([ -0.95207328,  -3.34554439,   0.12129665,  -1.44711415,\n",
+       "           1.80638519,   1.2538222 ,   7.86227126, -16.36218613,\n",
+       "          -3.06892885,  -5.87542671,  11.30638281,  18.00606558]),\n",
+       "  array([ -0.94412415,  -3.36186144,   0.11826691,  -1.45295645,\n",
+       "           1.81771316,   1.27180115,   7.94912436, -16.31704629,\n",
+       "          -3.02973695,  -5.84229863,  11.3279708 ,  17.97895201]),\n",
+       "  array([ -0.93608751,  -3.37813443,   0.11527757,  -1.45876481,\n",
+       "           1.82906383,   1.28975341,   8.03664652, -16.27298705,\n",
+       "          -2.98934424,  -5.80836474,  11.35066929,  17.95226302]),\n",
+       "  array([ -0.92796265,  -3.39436446,   0.11232985,  -1.46453841,\n",
+       "           1.84043827,   1.3076795 ,   8.12485463, -16.23003307,\n",
+       "          -2.94771675,  -5.7735992 ,  11.37443694,  17.9260857 ]),\n",
+       "  array([ -0.91974889,  -3.41055267,   0.10942503,  -1.47027639,\n",
+       "           1.8518375 ,   1.32558002,   8.21376336, -16.18821182,\n",
+       "          -2.90482249,  -5.73797646,  11.39923741,  17.90052201]),\n",
+       "  array([ -0.91144551,  -3.42670023,   0.1065644 ,  -1.47597786,\n",
+       "           1.86326254,   1.34345571,   8.30338521, -16.14755395,\n",
+       "          -2.86063128,  -5.70147199,  11.42504029,  17.8756909 ]),\n",
+       "  array([ -0.90305177,  -3.44280832,   0.10374928,  -1.48164192,\n",
+       "           1.87471437,   1.36130744,   8.39373051, -16.10809382,\n",
+       "          -2.8151145 ,  -5.66406342,  11.45182213,  17.85173058]),\n",
+       "  array([ -0.89456697,  -3.45887819,   0.10098104,  -1.48726766,\n",
+       "           1.88619393,   1.37913624,   8.48480745, -16.06987003,\n",
+       "          -2.76824449,  -5.62573198,  11.47956782,  17.82880102]),\n",
+       "  array([ -0.88599034,  -3.47491112,   0.09826104,  -1.49285412,\n",
+       "           1.89770221,   1.39694333,   8.57662212, -16.03292592,\n",
+       "          -2.7199937 ,  -5.58646462,  11.50827215,  17.80708664]),\n",
+       "  array([ -0.87732117,  -3.49090843,   0.09559071,  -1.49840038,\n",
+       "           1.90924015,   1.41473013,   8.6691785 , -15.9973102 ,\n",
+       "          -2.67033329,  -5.54625688,  11.53794192,  17.7867992 ]),\n",
+       "  array([ -0.86855869,  -3.5068715 ,   0.09297148,  -1.50390549,\n",
+       "           1.92080875,   1.43249831,   8.76247853, -15.96307757,\n",
+       "          -2.61923116,  -5.5051169 ,  11.56859856,  17.76818098]),\n",
+       "  array([ -0.85970217,  -3.52280179,   0.09040483,  -1.50936856,\n",
+       "           1.93240903,   1.45024982,   8.85652211, -15.93028941,\n",
+       "          -2.56664909,  -5.46307088,  11.6002816 ,  17.75150821]),\n",
+       "  array([ -0.85075086,  -3.53870081,   0.08789229,  -1.51478874,\n",
+       "           1.94404208,   1.46798691,   8.95130716, -15.89901454,\n",
+       "          -2.51253873,  -5.42017068,  11.63305319,  17.73709481]),\n",
+       "  array([ -0.84170403,  -3.55457014,   0.08543546,  -1.52016524,\n",
+       "           1.95570909,   1.48571221,   9.04682971, -15.86933005,\n",
+       "          -2.45683595,  -5.3765041 ,  11.66700415,  17.72529648]),\n",
+       "  array([ -0.83256094,  -3.57041146,   0.083036  ,  -1.52549745,\n",
+       "           1.96741135,   1.50342872,   9.14308404, -15.84132222,\n",
+       "          -2.39945305,  -5.3322091 ,  11.70226202,  17.71651514]),\n",
+       "  array([ -0.82332088,  -3.58622655,   0.08069573,  -1.53078494,\n",
+       "           1.97915035,   1.52113993,   9.24006289, -15.81508767,\n",
+       "          -2.34026801,  -5.28749312,  11.73900192,  17.71120395]),\n",
+       "  array([ -0.81398312,  -3.60201728,   0.07841662,  -1.5360276 ,\n",
+       "           1.99092781,   1.5388498 ,   9.33775791, -15.79073465,\n",
+       "          -2.27910963,  -5.24265947,  11.77746107,  17.7098728 ]),\n",
+       "  array([ -0.80454696,  -3.61778567,   0.07620089,  -1.54122574,\n",
+       "           2.00274577,   1.5565629 ,   9.43616034, -15.76838471,\n",
+       "          -2.21573713,  -5.19814334,  11.81795841,  17.71309463]),\n",
+       "  array([ -0.7950117 ,  -3.63353384,   0.07405108,  -1.5463803 ,\n",
+       "           2.01460669,   1.57428441,   9.53526215, -15.74817491,\n",
+       "          -2.14981217,  -5.15456068,  11.86092106,  17.72151277]),\n",
+       "  array([ -0.78537664,  -3.6492641 ,   0.07197021,  -1.55149308,\n",
+       "           2.02651361,   1.59202026,   9.63505797, -15.73026065,\n",
+       "          -2.08086044,  -5.11277477,  11.90692001,  17.73584957]),\n",
+       "  array([ -0.7756411 ,  -3.66497892,   0.069962  ,  -1.55656707,\n",
+       "           2.03847033,   1.60977718,   9.73554816, -15.71481977,\n",
+       "          -2.00821903,  -5.07398638,  11.95671807,  17.75691702]),\n",
+       "  array([ -0.76580435,  -3.68068098,   0.06803103,  -1.56160692,\n",
+       "           2.05048166,   1.62756281,   9.83674367, -15.70205807,\n",
+       "          -1.93096444,  -5.03985592,  12.01133467,  17.78562993]),\n",
+       "  array([ -0.75586568,  -3.6963732 ,   0.06618322,  -1.56661959,\n",
+       "           2.0625538 ,   1.64538583,   9.93867362, -15.69221705,\n",
+       "          -1.84781445,  -5.01266849,  12.07213285,  17.82302266]),\n",
+       "  array([ -0.74582428,  -3.71205878,   0.06442622,  -1.57161515,\n",
+       "           2.07469473,   1.6632561 ,  10.04139669, -15.68558442,\n",
+       "          -1.75699514,  -4.99555599,  12.14093657,  17.87027064]),\n",
+       "  array([ -0.73567926,  -3.72774129,   0.06277016,  -1.57660794,\n",
+       "           2.08691492,   1.68118482,  10.14501794, -15.68250784,\n",
+       "          -1.65606265,  -4.99279451,  12.22018868,  17.928718  ]),\n",
+       "  array([ -0.72542955,  -3.7434247 ,   0.06122849,  -1.58161814,\n",
+       "           2.09922809,   1.69918473,  10.24971283, -15.68341159,\n",
+       "          -1.54166879,  -5.01019887,  12.31316445,  17.99991234]),\n",
+       "  array([ -0.71507379,  -3.75911352,   0.05981923,  -1.58667378,\n",
+       "           2.11165235,   1.71727038,  10.35576069, -15.68881446,\n",
+       "          -1.40926265,  -5.05563633,  12.42425945,  18.08564747]),\n",
+       "  array([ -0.7046102 ,  -3.77481286,   0.0585665 ,  -1.59181345,\n",
+       "           2.12421172,   1.73545839,  10.46359109, -15.69934335,\n",
+       "          -1.25273017,  -5.1396722 ,  12.55937331,  18.18801368]),\n",
+       "  array([ -0.69403635,  -3.79052859,   0.0575025 ,  -1.59708977,\n",
+       "           2.13693812,   1.75376785,  10.57385272, -15.71573049,\n",
+       "          -1.06399374,  -5.27632381,  12.72640075,  18.30945497]),\n",
+       "  array([ -0.6833488 ,  -3.80626735,   0.0566699 ,  -1.60257361,\n",
+       "           2.14987393,   1.77222068,  10.6875413 , -15.73876472,\n",
+       "          -0.83260015,  -5.48383705,  12.93581111,  18.4528369 ]),\n",
+       "  array([ -0.67254248,  -3.82203647,   0.0561248 ,  -1.60835918,\n",
+       "           2.1630753 ,   1.79084223,  10.80632893, -15.76911665,\n",
+       "          -0.54510808,  -5.78557097,  13.20136469,  18.62154833]),\n",
+       "  array([ -0.66160891,  -3.8378433 ,   0.05594214,  -1.61457256,\n",
+       "           2.17661774,   1.80966195,  10.933567  , -15.80682908,\n",
+       "          -0.18265352,  -6.21337902,  13.5424454 ,  18.81972159]),\n",
+       "  array([ -0.65053258,  -3.85369364,   0.05622943,  -1.62139983,\n",
+       "           2.1906196 ,   1.82871416,  11.07632757, -15.8503412 ,\n",
+       "           0.28729204,  -6.82727353,  14.00185471,  19.05221265])],\n",
+       " [array([ -52.33562191,  -66.65932781,  -26.90708972,  -54.25815874,\n",
+       "          -83.01253149, -142.47197924]),\n",
+       "  array([ -49.86179662,  -65.06231854,  -27.64420269,  -51.10486444,\n",
+       "          -71.45190134, -118.53929599]),\n",
+       "  array([-47.64325056, -63.10105583, -28.06060798, -47.70654668,\n",
+       "         -61.31702629, -97.58708553]),\n",
+       "  array([-45.56654598, -60.85340585, -28.16723897, -44.19986009,\n",
+       "         -52.41615179, -79.28037558]),\n",
+       "  array([-43.5533942 , -58.38464846, -27.98535504, -40.68187455,\n",
+       "         -44.5910181 , -63.32305895]),\n",
+       "  array([-41.55253999, -55.74874417, -27.54244134, -37.22064912,\n",
+       "         -37.70931187, -49.4521516 ]),\n",
+       "  array([-39.53326917, -52.98995659, -26.8694662 , -33.86302897,\n",
+       "         -31.65893967, -37.43323756]),\n",
+       "  array([-37.48021354, -50.14452614, -25.99898374, -30.64038825,\n",
+       "         -26.34370869, -27.05682698]),\n",
+       "  array([-35.38919921, -47.24222532, -24.96377625, -27.57285112,\n",
+       "         -21.68008726, -18.13540619]),\n",
+       "  array([-33.26394021, -44.3077121 , -23.79585628, -24.67238537,\n",
+       "         -17.59478591, -10.50100696]),\n",
+       "  array([-31.11342238, -41.36165172, -22.52572398, -21.94506203,\n",
+       "         -14.02295518,  -4.00316399]),\n",
+       "  array([-28.94985488, -38.42160913, -21.18181895, -19.39270023,\n",
+       "         -10.90684046,   1.49283681]),\n",
+       "  array([-26.78709075, -35.50273314, -19.79013033, -17.0140609 ,\n",
+       "          -8.19477088,   6.10748969]),\n",
+       "  array([-24.6394361 , -32.61826193, -18.37394185, -14.80571151,\n",
+       "          -5.84038873,   9.94843066]),\n",
+       "  array([-22.52078023, -29.77988263, -16.95369419, -12.76265275,\n",
+       "          -3.80204939,  13.11166458]),\n",
+       "  array([-20.44398951, -26.9979774 , -15.54694908, -10.87877448,\n",
+       "          -2.04234062,  15.68268195]),\n",
+       "  array([-18.4205151 , -24.28178479, -14.16844005,  -9.14719019,\n",
+       "          -0.52768431,  17.73748202]),\n",
+       "  array([-16.46017149, -21.63950173, -12.83019387,  -7.56048578,\n",
+       "           0.77200481,  19.3435133 ]),\n",
+       "  array([-14.57104783, -19.0783465 , -11.54170724,  -6.11090824,\n",
+       "           1.88362105,  20.5605387 ]),\n",
+       "  array([-12.75951961, -16.60459861, -10.31016309,  -4.7905123 ,\n",
+       "           2.8311416 ,  21.4414305 ]),\n",
+       "  array([-11.03033258, -14.22362748,  -9.14067205,  -3.59127709,\n",
+       "           3.63587957,  22.03289885]),\n",
+       "  array([ -9.38673544, -11.93991811,  -8.03652625,  -2.50520137,\n",
+       "           4.31672034,  22.37615666]),\n",
+       "  array([-7.83064227, -9.75709893, -6.99945418, -1.52438245,  4.89034364,\n",
+       "         22.50752391]),\n",
+       "  array([-6.3628091 , -7.67797481, -6.02986803, -0.64108225,  5.37143238,\n",
+       "         22.45897404]),\n",
+       "  array([-4.98301325, -5.70456636, -5.12709645,  0.15221735,  5.77286871,\n",
+       "         22.25862563]),\n",
+       "  array([-3.69022646, -3.83815544, -4.28959828,  0.86276875,  6.10591744,\n",
+       "         21.93118274]),\n",
+       "  array([-2.48277623, -2.07933617, -3.5151544 ,  1.49752152,  6.38039668,\n",
+       "         21.49832753]),\n",
+       "  array([-1.35849143, -0.42807007, -2.8010364 ,  2.06309341,  6.60483582,\n",
+       "         20.97906899]),\n",
+       "  array([-0.31483034,  1.11625604, -2.14415207,  2.56574884,  6.78662097,\n",
+       "         20.39005174]),\n",
+       "  array([ 0.65100957,  2.55477087, -1.54116861,  3.01138451,  6.93212802,\n",
+       "         19.74582872]),\n",
+       "  array([ 1.54199953,  3.88905959, -0.98861517,  3.4055213 ,  7.04684374,\n",
+       "         19.05910174]),\n",
+       "  array([ 2.36120424,  5.12110591, -0.48296658,  3.75330205,  7.13547542,\n",
+       "         18.34093334]),\n",
+       "  array([ 3.11172176,  6.25323631, -0.02071061,  4.05949428,  7.20204958,\n",
+       "         17.60093346]),\n",
+       "  array([ 3.79663696,  7.28806726,  0.40159934,  4.32849729,  7.25000052,\n",
+       "         16.84742402]),\n",
+       "  array([ 4.4189866 ,  8.22845579,  0.78730369,  4.5643528 ,  7.28224917,\n",
+       "         16.08758417]),\n",
+       "  array([ 4.98173437,  9.07745379,  1.13960644,  4.77075851,  7.30127324,\n",
+       "         15.32757869]),\n",
+       "  array([ 5.48775411,  9.83826632,  1.4615535 ,  4.95108379,  7.30916915,\n",
+       "         14.57267175]),\n",
+       "  array([ 5.93981979, 10.51421394,  1.75601782,  5.1083869 ,  7.30770656,\n",
+       "         13.82732793]),\n",
+       "  array([ 6.34060067, 11.10869891,  2.02569021,  5.24543335,  7.29837613,\n",
+       "         13.09530212]),\n",
+       "  array([ 6.69266075, 11.62517528,  2.27307448,  5.36471461,  7.28243126,\n",
+       "         12.37971969]),\n",
+       "  array([ 6.99846117, 12.06712268,  2.50048601,  5.46846703,  7.26092422,\n",
+       "         11.68314815]),\n",
+       "  array([ 7.26036495, 12.43802341,  2.71005309,  5.55869048,  7.23473748,\n",
+       "         11.00766133]),\n",
+       "  array([ 7.48064319, 12.74134284,  2.90372017,  5.63716654,  7.2046106 ,\n",
+       "         10.35489687]),\n",
+       "  array([ 7.66148224, 12.98051268,  3.08325269,  5.70547593,  7.17116326,\n",
+       "          9.72610785]),\n",
+       "  array([ 7.80499133, 13.15891688,  3.25024301,  5.76501508,  7.13491483,\n",
+       "          9.12220918]),\n",
+       "  array([ 7.91321031, 13.27988003,  3.40611719,  5.81701182,  7.09630093,\n",
+       "          8.54381922]),\n",
+       "  array([ 7.98811719, 13.34665779,  3.5521423 ,  5.86253999,  7.05568739,\n",
+       "          7.99129718]),\n",
+       "  array([ 8.03163528, 13.36242931,  3.68943415,  5.90253304,  7.01338186,\n",
+       "          7.46477671]),\n",
+       "  array([ 8.04563976, 13.33029133,  3.81896535,  5.93779668,  6.96964341,\n",
+       "          6.96419602]),\n",
+       "  array([ 8.03196357, 13.25325369,  3.94157341,  5.96902045,  6.92469051,\n",
+       "          6.48932488]),\n",
+       "  array([ 7.9924025 , 13.13423616,  4.0579691 ,  5.99678842,  6.87870749,\n",
+       "          6.03978875]),\n",
+       "  array([ 7.92871958, 12.97606636,  4.16874473,  6.02158903,  6.83184975,\n",
+       "          5.61509041]),\n",
+       "  array([ 7.84264851, 12.78147854,  4.27438249,  6.04382405,  6.78424799,\n",
+       "          5.21462918]),\n",
+       "  array([ 7.73589637, 12.55311324,  4.37526282,  6.0638169 ,  6.73601154,\n",
+       "          4.83771816]),\n",
+       "  array([ 7.61014546, 12.29351747,  4.47167264,  6.08182024,  6.68723103,\n",
+       "          4.4835994 ]),\n",
+       "  array([ 7.46705445, 12.00514545,  4.56381362,  6.09802302,  6.63798043,\n",
+       "          4.15145759]),\n",
+       "  array([ 7.30825872, 11.69035982,  4.65181027,  6.11255694,  6.58831875,\n",
+       "          3.84043199]),\n",
+       "  array([ 7.13537007, 11.35143303,  4.73571802,  6.12550256,  6.53829127,\n",
+       "          3.54962717]),\n",
+       "  array([ 6.9499758 , 10.99054909,  4.81553115,  6.13689489,  6.48793059,\n",
+       "          3.2781224 ]),\n",
+       "  array([ 6.75363732, 10.60980538,  4.89119051,  6.14672866,  6.43725748,\n",
+       "          3.02498004]),\n",
+       "  array([ 6.54788813, 10.21121463,  4.96259118,  6.15496333,  6.38628163,\n",
+       "          2.78925294]),\n",
+       "  array([6.3342316 , 9.79670696, 5.02958987, 6.16152774, 6.33500222,\n",
+       "         2.56999094]),\n",
+       "  array([6.11413827, 9.36813186, 5.09201213, 6.16632454, 6.28340854,\n",
+       "         2.36624668]),\n",
+       "  array([5.88904299, 8.92726026, 5.14965924, 6.16923438, 6.23148063,\n",
+       "         2.17708075]),\n",
+       "  array([5.6603419 , 8.47578651, 5.20231494, 6.17011992, 6.17918975,\n",
+       "         2.00156622]),\n",
+       "  array([5.42938926, 8.01533035, 5.24975175, 6.16882955, 6.12649907,\n",
+       "         1.83879274]),\n",
+       "  array([5.19749431, 7.54743885, 5.29173699, 6.16520097, 6.07336427,\n",
+       "         1.68787012]),\n",
+       "  array([4.96591821, 7.07358822, 5.32803847, 6.15906455, 6.01973415,\n",
+       "         1.54793161]),\n",
+       "  array([4.73587101, 6.59518573, 5.35842971, 6.15024646, 5.96555132,\n",
+       "         1.4181368 ]),\n",
+       "  array([4.50850887, 6.11357145, 5.38269484, 6.13857161, 5.91075284,\n",
+       "         1.29767421]),\n",
+       "  array([4.28493147, 5.63002003, 5.40063304, 6.12386633, 5.85527093,\n",
+       "         1.18576374]),\n",
+       "  array([4.06617971, 5.1457425 , 5.4120625 , 6.10596088, 5.79903357,\n",
+       "         1.08165873]),\n",
+       "  array([3.85323366, 4.66188801, 5.41682403, 6.08469166, 5.74196516,\n",
+       "         0.98464792]),\n",
+       "  array([3.64701095, 4.17954563, 5.41478413, 6.05990319, 5.68398705,\n",
+       "         0.89405723]),\n",
+       "  array([3.44836539, 3.69974607, 5.40583761, 6.03144986, 5.62501811,\n",
+       "         0.80925126]),\n",
+       "  array([3.25808605, 3.22346359, 5.38990983, 5.99919739, 5.5649751 ,\n",
+       "         0.72963479]),\n",
+       "  array([3.07689666, 2.75161777, 5.36695843, 5.963024  , 5.50377309,\n",
+       "         0.65465391]),\n",
+       "  array([2.90545542, 2.28507539, 5.33697462, 5.92282138, 5.44132566,\n",
+       "         0.58379718]),\n",
+       "  array([2.74435512, 1.82465233, 5.29998414, 5.87849529, 5.37754504,\n",
+       "         0.51659649]),\n",
+       "  array([2.59412369, 1.37111547, 5.25604769, 5.82996596, 5.31234215,\n",
+       "         0.45262783]),\n",
+       "  array([2.455225  , 0.92518457, 5.20526106, 5.7771682 , 5.24562645,\n",
+       "         0.39151182]),\n",
+       "  array([2.32806001, 0.48753425, 5.1477549 , 5.72005122, 5.17730577,\n",
+       "         0.33291412]),\n",
+       "  array([2.21296823, 0.05879575, 5.08369405, 5.6585782 , 5.10728585,\n",
+       "         0.27654558]),\n",
+       "  array([ 2.11022937, -0.36044114,  5.01327666,  5.59272568,  5.03546994,\n",
+       "          0.22216224]),\n",
+       "  array([ 2.02006529, -0.76962634,  4.93673287,  5.52248256,  4.96175816,\n",
+       "          0.1695651 ]),\n",
+       "  array([ 1.9426421 , -1.16824779,  4.85432333,  5.44784904,  4.8860468 ,\n",
+       "          0.11859959]),\n",
+       "  array([ 1.87807247, -1.55582988,  4.76633734,  5.36883526,  4.80822753,\n",
+       "          0.06915493]),\n",
+       "  array([ 1.82641807, -1.93193194,  4.67309075,  5.28545979,  4.7281866 ,\n",
+       "          0.02116307]),\n",
+       "  array([ 1.78769208, -2.2961469 ,  4.57492363,  5.19774795,  4.64580389,\n",
+       "         -0.02540251]),\n",
+       "  array([ 1.76186189, -2.64810013,  4.47219767,  5.10573001,  4.5609521 ,\n",
+       "         -0.07052837]),\n",
+       "  array([ 1.74885176, -2.98744831,  4.36529337,  5.00943931,  4.47349586,\n",
+       "         -0.11416299]),\n",
+       "  array([ 1.74854557, -3.31387854,  4.25460703,  4.90891029,  4.38329101,\n",
+       "         -0.15621897]),\n",
+       "  array([ 1.76078957, -3.62710753,  4.14054746,  4.80417657,  4.29018395,\n",
+       "         -0.19657552]),\n",
+       "  array([ 1.78539513, -3.92688085,  4.02353256,  4.69526902,  4.19401125,\n",
+       "         -0.23508148]),\n",
+       "  array([ 1.82214137, -4.21297232,  3.90398574,  4.58221402,  4.09459948,\n",
+       "         -0.27155856]),\n",
+       "  array([ 1.87077783, -4.48518333,  3.78233212,  4.46503185,  3.99176538,\n",
+       "         -0.30580508]),\n",
+       "  array([ 1.93102694, -4.74334218,  3.65899463,  4.34373536,  3.88531646,\n",
+       "         -0.33760019]),\n",
+       "  array([ 2.0025863 , -4.98730328,  3.53439006,  4.21832906,  3.77505213,\n",
+       "         -0.36670842]),\n",
+       "  array([ 2.0851309 , -5.21694618,  3.40892502,  4.08880864,  3.66076534,\n",
+       "         -0.39288483]),\n",
+       "  array([ 2.17831489, -5.43217434,  3.28299196,  3.9551611 ,  3.54224502,\n",
+       "         -0.41588051]),\n",
+       "  array([ 2.28177313, -5.63291357,  3.15696529,  3.81736561,  3.41927926,\n",
+       "         -0.43544873]),\n",
+       "  array([ 2.39512225, -5.81911007,  3.03119767,  3.67539521,  3.29165931,\n",
+       "         -0.45135138]),\n",
+       "  array([ 2.51796124, -5.99072798,  2.90601666,  3.52921956,  3.15918463,\n",
+       "         -0.463366  ]),\n",
+       "  array([ 2.64987133, -6.14774646,  2.78172186,  3.37880871,  3.02166895,\n",
+       "         -0.47129322]),\n",
+       "  array([ 2.79041519, -6.29015628,  2.65858257,  3.22413823,  2.87894737,\n",
+       "         -0.47496445]),\n",
+       "  array([ 2.93913519, -6.4179559 ,  2.53683639,  3.06519564,  2.73088464,\n",
+       "         -0.47425003]),\n",
+       "  array([ 3.09555063, -6.53114718,  2.41668874,  2.90198828,  2.57738443,\n",
+       "         -0.46906734]),\n",
+       "  array([ 3.25915386, -6.6297309 ,  2.29831367,  2.73455263,  2.41839969,\n",
+       "         -0.45938907]),\n",
+       "  array([ 3.4294051 , -6.71370216,  2.18185605,  2.56296509,  2.25394385,\n",
+       "         -0.44525122]),\n",
+       "  array([ 3.60572597, -6.78304607,  2.06743549,  2.38735399,  2.08410272,\n",
+       "         -0.4267606 ]),\n",
+       "  array([ 3.78749167, -6.83773403,  1.95515193,  2.20791269,  1.90904669,\n",
+       "         -0.40410168]),\n",
+       "  array([ 3.97402193, -6.87772092,  1.84509329,  2.02491349,  1.72904296,\n",
+       "         -0.37754224]),\n",
+       "  array([ 4.16457088, -6.90294374,  1.73734487,  1.8387216 ,  1.54446718,\n",
+       "         -0.34743757]),\n",
+       "  array([ 4.35831631, -6.91332201,  1.63200064,  1.64980888,  1.35581392,\n",
+       "         -0.31423263]),\n",
+       "  array([ 4.55434867, -6.90876048,  1.52917599,  1.45876616,  1.16370522,\n",
+       "         -0.27846184]),\n",
+       "  array([ 4.75166081, -6.88915435,  1.42902147,  1.26631351,  0.96889646,\n",
+       "         -0.24074598]),\n",
+       "  array([ 4.94913916, -6.85439735,  1.33173685,  1.07330712,  0.77227859,\n",
+       "         -0.2017856 ]),\n",
+       "  array([ 5.14555779, -6.80439259,  1.23758446,  0.88074165,  0.57487576,\n",
+       "         -0.16235082]),\n",
+       "  array([ 5.33957662, -6.73906614,  1.14690061,  0.6897469 ,  0.3778377 ,\n",
+       "         -0.12326703]),\n",
+       "  array([ 5.52974541, -6.65838282,  1.06010364,  0.50157746,  0.18242577,\n",
+       "         -0.08539643]),\n",
+       "  array([ 5.71451513, -6.56236356,  0.97769687,  0.31759443, -0.01000771,\n",
+       "         -0.04961559]),\n",
+       "  array([ 5.89225835, -6.45110321,  0.90026481,  0.13923841, -0.19804715,\n",
+       "         -0.01678936]),\n",
+       "  array([ 6.06130005, -6.32478781,  0.82846078, -0.03200656, -0.38024844,\n",
+       "          0.01225827]),\n",
+       "  array([ 6.21995978, -6.18370961,  0.76298449, -0.19465785, -0.55518021,\n",
+       "          0.03677506]),\n",
+       "  array([ 6.3666056 , -6.02827873,  0.70454855, -0.34728707, -0.72147039,\n",
+       "          0.05611212]),\n",
+       "  array([ 6.49971915, -5.85902974,  0.65383341, -0.48857901, -0.87785669,\n",
+       "          0.06975437]),\n",
+       "  array([ 6.61797022, -5.67662234,  0.61143158, -0.61739433, -1.02323851,\n",
+       "          0.07734801]),\n",
+       "  array([ 6.72029774, -5.48183525,  0.57778294, -0.73283268, -1.15672779,\n",
+       "          0.07872325]),\n",
+       "  array([ 6.80599254, -5.27555318,  0.55310472, -0.83429208, -1.27769542,\n",
+       "          0.0739103 ]),\n",
+       "  array([ 6.87477581, -5.05874743,  0.53732127, -0.92152034, -1.38581001,\n",
+       "          0.0631472 ]),\n",
+       "  array([ 6.92686606, -4.8324514 ,  0.5300001 , -0.9946536 , -1.48106546,\n",
+       "          0.04687834]),\n",
+       "  array([ 6.96302632, -4.59773271,  0.53030213, -1.0542378 , -1.56379424,\n",
+       "          0.02574323]),\n",
+       "  array([ 6.98458379e+00, -4.35566458e+00,  5.36954030e-01, -1.10122923e+00,\n",
+       "         -1.63466406e+00,  5.55777308e-04]),\n",
+       "  array([ 6.99341481, -4.10729885,  0.54825028, -1.13697179, -1.69465618,\n",
+       "         -0.0277251 ]),\n",
+       "  array([ 6.9918907 , -3.85364338,  0.56209038, -1.16315014, -1.7450254 ,\n",
+       "         -0.0580318 ]),\n",
+       "  array([ 6.98278309, -3.59564593,  0.57605378, -1.18172008, -1.78724302,\n",
+       "         -0.08922936]),\n",
+       "  array([ 6.96913209, -3.334186  ,  0.58751072, -1.1948195 , -1.82292561,\n",
+       "         -0.12015933]),\n",
+       "  array([ 6.95408484, -3.07007503,  0.59376269, -1.20466555, -1.85375422,\n",
+       "         -0.14968391]),\n",
+       "  array([ 6.94071673, -2.80406442,  0.59220157, -1.21344511, -1.88138957,\n",
+       "         -0.17672812]),\n",
+       "  array([ 6.93185053, -2.53685974,  0.58047294, -1.22320684, -1.90738942,\n",
+       "         -0.20031814]),\n",
+       "  array([ 6.92989007, -2.26913873,  0.55662783, -1.23576312, -1.93313458,\n",
+       "         -0.21961442]),\n",
+       "  array([ 6.93668419, -2.00157024,  0.51924695, -1.25260927, -1.95976886,\n",
+       "         -0.23393853]),\n",
+       "  array([ 6.95343388, -1.73483135,  0.46752496, -1.27486597, -1.98815736,\n",
+       "         -0.24279306]),\n",
+       "  array([ 6.98065011, -1.46962003,  0.4013067 , -1.30324835, -2.01886515,\n",
+       "         -0.24587415]),\n",
+       "  array([ 7.01816458, -1.2066619 ,  0.32107317, -1.33806248, -2.05215693,\n",
+       "         -0.24307645]),\n",
+       "  array([ 7.06518905, -0.94670995,  0.22788113, -1.37922765, -2.08801567,\n",
+       "         -0.23449049]),\n",
+       "  array([ 7.12041449, -0.69053767,  0.12326497, -1.42632031, -2.12617722,\n",
+       "         -0.22039253]),\n",
+       "  array([ 7.1821374 , -0.43892647,  0.00911335, -1.47863432, -2.16617627,\n",
+       "         -0.20122747]),\n",
+       "  array([ 7.24839949, -0.19264898, -0.11246603, -1.53525094, -2.20739892,\n",
+       "         -0.17758551]),\n",
+       "  array([ 7.31712741,  0.04754974, -0.23928018, -1.59511251, -2.24913712,\n",
+       "         -0.15017381]),\n",
+       "  array([ 7.38626102,  0.28097116, -0.36917222, -1.65709394, -2.29064067,\n",
+       "         -0.11978457]),\n",
+       "  array([ 7.45386196,  0.50698071, -0.50012241, -1.7200674 , -2.33116375,\n",
+       "         -0.08726132]),\n",
+       "  array([ 7.51819755,  0.72502225, -0.63032438, -1.78295708, -2.37000356,\n",
+       "         -0.05346534]),\n",
+       "  array([ 7.57779833,  0.93462871, -0.75823523, -1.84478211, -2.4065301 ,\n",
+       "         -0.01924376]),\n",
+       "  array([ 7.63149017,  1.13542865, -0.882601  , -1.90468702, -2.4402067 ,\n",
+       "          0.01459886]),\n",
+       "  array([ 7.67840396,  1.32714856, -1.00246077, -1.96196028, -2.47060205,\n",
+       "          0.04732453]),\n",
+       "  array([ 7.71796697,  1.50961148, -1.1171336 , -2.01604208, -2.49739449,\n",
+       "          0.07828052]),\n",
+       "  array([ 7.74988042,  1.68273238, -1.22619326, -2.06652322, -2.52037009,\n",
+       "          0.10691244]),\n",
+       "  array([ 7.77408785,  1.84651103, -1.32943503, -2.11313677, -2.53941586,\n",
+       "          0.13277187]),\n",
+       "  array([ 7.79073818,  2.00102316, -1.4268386 , -2.15574481, -2.55450954,\n",
+       "          0.1555189 ]),\n",
+       "  array([ 7.80014695,  2.1464105 , -1.5185303 , -2.19432179, -2.56570724,\n",
+       "          0.17492016]),\n",
+       "  array([ 7.8027582 ,  2.28287039, -1.60474691, -2.22893615, -2.57313002,\n",
+       "          0.1908433 ]),\n",
+       "  array([ 7.79910886,  2.41064538, -1.68580281, -2.25973165, -2.57695032,\n",
+       "          0.20324858]),\n",
+       "  array([ 7.78979686,  2.53001328, -1.76206127, -2.28690918, -2.57737892,\n",
+       "          0.21217853]),\n",
+       "  array([ 7.77545352,  2.64127789, -1.83391036, -2.31070997, -2.57465291,\n",
+       "          0.21774645]),\n",
+       "  array([ 7.75672042,  2.7447606 , -1.90174354, -2.33140053, -2.56902489,\n",
+       "          0.22012428]),\n",
+       "  array([ 7.73423073,  2.84079302, -1.96594454, -2.34925967, -2.56075374,\n",
+       "          0.21953063]),\n",
+       "  array([ 7.70859457,  2.92971056, -2.02687623, -2.36456763, -2.55009688,\n",
+       "          0.21621917]),\n",
+       "  array([ 7.68038806,  3.01184708, -2.08487291, -2.37759735, -2.53730403,\n",
+       "          0.21046789]),\n",
+       "  array([ 7.65014557,  3.08753046, -2.14023544, -2.38860775, -2.52261241,\n",
+       "          0.20256934]),\n",
+       "  array([ 7.61835462,  3.15707908, -2.19322873, -2.39783872, -2.50624323,\n",
+       "          0.19282203]),\n",
+       "  array([ 7.585453  ,  3.22079917, -2.24408111, -2.40550785, -2.48839933,\n",
+       "          0.18152297]),\n",
+       "  array([ 7.55182771,  3.27898277, -2.29298504, -2.41180844, -2.46926384,\n",
+       "          0.16896155]),\n",
+       "  array([ 7.51781523,  3.33190642, -2.34009894, -2.41690868, -2.44899961,\n",
+       "          0.15541443]),\n",
+       "  array([ 7.48370293,  3.37983037, -2.38554968, -2.42095179, -2.42774946,\n",
+       "          0.14114163]),\n",
+       "  array([ 7.44973117,  3.42299822, -2.42943559, -2.42405688, -2.40563681,\n",
+       "          0.12638359]),\n",
+       "  array([ 7.41609605,  3.46163697, -2.47182966, -2.42632033, -2.38276689,\n",
+       "          0.11135912]),\n",
+       "  array([ 7.38295241,  3.49595737, -2.51278289, -2.42781766, -2.35922815,\n",
+       "          0.09626413]),\n",
+       "  array([ 7.35041715,  3.52615445, -2.55232757, -2.42860559, -2.33509393,\n",
+       "          0.08127107]),\n",
+       "  array([ 7.31857256,  3.55240836, -2.59048052, -2.42872426, -2.3104242 ,\n",
+       "          0.06652895]),\n",
+       "  array([ 7.28746963,  3.57488518, -2.62724598, -2.42819957, -2.28526743,\n",
+       "          0.05216377]),\n",
+       "  array([ 7.25713136,  3.59373796, -2.66261848, -2.42704538, -2.25966237,\n",
+       "          0.03827945]),\n",
+       "  array([ 7.22755588,  3.60910765, -2.69658527, -2.4252658 , -2.2336398 ,\n",
+       "          0.0249589 ]),\n",
+       "  array([ 7.1987194 ,  3.6211242 , -2.72912859, -2.42285721, -2.20722423,\n",
+       "          0.01226551]),\n",
+       "  array([ 7.17057903e+00,  3.62990755e+00, -2.76022761e+00, -2.41981019e+00,\n",
+       "         -2.18043539e+00,  2.44639452e-04]),\n",
+       "  array([ 7.14307531,  3.63556857, -2.78986012, -2.41611129, -2.15328967,\n",
+       "         -0.01107473]),\n",
+       "  array([ 7.11613457,  3.63821002, -2.81800395, -2.41174457, -2.12580133,\n",
+       "         -0.02167824]),\n",
+       "  array([ 7.08967107,  3.63792742, -2.84463815, -2.40669295, -2.0979836 ,\n",
+       "         -0.03156447]),\n",
+       "  array([ 7.06358894,  3.6348098 , -2.86974393, -2.40093938, -2.06984958,\n",
+       "         -0.0407432 ]),\n",
+       "  array([ 7.03778386,  3.62894043, -2.8933054 , -2.39446783, -2.041413  ,\n",
+       "         -0.04923377]),\n",
+       "  array([ 7.01214456,  3.62039744, -2.91531013, -2.38726401, -2.01268885,\n",
+       "         -0.05706344]),\n",
+       "  array([ 6.98655419,  3.6092544 , -2.93574946, -2.37931603, -1.98369376,\n",
+       "         -0.06426588]),\n",
+       "  array([ 6.96089142,  3.59558075, -2.95461882, -2.37061484, -1.95444638,\n",
+       "         -0.07087977]),\n",
+       "  array([ 6.93503142,  3.57944223, -2.97191772, -2.36115447, -1.92496753,\n",
+       "         -0.0769474 ]),\n",
+       "  array([ 6.9088467 ,  3.56090119, -2.98764979, -2.35093227, -1.89528025,\n",
+       "         -0.08251349]),\n",
+       "  array([ 6.88220779,  3.54001688, -3.00182265, -2.33994887, -1.86540979,\n",
+       "         -0.08762401]),\n",
+       "  array([ 6.85498381,  3.51684565, -3.01444772, -2.32820818, -1.83538349,\n",
+       "         -0.09232516]),\n",
+       "  array([ 6.82704292,  3.49144108, -3.02553994, -2.31571721, -1.80523053,\n",
+       "         -0.0966624 ]),\n",
+       "  array([ 6.79825267,  3.46385414, -3.0351175 , -2.30248584, -1.7749817 ,\n",
+       "         -0.10067963]),\n",
+       "  array([ 6.76848026,  3.43413325, -3.04320144, -2.28852653, -1.74466904,\n",
+       "         -0.10441836]),\n",
+       "  array([ 6.73759276,  3.40232429, -3.04981537, -2.27385399, -1.71432547,\n",
+       "         -0.10791702]),\n",
+       "  array([ 6.70545722,  3.36847069, -3.05498498, -2.25848479, -1.68398443,\n",
+       "         -0.11121028]),\n",
+       "  array([ 6.67194076,  3.33261338, -3.05873774, -2.24243694, -1.65367936,\n",
+       "         -0.11432853]),\n",
+       "  array([ 6.63691056,  3.29479078, -3.06110243, -2.22572949, -1.62344332,\n",
+       "         -0.1172972 ]),\n",
+       "  array([ 6.60023387,  3.25503878, -3.06210881, -2.20838207, -1.59330853,\n",
+       "         -0.12013634]),\n",
+       "  array([ 6.56177796,  3.21339071, -3.0617872 , -2.19041444, -1.56330586,\n",
+       "         -0.12286004]),\n",
+       "  array([ 6.52141004,  3.16987732, -3.06016812, -2.17184608, -1.53346441,\n",
+       "         -0.12547599]),\n",
+       "  array([ 6.47899715,  3.12452669, -3.05728193, -2.1526957 , -1.50381106,\n",
+       "         -0.12798491]),\n",
+       "  array([ 6.43440602,  3.07736426, -3.05315853, -2.13298089, -1.47437   ,\n",
+       "         -0.13038011]),\n",
+       "  array([ 6.38750293,  3.02841274, -3.04782698, -2.11271766, -1.44516235,\n",
+       "         -0.13264689]),\n",
+       "  array([ 6.33815354,  2.9776921 , -3.04131523, -2.09192006, -1.4162057 ,\n",
+       "         -0.13476202]),\n",
+       "  array([ 6.28622267,  2.92521956, -3.03364984, -2.07059983, -1.38751375,\n",
+       "         -0.13669314]),\n",
+       "  array([ 6.2315741 ,  2.87100953, -3.02485566, -2.04876608, -1.35909593,\n",
+       "         -0.13839805]),\n",
+       "  array([ 6.1740703 ,  2.81507362, -3.01495558, -2.02642492, -1.33095701,\n",
+       "         -0.13982403]),\n",
+       "  array([ 6.11357212,  2.7574206 , -3.00397025, -2.00357923, -1.3030968 ,\n",
+       "         -0.14090704]),\n",
+       "  array([ 6.0499385 ,  2.69805643, -2.99191782, -1.98022842, -1.27550979,\n",
+       "         -0.14157084]),\n",
+       "  array([ 5.98302601,  2.6369842 , -2.9788136 , -1.95636817, -1.2481848 ,\n",
+       "         -0.14172605]),\n",
+       "  array([ 5.91268841,  2.57420417, -2.96466977, -1.93199036, -1.2211047 ,\n",
+       "         -0.14126906]),\n",
+       "  array([ 5.83877612,  2.50971375, -2.94949495, -1.9070829 , -1.194246  ,\n",
+       "         -0.14008089]),\n",
+       "  array([ 5.76113551,  2.44350746, -2.93329382, -1.88162977, -1.16757857,\n",
+       "         -0.13802588]),\n",
+       "  array([ 5.67960814,  2.375577  , -2.9160665 , -1.85561107, -1.14106512,\n",
+       "         -0.13495032]),\n",
+       "  array([ 5.59402975,  2.30591118, -2.89780788, -1.82900322, -1.11466083,\n",
+       "         -0.13068087]),\n",
+       "  array([ 5.50422913,  2.23449589, -2.87850674, -1.80177934, -1.08831271,\n",
+       "         -0.12502289]),\n",
+       "  array([ 5.41002664,  2.16131412, -2.85814457, -1.77390989, -1.06195892,\n",
+       "         -0.11775858]),\n",
+       "  array([ 5.31123248,  2.0863458 , -2.83669407, -1.7453635 , -1.03552781,\n",
+       "         -0.10864502]),\n",
+       "  array([ 5.20764456,  2.00956776, -2.81411711, -1.71610838, -1.00893678,\n",
+       "         -0.09741197]),\n",
+       "  array([ 5.0990458 ,  1.9309534 , -2.79036211, -1.68611415, -0.98209066,\n",
+       "         -0.08375949]),\n",
+       "  array([ 4.98520101,  1.85047235, -2.76536047, -1.65535454, -0.95487959,\n",
+       "         -0.06735541]),\n",
+       "  array([ 4.86585291,  1.76808977, -2.73902177, -1.62381106, -0.92717618,\n",
+       "         -0.04783259]),\n",
+       "  array([ 4.74071739,  1.68376521, -2.71122737, -1.59147818, -0.89883163,\n",
+       "         -0.02478587]),\n",
+       "  array([ 4.60947781e+00,  1.59745075e+00, -2.68182175e+00, -1.55837035e+00,\n",
+       "         -8.69670515e-01,  2.23110239e-03]),\n",
+       "  array([ 4.47177814,  1.50908799, -2.65060074, -1.52453167, -0.83948367,\n",
+       "          0.0337094 ]),\n",
+       "  array([ 4.32721496,  1.41860308, -2.61729554, -1.49004898, -0.80801854,\n",
+       "          0.07018862]),\n",
+       "  array([ 4.1753282 ,  1.325899  , -2.58155094, -1.45506975, -0.7749661 ,\n",
+       "          0.11226097]),\n",
+       "  array([ 4.01559077,  1.2308432 , -2.5428955 , -1.41982605, -0.73994301,\n",
+       "          0.16057584]),\n",
+       "  array([ 3.8473974 ,  1.13324856, -2.50070069, -1.38466702, -0.70246751,\n",
+       "          0.2158447 ]),\n",
+       "  array([ 3.67005332,  1.03284432, -2.45412485, -1.35010217, -0.66192663,\n",
+       "          0.27884666]),\n",
+       "  array([ 3.48276368,  0.92923281, -2.40203646, -1.3168596 , -0.61753192,\n",
+       "          0.35043464]),\n",
+       "  array([ 3.28462528,  0.82182713, -2.34291   , -1.28596362, -0.56825955,\n",
+       "          0.43154267]),\n",
+       "  array([ 3.07462255,  0.70976532, -2.27468664, -1.25883928, -0.51276978,\n",
+       "          0.52319461]),\n",
+       "  array([ 2.85163103,  0.59180017, -2.19459421, -1.237454  , -0.44929893,\n",
+       "          0.62651555]),\n",
+       "  array([ 2.61443471,  0.46617382, -2.09892828, -1.22451277, -0.37551555,\n",
+       "          0.74274775]),\n",
+       "  array([ 2.36177336,  0.33050882, -1.98281654, -1.22373052, -0.2883301 ,\n",
+       "          0.87327516]),\n",
+       "  array([ 2.0924633 ,  0.18179214, -1.84002523, -1.24020707, -0.18364463,\n",
+       "          1.01966444]),\n",
+       "  array([ 1.80570754,  0.01661621, -1.66290677, -1.28089393, -0.05602076,\n",
+       "          1.18373752]),\n",
+       "  array([ 1.50191892, -0.16796766, -1.44255224, -1.35498021,  0.10178605,\n",
+       "          1.36770709]),\n",
+       "  array([ 1.18503942, -0.37207516, -1.16881095, -1.4736232 ,  0.29960962,\n",
+       "          1.57444144]),\n",
+       "  array([ 0.86953931, -0.58633231, -0.82798614, -1.64831962,  0.55190896,\n",
+       "          1.80801137]),\n",
+       "  array([ 0.60030872, -0.77390263, -0.38975414, -1.89159215,  0.88828811,\n",
+       "          2.07472138]),\n",
+       "  array([ 0.4764655 , -0.84946206,  0.22134384, -2.23923687,  1.44338066,\n",
+       "          2.37952862])],\n",
+       " True)"
+      ]
+     },
+     "execution_count": 4,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "# Next, we need to create an action model for running and terminal knots. The\n",
+    "# forward dynamics (computed using ABA) are implemented\n",
+    "# inside DifferentialActionModelFullyActuated.\n",
+    "runningModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, runningCostModel))\n",
+    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelFullyActuated(robot.model, terminalCostModel))\n",
+    "\n",
+    "# Defining the time duration for running action models and the terminal one\n",
+    "dt = 1e-3\n",
+    "runningModel.timeStep = dt\n",
+    "\n",
+    "# For this optimal control problem, we define 250 knots (or running action\n",
+    "# models) plus a terminal knot\n",
+    "T = 250\n",
+    "q0 = [0., 0., 0., 0., 0., 0.]\n",
+    "x0 = np.hstack([q0, np.zeros(robot.model.nv)])\n",
+    "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)\n",
+    "\n",
+    "# Creating the DDP solver for this OC problem, defining a logger\n",
+    "ddp = SolverDDP(problem)\n",
+    "# ddp.callback = [CallbackDDPVerbose()]\n",
+    "# ddp.callback.append(CallbackDDPLogger())\n",
+    "\n",
+    "# Solving it with the DDP algorithm\n",
+    "ddp.solve()\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 5,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "from crocoddyl.diagnostic import displayTrajectory\n",
+    "\n",
+    "displayTrajectory(robot, ddp.xs, runningModel.timeStep)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": []
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": []
+  }
+ ],
+ "metadata": {
+  "kernelspec": {
+   "display_name": "Python 2",
+   "language": "python",
+   "name": "python2"
+  },
+  "language_info": {
+   "codemirror_mode": {
+    "name": "ipython",
+    "version": 2
+   },
+   "file_extension": ".py",
+   "mimetype": "text/x-python",
+   "name": "python",
+   "nbconvert_exporter": "python",
+   "pygments_lexer": "ipython2",
+   "version": "2.7.12"
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}
diff --git a/examples/notebooks/kinton_flying_base.ipynb b/examples/notebooks/kinton_flying_base.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..5a43b10c43988236c8380d18f8ee64b0ba27a80a
--- /dev/null
+++ b/examples/notebooks/kinton_flying_base.ipynb
@@ -0,0 +1,5251 @@
+{
+ "cells": [
+  {
+   "cell_type": "code",
+   "execution_count": 111,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "from crocoddyl import *\n",
+    "import pinocchio as pin\n",
+    "import numpy as np\n",
+    "from crocoddyl.diagnostic import displayTrajectory"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 112,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# LOAD ROBOT\n",
+    "robot = loadKinton()\n",
+    "robot.initDisplay(loadModel=True)\n",
+    "robot.display(robot.q0)\n",
+    "\n",
+    "robot.framesForwardKinematics(robot.q0)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 114,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# DEFINE TARGET POSITION\n",
+    "target_pos  = np.array([0,0,1])\n",
+    "target_quat = pin.Quaternion(1, 0, 0, 0)\n",
+    "target_quat.normalize()\n",
+    "\n",
+    "# Plot goal frame\n",
+    "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)\n",
+    "robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])\n",
+    "robot.viewer.gui.refresh()"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 115,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# ACTUATION MODEL\n",
+    "actModel = ActuationModelUAM(robot.model)\n",
+    "\n",
+    "# COST MODEL\n",
+    "# Create a cost model per the running and terminal action model.\n",
+    "runningCostModel = CostModelSum(robot.model, actModel.nu)\n",
+    "terminalCostModel = CostModelSum(robot.model, actModel.nu)\n",
+    "\n",
+    "frameName = 'base_link'\n",
+    "state = StatePinocchio(robot.model)\n",
+    "SE3ref = pin.SE3()\n",
+    "SE3ref.translation = target_pos.reshape(3,1)\n",
+    "SE3ref.rotation = target_quat.matrix()\n",
+    "\n",
+    "\n",
+    "stateWeights = np.array([0] * 3 + [500.] * 3 + [0.01] * (robot.model.nv - 2) + [10] * robot.model.nv)\n",
+    "goalTrackingCost = CostModelFramePlacement(robot.model,\n",
+    "                                           frame=robot.model.getFrameId(frameName),\n",
+    "                                           ref=SE3ref,\n",
+    "                                           nu =actModel.nu)\n",
+    "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=actModel.nu)\n",
+    "uRegCost = CostModelControl(robot.model, nu=robot.model.nv-2)\n",
+    "\n",
+    "# Then let's add the running and terminal cost functions\n",
+    "runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n",
+    "runningCostModel.addCost(name=\"regx\", weight=1e-5, cost=xRegCost)\n",
+    "runningCostModel.addCost(name=\"regu\", weight=1e-7, cost=uRegCost)\n",
+    "terminalCostModel.addCost(name=\"pos\", weight=50, cost=goalTrackingCost)\n",
+    "\n",
+    "# DIFFERENTIAL ACTION MODEL\n",
+    "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n",
+    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 116,
+   "metadata": {
+    "scrolled": true
+   },
+   "outputs": [
+    {
+     "name": "stdout",
+     "output_type": "stream",
+     "text": [
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "   0  7.26954e+00  1.01735e-05  9.62434e+01  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "   1  2.81986e+00  1.25848e-06  8.92713e+00  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "   2  2.79917e+00  5.40348e-09  4.13316e-02  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "   3  2.79916e+00  4.83151e-12  2.97873e-05  1.00000e-09  1.00000e-09   1.0000     1\n"
+     ]
+    },
+    {
+     "data": {
+      "text/plain": [
+       "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.,\n",
+       "         0., 0., 0., 0., 0., 0., 0., 0.]),\n",
+       "  array([-1.33325576e-09,  1.56950264e-20,  6.50683190e-04,  1.03040522e-17,\n",
+       "          9.70119766e-07,  2.23585706e-18,  1.00000000e+00,  3.31193242e-17,\n",
+       "          1.48746279e-17,  1.11334492e-05,  4.18934321e-09, -5.00376766e-06,\n",
+       "         -2.71365688e-17, -1.96449638e-06,  2.23997034e-17,  6.50683190e-01,\n",
+       "          2.06081043e-14,  1.94023953e-03,  4.47171412e-15,  3.31193242e-14,\n",
+       "          1.48746279e-14,  1.11334492e-02,  4.18934321e-06, -5.00376766e-03,\n",
+       "         -2.71365688e-14]),\n",
+       "  array([-9.66517403e-10,  1.53133220e-20,  1.92798373e-03,  2.41256192e-17,\n",
+       "          2.13625709e-06,  3.78907141e-18,  1.00000000e+00,  7.90598990e-17,\n",
+       "          4.43456995e-17,  2.64262320e-05,  1.75599819e-06, -1.04041370e-05,\n",
+       "         -6.66115440e-17, -3.60103850e-06,  4.35953429e-17,  1.27730054e+00,\n",
+       "          2.76431363e-14,  2.33227465e-03,  3.10643149e-15,  4.59405749e-14,\n",
+       "          2.94710715e-14,  1.52927828e-02,  1.75180884e-03, -5.40036933e-03,\n",
+       "         -3.94749752e-14]),\n",
+       "  array([ 2.73770518e-09, -2.22874948e-20,  3.80830264e-03,  3.79343830e-17,\n",
+       "          3.22426492e-06,  3.88851994e-18,  1.00000000e+00,  1.30208255e-16,\n",
+       "          8.41018369e-17,  4.38803188e-05,  5.17451095e-06, -1.49368190e-05,\n",
+       "         -1.08735783e-16, -6.37526830e-06,  7.90917889e-17,  1.88031891e+00,\n",
+       "          2.76175354e-14,  2.17601566e-03,  1.98903559e-16,  5.11483563e-14,\n",
+       "          3.97561374e-14,  1.74540868e-02,  3.41851276e-03, -4.53268199e-03,\n",
+       "         -4.21242389e-14]),\n",
+       "  array([ 1.07979090e-08, -1.11186391e-19,  6.26850601e-03,  4.98290977e-17,\n",
+       "          4.12340250e-06,  2.52507067e-18,  1.00000000e+00,  1.83342344e-16,\n",
+       "          1.30990657e-16,  6.27724549e-05,  1.00155483e-05, -1.83939120e-05,\n",
+       "         -1.49477789e-16, -1.00165523e-05,  1.27017122e-16,  2.46020337e+00,\n",
+       "          2.37894452e-14,  1.79827516e-03, -2.72689006e-15,  5.31340882e-14,\n",
+       "          4.68888198e-14,  1.88921361e-02,  4.84103737e-03, -3.45709300e-03,\n",
+       "         -4.07420065e-14]),\n",
+       "  array([ 2.38075132e-08, -2.59756113e-19,  9.28592317e-03,  5.88012711e-17,\n",
+       "          4.78875371e-06, -5.66591369e-20,  1.00000000e+00,  2.36950470e-16,\n",
+       "          1.83072463e-16,  8.27547422e-05,  1.60546303e-05, -2.08416011e-05,\n",
+       "         -1.87609127e-16, -1.38820890e-05,  1.79213418e-16,  3.01741716e+00,\n",
+       "          1.79443713e-14,  1.33070243e-03, -5.16345192e-15,  5.36081262e-14,\n",
+       "          5.20818065e-14,  1.99822873e-02,  6.03908201e-03, -2.44768915e-03,\n",
+       "         -3.81313377e-14]),\n",
+       "  array([ 4.20186198e-08, -4.71492434e-19,  1.28383446e-02,  6.43780805e-17,\n",
+       "          5.20775326e-06, -3.55412845e-18,  1.00000000e+00,  2.90254883e-16,\n",
+       "          2.39171048e-16,  1.03608476e-04,  2.31049291e-05, -2.23980327e-05,\n",
+       "         -2.22976720e-16, -1.73006986e-05,  2.25848647e-16,  3.55242140e+00,\n",
+       "          1.11536524e-14,  8.37999089e-04, -6.99493448e-15,  5.33044134e-14,\n",
+       "          5.60985846e-14,  2.08537337e-02,  7.05029874e-03, -1.55643150e-03,\n",
+       "         -3.53675923e-14]),\n",
+       "  array([ 6.54049443e-08, -7.45770457e-19,  1.69040195e-02,  6.64300142e-17,\n",
+       "          5.38603111e-06, -7.68148349e-18,  1.00000000e+00,  3.42818233e-16,\n",
+       "          2.98566282e-16,  1.25170642e-04,  3.10128574e-05, -2.31768783e-05,\n",
+       "         -2.55754848e-16, -1.96845588e-05,  2.57545187e-16,  4.06567491e+00,\n",
+       "          4.10390909e-15,  3.56555702e-04, -8.25471167e-15,  5.25633497e-14,\n",
+       "          5.93952340e-14,  2.15621666e-02,  7.90792831e-03, -7.78845624e-04,\n",
+       "         -3.27781282e-14]),\n",
+       "  array([ 9.37189432e-08, -1.07860667e-18,  2.14616535e-02,  6.50538818e-17,\n",
+       "          5.33998793e-06, -1.21945430e-17,  1.00000000e+00,  3.94371323e-16,\n",
+       "          3.60819442e-16,  1.47309040e-04,  3.96512100e-05, -2.32762636e-05,\n",
+       "         -2.86172246e-16, -2.05712701e-05,  2.66419341e-16,  4.55763400e+00,\n",
+       "         -2.75221558e-15, -9.20863578e-05, -9.02612766e-15,  5.15530896e-14,\n",
+       "          6.22531600e-14,  2.21383976e-02,  8.63835265e-03, -9.93853449e-05,\n",
+       "         -3.04173982e-14]),\n",
+       "  array([ 1.26544314e-07, -1.46340811e-18,  2.64904057e-02,  6.04942872e-17,\n",
+       "          5.09225187e-06, -1.68952420e-17,  1.00000000e+00,  4.44733122e-16,\n",
+       "          4.25670637e-16,  1.69911998e-04,  4.89132225e-05, -2.27791337e-05,\n",
+       "         -3.14429579e-16, -1.96357789e-05,  2.46549389e-16,  5.02875225e+00,\n",
+       "         -9.11913289e-15, -4.95472126e-04, -9.40141445e-15,  5.03617991e-14,\n",
+       "          6.48511950e-14,  2.26029577e-02,  9.26201247e-03,  4.97129880e-04,\n",
+       "         -2.82573326e-14]),\n",
+       "  array([ 1.63343133e-07, -1.89167733e-18,  3.19698861e-02,  5.30876571e-17,\n",
+       "          4.66867121e-06, -2.16280124e-17,  1.00000000e+00,  4.93772162e-16,\n",
+       "          4.92972745e-16,  1.92883004e-04,  5.87079512e-05, -2.17558907e-05,\n",
+       "         -3.40684441e-16, -1.66859660e-05,  1.94101190e-16,  5.47948032e+00,\n",
+       "         -1.48131976e-14, -8.47161308e-04, -9.46556511e-15,  4.90390402e-14,\n",
+       "          6.73021078e-14,  2.29710060e-02,  9.79472866e-03,  1.02324306e-03,\n",
+       "         -2.62548620e-14]),\n",
+       "  array([ 2.03497107e-07, -2.35364964e-18,  3.78801518e-02,  4.32212521e-17,\n",
+       "          4.09626796e-06, -2.62735603e-17,  1.00000000e+00,  5.41387428e-16,\n",
+       "          5.62645417e-16,  2.16137330e-04,  6.89567918e-05, -2.02669972e-05,\n",
+       "         -3.65057047e-16, -1.16491464e-05,  1.07239620e-16,  5.91026577e+00,\n",
+       "         -1.97327419e-14, -1.14480651e-03, -9.29112717e-15,  4.76152657e-14,\n",
+       "          6.96726726e-14,  2.32543266e-02,  1.02488406e-02,  1.48889348e-03,\n",
+       "         -2.43726066e-14]),\n",
+       "  array([ 2.46342773e-07, -2.83884925e-18,  4.42017047e-02,  3.13030195e-17,\n",
+       "          3.40184674e-06, -3.07423748e-17,  1.00000000e+00,  5.87498686e-16,\n",
+       "          6.34641870e-16,  2.39599684e-04,  7.95908790e-05, -1.83650847e-05,\n",
+       "         -3.87640294e-16, -4.55406312e-06, -1.40893940e-17,  6.32155288e+00,\n",
+       "         -2.38363921e-14, -1.38884243e-03, -8.93766662e-15,  4.61112580e-14,\n",
+       "          7.19964527e-14,  2.34623532e-02,  1.06340872e-02,  1.90191248e-03,\n",
+       "         -2.25832466e-14]),\n",
+       "  array([ 2.91200834e-07, -3.33655937e-18,  5.09154872e-02,  1.77396817e-17,\n",
+       "          2.61106855e-06, -3.49688820e-17,  1.00000000e+00,  6.32041443e-16,\n",
+       "          7.08924948e-16,  2.63202486e-04,  9.05491461e-05, -1.60965671e-05,\n",
+       "         -4.08509089e-16,  4.48865602e-06, -1.68446481e-16,  6.71378245e+00,\n",
+       "         -2.71265981e-14, -1.58155639e-03, -8.45305703e-15,  4.45427569e-14,\n",
+       "          7.42830782e-14,  2.36028023e-02,  1.09582671e-02,  2.26851760e-03,\n",
+       "         -2.08687957e-14]),\n",
+       "  array([ 3.37399977e-07, -3.83620724e-18,  5.80028788e-02,  2.92122959e-18,\n",
+       "          1.74785894e-06, -3.89065140e-17,  1.00000000e+00,  6.74964175e-16,\n",
+       "          7.85450441e-16,  2.86884596e-04,  1.01776875e-04, -1.35028554e-05,\n",
+       "         -4.27727719e-16,  1.53057164e-05, -3.53213634e-16,  7.08739170e+00,\n",
+       "         -2.96368234e-14, -1.72641921e-03, -7.87531079e-15,  4.29227324e-14,\n",
+       "          7.65254929e-14,  2.36821099e-02,  1.12277286e-02,  2.59371177e-03,\n",
+       "         -1.92186291e-14]),\n",
+       "  array([ 3.84295650e-07, -4.32766892e-18,  6.54456929e-02, -1.27895626e-17,\n",
+       "          8.34058194e-07, -4.25236899e-17,  1.00000000e+00,  7.16226673e-16,\n",
+       "          8.64156195e-16,  3.10590343e-04,  1.13224607e-04, -1.06212681e-05,\n",
+       "         -4.45355206e-16,  2.76789448e-05, -5.64906806e-16,  7.44281406e+00,\n",
+       "         -3.14215005e-14, -1.82760150e-03, -7.23440149e-15,  4.12624985e-14,\n",
+       "          7.87057535e-14,  2.37057474e-02,  1.14477326e-02,  2.88158723e-03,\n",
+       "         -1.76274879e-14]),\n",
+       "  array([ 4.31284359e-07, -4.80150125e-18,  7.32261719e-02, -2.90636904e-17,\n",
+       "         -1.10754325e-07, -4.58005985e-17,  1.00000000e+00,  7.55798931e-16,\n",
+       "          9.44955850e-16,  3.34268799e-04,  1.24847329e-04, -7.48571560e-06,\n",
+       "         -4.61448994e-16,  4.13610574e-05, -7.99466796e-16,  7.78047904e+00,\n",
+       "         -3.25481698e-14, -1.88962504e-03, -6.55386853e-15,  3.95722579e-14,\n",
+       "          8.07996550e-14,  2.36784555e-02,  1.16227219e-02,  3.13555253e-03,\n",
+       "         -1.60937878e-14]),\n",
+       "  array([ 4.77814023e-07, -5.24910974e-18,  8.13269841e-02, -4.56094245e-17,\n",
+       "         -1.06931108e-06, -4.87266478e-17,  1.00000000e+00,  7.93660298e-16,\n",
+       "          1.02773619e-15,  3.57873217e-04,  1.36603850e-04, -4.12721458e-06,\n",
+       "         -4.76067271e-16,  5.60891522e-05, -1.05251652e-15,  8.10081213e+00,\n",
+       "         -3.30913811e-14, -1.91711351e-03, -5.85215055e-15,  3.78613669e-14,\n",
+       "          8.27803418e-14,  2.36044182e-02,  1.17565207e-02,  3.35850102e-03,\n",
+       "         -1.46182768e-14]),\n",
+       "  array([ 5.23390982e-07, -5.66286116e-18,  8.97312187e-02, -6.21734888e-17,\n",
+       "         -2.02661962e-06, -5.12984517e-17,  1.00000000e+00,  8.29798766e-16,\n",
+       "          1.11235723e-15,  3.81360608e-04,  1.48456332e-04, -5.74278806e-07,\n",
+       "         -4.89270281e-16,  7.15958873e-05, -1.31957845e-15,  8.40423460e+00,\n",
+       "         -3.31280407e-14, -1.91461708e-03, -5.14365965e-15,  3.61384674e-14,\n",
+       "          8.46210428e-14,  2.34873917e-02,  1.18524824e-02,  3.55293577e-03,\n",
+       "         -1.32030097e-14]),\n",
+       "  array([ 5.67584157e-07, -6.03615004e-18,  9.84223821e-02, -7.85405045e-17,\n",
+       "         -2.96986563e-06, -5.35182421e-17,  1.00000000e+00,  8.64210321e-16,\n",
+       "          1.19865428e-15,  4.04691410e-04,  1.60369932e-04,  3.14678313e-06,\n",
+       "         -5.01120868e-16,  8.76184450e-05, -1.59625028e-15,  8.69116345e+00,\n",
+       "         -3.27339437e-14, -1.88649202e-03, -4.43963190e-15,  3.44115551e-14,\n",
+       "          8.62970504e-14,  2.33308013e-02,  1.19135993e-02,  3.72106194e-03,\n",
+       "         -1.18505870e-14]),\n",
+       "  array([ 6.10026870e-07, -6.36342723e-18,  1.07384393e-01, -9.45311883e-17,\n",
+       "         -3.88827644e-06, -5.53926147e-17,  1.00000000e+00,  8.96898338e-16,\n",
+       "          1.28644135e-15,  4.27829221e-04,  1.72312515e-04,  7.01163817e-06,\n",
+       "         -5.11684477e-16,  1.03905460e-04, -1.87833968e-15,  8.96201124e+00,\n",
+       "         -3.19812806e-14, -1.83682162e-03, -3.74879439e-15,  3.26880173e-14,\n",
+       "          8.77870638e-14,  2.31378111e-02,  1.19425837e-02,  3.86485504e-03,\n",
+       "         -1.05636093e-14]),\n",
+       "  array([ 6.50416771e-07, -6.64019832e-18,  1.16601579e-01, -1.09999700e-16,\n",
+       "         -4.77296037e-06, -5.69315341e-17,  1.00000000e+00,  9.27872995e-16,\n",
+       "          1.37551535e-15,  4.50740597e-04,  1.84254442e-04,  1.09977493e-05,\n",
+       "         -5.21028783e-16,  1.20222131e-04, -2.16196132e-15,  9.21718602e+00,\n",
+       "         -3.09369370e-14, -1.76936786e-03, -3.07788582e-15,  3.09746572e-14,\n",
+       "          8.90740063e-14,  2.29113758e-02,  1.19419267e-02,  3.98611116e-03,\n",
+       "         -9.34430593e-15]),\n",
+       "  array([ 6.88514256e-07, -6.86299846e-18,  1.26058671e-01, -1.24830460e-16,\n",
+       "         -5.61673352e-06, -5.81475431e-17,  1.00000000e+00,  9.57150707e-16,\n",
+       "          1.46566078e-15,  4.73394874e-04,  1.96168384e-04,  1.50842330e-05,\n",
+       "         -5.29223084e-16,  1.36353768e-04, -2.44360034e-15,  9.45709120e+00,\n",
+       "         -2.96614350e-14, -1.68754631e-03, -2.43206199e-15,  2.92777119e-14,\n",
+       "          9.01454203e-14,  2.26542777e-02,  1.19139418e-02,  4.08648367e-03,\n",
+       "         -8.19430065e-15]),\n",
+       "  array([ 7.24139735e-07, -7.02934938e-18,  1.35740796e-01, -1.38934693e-16,\n",
+       "         -6.41394253e-06, -5.90551287e-17,  1.00000000e+00,  9.84753574e-16,\n",
+       "          1.55665431e-15,  4.95764026e-04,  2.08029179e-04,  1.92517429e-05,\n",
+       "         -5.36337567e-16,  1.52107995e-04, -2.72014723e-15,  9.68212548e+00,\n",
+       "         -2.82083850e-14, -1.59441802e-03, -1.81521172e-15,  2.76028667e-14,\n",
+       "          9.09935305e-14,  2.23691517e-02,  1.18607957e-02,  4.16750993e-03,\n",
+       "         -7.11448373e-15]),\n",
+       "  array([ 7.57170038e-07, -7.13770354e-18,  1.45633479e-01, -1.52246902e-16,\n",
+       "         -7.16028955e-06, -5.96702120e-17,  1.00000000e+00,  1.01070884e-15,\n",
+       "          1.64826936e-15,  5.17822529e-04,  2.19813710e-04,  2.34823733e-05,\n",
+       "         -5.42442533e-16,  1.67315874e-04, -2.98890942e-15,  9.89268274e+00,\n",
+       "         -2.66243378e-14, -1.49269403e-03, -1.23020332e-15,  2.59552691e-14,\n",
+       "          9.16150573e-14,  2.20585034e-02,  1.17845303e-02,  4.23063040e-03,\n",
+       "         -6.10496613e-15]),\n",
+       "  array([ 7.87534206e-07, -7.18737930e-18,  1.55722631e-01, -1.64721411e-16,\n",
+       "         -7.85266394e-06, -6.00097346e-17,  1.00000000e+00,  1.03504838e-15,\n",
+       "          1.74028021e-15,  5.39547250e-04,  2.31500788e-04,  2.77595755e-05,\n",
+       "         -5.47607627e-16,  1.81832137e-04, -3.24760454e-15,  1.00891520e+01,\n",
+       "         -2.49489401e-14, -1.38474878e-03, -6.79077479e-16,  2.43395418e-14,\n",
+       "          9.20108493e-14,  2.17247202e-02,  1.16870778e-02,  4.27720215e-03,\n",
+       "         -5.16509386e-15]),\n",
+       "  array([ 8.15208888e-07, -7.17849028e-18,  1.65994548e-01, -1.76329106e-16,\n",
+       "         -8.48898384e-06, -6.00913204e-17,  1.00000000e+00,  1.05780818e-15,\n",
+       "          1.83246561e-15,  5.60917328e-04,  2.43071059e-04,  3.20680839e-05,\n",
+       "         -5.51901132e-16,  1.95534736e-04, -3.49434026e-15,  1.02719172e+01,\n",
+       "         -2.32153149e-14, -1.27263980e-03, -1.63198851e-16,  2.27597964e-14,\n",
+       "          9.21853952e-14,  2.13700785e-02,  1.15702714e-02,  4.30850838e-03,\n",
+       "         -4.29350526e-15]),\n",
+       "  array([ 8.40213511e-07, -7.11187159e-18,  1.76435905e-01, -1.87054441e-16,\n",
+       "         -9.06804951e-06, -5.99329973e-17,  1.00000000e+00,  1.07902783e-15,\n",
+       "          1.92461187e-15,  5.81914076e-04,  2.54506910e-04,  3.63938486e-05,\n",
+       "         -5.55389349e-16,  2.08323883e-04, -3.72758482e-15,  1.04413575e+01,\n",
+       "         -2.14505974e-14, -1.15813134e-03,  3.16624195e-16,  2.12196474e-14,\n",
+       "          9.21462628e-14,  2.09967476e-02,  1.14358515e-02,  4.32576476e-03,\n",
+       "         -3.48821698e-15]),\n",
+       "  array([ 8.62605351e-07, -6.98900469e-18,  1.87033752e-01, -1.96892761e-16,\n",
+       "         -9.58940969e-06, -5.95529669e-17,  1.00000000e+00,  1.09875006e-15,\n",
+       "          2.01651538e-15,  6.02520867e-04,  2.65792381e-04,  4.07239725e-05,\n",
+       "         -5.58136077e-16,  2.20120730e-04, -3.94613215e-15,  1.05978466e+01,\n",
+       "         -1.96765698e-14, -1.04272037e-03,  7.60044178e-16,  1.97222280e-14,\n",
+       "          9.19035073e-14,  2.06067917e-02,  1.12854707e-02,  4.33012384e-03,\n",
+       "         -2.74672710e-15]),\n",
+       "  array([ 8.82474641e-07, -6.81194245e-18,  1.97775505e-01, -2.05847968e-16,\n",
+       "         -1.00532415e-05, -5.89694125e-17,  1.00000000e+00,  1.11702026e-15,\n",
+       "          2.10798446e-15,  6.22723038e-04,  2.76913077e-04,  4.50466503e-05,\n",
+       "         -5.60202203e-16,  2.30865803e-04, -4.14906446e-15,  1.07417533e+01,\n",
+       "         -1.79103473e-14, -9.27663535e-04,  1.16709784e-15,  1.82702065e-14,\n",
+       "          9.14690798e-14,  2.02021708e-02,  1.11206959e-02,  4.32267782e-03,\n",
+       "         -2.06612594e-15]),\n",
+       "  array([ 8.99939777e-07, -6.58323552e-18,  2.08648947e-01, -2.13930539e-16,\n",
+       "         -1.04602435e-05, -5.82003381e-17,  1.00000000e+00,  1.13388607e-15,\n",
+       "          2.19884072e-15,  6.42507779e-04,  2.87856088e-04,  4.93511108e-05,\n",
+       "         -5.61645410e-16,  2.40517310e-04, -4.33571488e-15,  1.08734412e+01,\n",
+       "         -1.61650794e-14, -8.14004092e-04,  1.53814378e-15,  1.68658048e-14,\n",
+       "          9.08562617e-14,  1.97847405e-02,  1.09430106e-02,  4.30446051e-03,\n",
+       "         -1.44320766e-15]),\n",
+       "  array([ 9.15142709e-07, -6.30586075e-18,  2.19642215e-01, -2.21155886e-16,\n",
+       "         -1.08115425e-05, -5.72634330e-17,  1.00000000e+00,  1.14939689e-15,\n",
+       "          2.28891986e-15,  6.61864031e-04,  2.98609903e-04,  5.36275594e-05,\n",
+       "         -5.62519987e-16,  2.49049388e-04, -4.50563189e-15,  1.09932686e+01,\n",
+       "         -1.44506330e-14, -7.02597997e-04,  1.87381102e-15,  1.55108182e-14,\n",
+       "          9.00791430e-14,  1.93562525e-02,  1.07538152e-02,  4.27644858e-03,\n",
+       "         -8.74576985e-16]),\n",
+       "  array([ 9.28244548e-07, -5.98315231e-18,  2.30743803e-01, -2.27543034e-16,\n",
+       "         -1.11086118e-05, -5.61759584e-17,  1.00000000e+00,  1.16360352e-15,\n",
+       "          2.37807202e-15,  6.80782385e-04,  3.09164332e-04,  5.78671220e-05,\n",
+       "         -5.62876734e-16,  2.56450367e-04, -4.65854693e-15,  1.11015883e+01,\n",
+       "         -1.27742381e-14, -5.94138630e-04,  2.17495583e-15,  1.42066371e-14,\n",
+       "          8.91521574e-14,  1.89183544e-02,  1.05544288e-02,  4.23956261e-03,\n",
+       "         -3.56747195e-16]),\n",
+       "  array([ 9.39421447e-07, -5.61873583e-18,  2.41942551e-01, -2.33113599e-16,\n",
+       "         -1.13532017e-05, -5.49546521e-17,  1.00000000e+00,  1.17655779e-15,\n",
+       "          2.46616170e-15,  6.99254976e-04,  3.19510421e-04,  6.20617900e-05,\n",
+       "         -5.62762961e-16,  2.62721089e-04, -4.79434585e-15,  1.11987480e+01,\n",
+       "         -1.11410760e-14, -4.89179714e-04,  2.44262500e-15,  1.29542700e-14,\n",
+       "          8.80896829e-14,  1.84725905e-02,  1.03460897e-02,  4.19466801e-03,\n",
+       "          1.13773343e-16]),\n",
+       "  array([ 9.48860763e-07, -5.21646595e-18,  2.53227642e-01, -2.37891026e-16,\n",
+       "         -1.15472798e-05, -5.36156492e-17,  1.00000000e+00,  1.18831216e-15,\n",
+       "          2.55306741e-15,  7.17275379e-04,  3.29640378e-04,  6.62043660e-05,\n",
+       "         -5.62222553e-16,  2.67873311e-04, -4.91304467e-15,  1.12850900e+01,\n",
+       "         -9.55480174e-15, -3.88156192e-04,  2.67802384e-15,  1.17543687e-14,\n",
+       "          8.69057099e-14,  1.80204029e-02,  1.01299565e-02,  4.14257600e-03,\n",
+       "          5.40407646e-16]),\n",
+       "  array([ 9.56757518e-07, -4.78036748e-18,  2.64588593e-01, -2.41900046e-16,\n",
+       "         -1.16929812e-05, -5.21744168e-17,  1.00000000e+00,  1.19891941e-15,\n",
+       "          2.63868099e-15,  7.34838512e-04,  3.39547488e-04,  7.02884107e-05,\n",
+       "         -5.61296103e-16,  2.71928226e-04, -5.01476969e-15,  1.13609512e+01,\n",
+       "         -8.01799256e-15, -2.91402909e-04,  2.88248803e-15,  1.06072531e-14,\n",
+       "          8.56135795e-14,  1.75631334e-02,  9.90711030e-03,  4.08404475e-03,\n",
+       "          9.26450331e-16]),\n",
+       "  array([ 9.63311176e-07, -4.31458024e-18,  2.76015256e-01, -2.45166330e-16,\n",
+       "         -1.17925668e-05, -5.06457018e-17,  1.00000000e+00,  1.20843235e-15,\n",
+       "          2.72290678e-15,  7.51940538e-04,  3.49226044e-04,  7.43081914e-05,\n",
+       "         -5.60021081e-16,  2.74915100e-04, -5.09974164e-15,  1.14266630e+01,\n",
+       "         -6.53252090e-15, -1.99171069e-04,  3.05745837e-15,  9.51293883e-15,\n",
+       "          8.42257881e-14,  1.71020254e-02,  9.67855583e-03,  4.01978071e-03,\n",
+       "          1.27502158e-15]),\n",
+       "  array([ 9.68722733e-07, -3.82330793e-18,  2.87497807e-01, -2.47716278e-16,\n",
+       "         -1.18483880e-05, -4.90434892e-17,  1.00000000e+00,  1.21690352e-15,\n",
+       "          2.80566063e-15,  7.68578765e-04,  3.58671268e-04,  7.82586316e-05,\n",
+       "         -5.58432047e-16,  2.76870036e-04, -5.16826349e-15,  1.14825514e+01,\n",
+       "         -5.09985267e-15, -1.11642477e-04,  3.20445788e-15,  8.47116410e-15,\n",
+       "          8.27538536e-14,  1.66382278e-02,  9.44522429e-03,  3.95044020e-03,\n",
+       "          1.58903425e-15]),\n",
+       "  array([ 9.73192115e-07, -3.31077084e-18,  2.99026744e-01, -2.49576936e-16,\n",
+       "         -1.18628588e-05, -4.73809722e-17,  1.00000000e+00,  1.22438494e-15,\n",
+       "          2.88686887e-15,  7.84751563e-04,  3.67879244e-04,  8.21352628e-05,\n",
+       "         -5.56560874e-16,  2.77834852e-04, -5.22071141e-15,  1.15289370e+01,\n",
+       "         -3.72127439e-15, -2.89416908e-05,  3.32507093e-15,  7.48141730e-15,\n",
+       "          8.12082391e-14,  1.61727976e-02,  9.20797588e-03,  3.87663120e-03,\n",
+       "          1.87117322e-15]),\n",
+       "  array([ 9.76915880e-07, -2.78116277e-18,  3.10592879e-01, -2.50775982e-16,\n",
+       "         -1.18384319e-05, -4.56705305e-17,  1.00000000e+00,  1.23092790e-15,\n",
+       "          2.96646720e-15,  8.00458268e-04,  3.76846847e-04,  8.59341782e-05,\n",
+       "         -5.54436988e-16,  2.77856088e-04, -5.25752811e-15,  1.15661348e+01,\n",
+       "         -2.39805462e-15,  4.88538125e-05,  3.42092402e-15,  6.54296461e-15,\n",
+       "          7.95983249e-14,  1.57067048e-02,  8.96760288e-03,  3.79891540e-03,\n",
+       "          2.12388558e-15]),\n",
+       "  array([ 9.80085218e-07, -2.23861204e-18,  3.22187333e-01, -2.51341773e-16,\n",
+       "         -1.17775793e-05, -4.39237184e-17,  1.00000000e+00,  1.23658278e-15,\n",
+       "          3.04439962e-15,  8.15699104e-04,  3.85571680e-04,  8.96519887e-05,\n",
+       "         -5.52087608e-16,  2.76984105e-04, -5.27921817e-15,  1.15944545e+01,\n",
+       "         -1.13154668e-15,  1.21705258e-04,  3.49366813e-15,  5.65487707e-15,\n",
+       "          7.79324232e-14,  1.52408364e-02,  8.72483298e-03,  3.71781042e-03,\n",
+       "          2.34938029e-15]),\n",
+       "  array([ 9.82884236e-07, -1.68714666e-18,  3.33801534e-01, -2.51303410e-16,\n",
+       "         -1.16827764e-05, -4.21512605e-17,  1.00000000e+00,  1.24139883e-15,\n",
+       "          3.12061745e-15,  8.30475106e-04,  3.94052013e-04,  9.32857808e-05,\n",
+       "         -5.49537972e-16,  2.75272287e-04, -5.28634446e-15,  1.16142002e+01,\n",
+       "          7.67595744e-17,  1.89605807e-04,  3.54496258e-15,  4.81605701e-15,\n",
+       "          7.62178261e-14,  1.47760012e-02,  8.48033283e-03,  3.63379216e-03,\n",
+       "          2.54963572e-15]),\n",
+       "  array([ 9.85488515e-07, -1.13066379e-18,  3.45427204e-01, -2.50690811e-16,\n",
+       "         -1.15564888e-05, -4.03630550e-17,  1.00000000e+00,  1.24542410e-15,\n",
+       "          3.19507833e-15,  8.44788041e-04,  4.02286725e-04,  9.68330781e-05,\n",
+       "         -5.46811559e-16,  2.72776323e-04, -5.27952526e-15,  1.16256707e+01,\n",
+       "          1.22522857e-15,  2.52575203e-04,  3.57646020e-15,  4.02526355e-15,\n",
+       "          7.44608812e-14,  1.43129350e-02,  8.23471181e-03,  3.54729728e-03,\n",
+       "          2.72641350e-15]),\n",
+       "  array([ 9.88063920e-07, -5.72903279e-19,  3.57056363e-01, -2.49534774e-16,\n",
+       "         -1.14011610e-05, -3.85681836e-17,  1.00000000e+00,  1.24870523e-15,\n",
+       "          3.26774541e-15,  8.58640346e-04,  4.10275250e-04,  1.00291804e-04,\n",
+       "         -5.43930282e-16,  2.69553566e-04, -5.25943165e-15,  1.16291591e+01,\n",
+       "          2.31210418e-15,  3.10655611e-04,  3.58979393e-15,  3.28113673e-15,\n",
+       "          7.26670851e-14,  1.38523055e-02,  7.98852579e-03,  3.45872581e-03,\n",
+       "          2.88127701e-15]),\n",
+       "  array([ 9.90765660e-07, -1.74254677e-20,  3.68681316e-01, -2.47867007e-16,\n",
+       "         -1.12192068e-05, -3.67749276e-17,  1.00000000e+00,  1.25128745e-15,\n",
+       "          3.33858660e-15,  8.72035063e-04,  4.18017531e-04,  1.03660248e-04,\n",
+       "         -5.40914669e-16,  2.65662455e-04, -5.22678446e-15,  1.16249531e+01,\n",
+       "          3.33556102e-15,  3.63908466e-04,  3.58656473e-15,  2.58222031e-15,\n",
+       "          7.08411915e-14,  1.33947172e-02,  7.74228104e-03,  3.36844368e-03,\n",
+       "          3.01561335e-15]),\n",
+       "  array([ 9.93737570e-07,  5.32407031e-19,  3.80294652e-01, -2.45720132e-16,\n",
+       "         -1.10130007e-05, -3.49907893e-17,  1.00000000e+00,  1.25321444e-15,\n",
+       "          3.40757393e-15,  8.84975780e-04,  4.25513969e-04,  1.06937033e-04,\n",
+       "         -5.37784011e-16,  2.61161986e-04, -5.18235089e-15,  1.16133352e+01,\n",
+       "          4.29377412e-15,  4.12412136e-04,  3.56833071e-15,  1.92698263e-15,\n",
+       "          6.89873241e-14,  1.29407170e-02,  7.49643800e-03,  3.27678528e-03,\n",
+       "          3.13065710e-15]),\n",
+       "  array([ 9.97111596e-07,  1.07344356e-18,  3.91889234e-01, -2.43127644e-16,\n",
+       "         -1.07848706e-05, -3.32225181e-17,  1.00000000e+00,  1.25452827e-15,\n",
+       "          3.47468302e-15,  8.97466579e-04,  4.32765384e-04,  1.10121089e-04,\n",
+       "         -5.34556496e-16,  2.56111233e-04, -5.12694027e-15,  1.15945820e+01,\n",
+       "          5.18500001e-15,  4.56260213e-04,  3.53659733e-15,  1.31383542e-15,\n",
+       "          6.71090926e-14,  1.24907984e-02,  7.25141503e-03,  3.18405605e-03,\n",
+       "          3.22751500e-15]),\n",
+       "  array([ 1.00100748e-06,  1.60275585e-18,  4.03458199e-01, -2.40123823e-16,\n",
+       "         -1.05370904e-05, -3.14761419e-17,  1.00000000e+00,  1.25526942e-15,\n",
+       "          3.53989273e-15,  9.09511985e-04,  4.39772976e-04,  1.13211624e-04,\n",
+       "         -5.31249306e-16,  2.50568914e-04, -5.06139889e-15,  1.15689652e+01,\n",
+       "          6.00766283e-15,  4.95560294e-04,  3.49280811e-15,  7.41149721e-16,\n",
+       "          6.52097045e-14,  1.20454064e-02,  7.00759197e-03,  3.09053483e-03,\n",
+       "          3.30719037e-15]),\n",
+       "  array([ 1.00553263e-06,  2.11764490e-18,  4.14994950e-01, -2.36743613e-16,\n",
+       "         -1.02718739e-05, -2.97570025e-17,  1.00000000e+00,  1.25547669e-15,\n",
+       "          3.60318480e-15,  9.21116927e-04,  4.46538290e-04,  1.16208100e-04,\n",
+       "         -5.27878700e-16,  2.44592985e-04, -4.98660409e-15,  1.15367508e+01,\n",
+       "          6.76043995e-15,  5.30433080e-04,  3.43833503e-15,  2.07267724e-16,\n",
+       "          6.32920715e-14,  1.16049423e-02,  6.76531358e-03,  2.99647624e-03,\n",
+       "          3.37060645e-15]),\n",
+       "  array([ 1.01078211e-06,  2.61564438e-18,  4.26493149e-01, -2.33022450e-16,\n",
+       "         -9.99136805e-06, -2.80697428e-17,  1.00000000e+00,  1.25518734e-15,\n",
+       "          3.66454370e-15,  9.32286694e-04,  4.53063183e-04,  1.19110213e-04,\n",
+       "         -5.24460072e-16,  2.38240273e-04, -4.90345733e-15,  1.14981994e+01,\n",
+       "          7.44234277e-15,  5.61011699e-04,  3.37457558e-15, -2.89351993e-16,\n",
+       "          6.13589054e-14,  1.11697671e-02,  6.52489275e-03,  2.90211285e-03,\n",
+       "          3.41862810e-15]),\n",
+       "  array([ 1.01683880e-06,  3.09452107e-18,  4.37946715e-01, -2.28996064e-16,\n",
+       "         -9.69764749e-06, -2.64184252e-17,  1.00000000e+00,  1.25443689e-15,\n",
+       "          3.72395651e-15,  9.43026900e-04,  4.59349796e-04,  1.21917870e-04,\n",
+       "         -5.21007991e-16,  2.31566136e-04, -4.81287655e-15,  1.14535664e+01,\n",
+       "          8.05278843e-15,  5.87441135e-04,  3.30269163e-15, -7.50449375e-16,\n",
+       "          5.94128037e-14,  1.07402060e-02,  6.28661346e-03,  2.80765725e-03,\n",
+       "          3.45208053e-15]),\n",
+       "  array([ 1.02377368e-06,  3.55227233e-18,  4.49349817e-01, -2.24700242e-16,\n",
+       "         -9.39270865e-06, -2.48065683e-17,  1.00000000e+00,  1.25325914e-15,\n",
+       "          3.78141283e-15,  9.53343452e-04,  4.65400530e-04,  1.24631174e-04,\n",
+       "         -5.17536224e-16,  2.24624153e-04, -4.71578793e-15,  1.14031017e+01,\n",
+       "          8.59166017e-15,  6.09877680e-04,  3.22377016e-15, -1.17774509e-15,\n",
+       "          5.74563215e-14,  1.03165514e-02,  6.05073352e-03,  2.71330389e-03,\n",
+       "          3.47176688e-15]),\n",
+       "  array([ 1.03164620e-06,  3.98712115e-18,  4.60696867e-01, -2.20170571e-16,\n",
+       "         -9.07846447e-06, -2.32371014e-17,  1.00000000e+00,  1.25168643e-15,\n",
+       "          3.83690486e-15,  9.63242518e-04,  4.71218017e-04,  1.27250405e-04,\n",
+       "         -5.14057742e-16,  2.17465845e-04, -4.61311722e-15,  1.13470502e+01,\n",
+       "          9.05935445e-15,  6.28488350e-04,  3.13898992e-15, -1.57271800e-15,\n",
+       "          5.54920302e-14,  9.89906621e-03,  5.81748705e-03,  2.61923083e-03,\n",
+       "          3.47848215e-15]),\n",
+       "  array([ 1.04050473e-06,  4.39750894e-18,  4.71982519e-01, -2.15442172e-16,\n",
+       "         -8.75673936e-06, -2.17124735e-17,  1.00000000e+00,  1.24974943e-15,\n",
+       "          3.89042742e-15,  9.72730505e-04,  4.76805103e-04,  1.29776006e-04,\n",
+       "         -5.10584719e-16,  2.10140425e-04, -4.50578079e-15,  1.12856513e+01,\n",
+       "          9.45681257e-15,  6.43450216e-04,  3.04931174e-15, -1.93699130e-15,\n",
+       "          5.35225627e-14,  9.48798672e-03,  5.58708669e-03,  2.52560126e-03,\n",
+       "          3.47302322e-15]),\n",
+       "  array([ 1.05038714e-06,  4.78208653e-18,  4.83201658e-01, -2.10549409e-16,\n",
+       "         -8.42926456e-06, -2.02346282e-17,  1.00000000e+00,  1.24747745e-15,\n",
+       "          3.94197807e-15,  9.81814030e-04,  4.82164829e-04,  1.32208571e-04,\n",
+       "         -5.07128521e-16,  2.02694577e-04, -4.39467677e-15,  1.12191392e+01,\n",
+       "          9.78553750e-15,  6.54949608e-04,  2.95574601e-15, -2.27198456e-15,\n",
+       "          5.15506445e-14,  9.08352488e-03,  5.35972563e-03,  2.43256491e-03,\n",
+       "          3.45619763e-15]),\n",
+       "  array([ 1.06132134e-06,  5.13970358e-18,  4.94349401e-01, -2.05525617e-16,\n",
+       "         -8.09767396e-06, -1.88051607e-17,  1.00000000e+00,  1.24489808e-15,\n",
+       "          3.99155718e-15,  9.90499900e-04,  4.87300408e-04,  1.34548830e-04,\n",
+       "         -5.03699693e-16,  1.95172266e-04, -4.28067635e-15,  1.11477429e+01,\n",
+       "          1.00475946e-14,  6.63181191e-04,  2.85898983e-15, -2.57937368e-15,\n",
+       "          4.95791122e-14,  8.68587052e-03,  5.13557925e-03,  2.34025921e-03,\n",
+       "          3.42882804e-15]),\n",
+       "  array([ 1.07332597e-06,  5.46939689e-18,  5.05421087e-01, -2.00402822e-16,\n",
+       "         -7.76350052e-06, -1.74252395e-17,  1.00000000e+00,  1.24203758e-15,\n",
+       "          4.03916810e-15,  9.98795093e-04,  4.92215215e-04,  1.36797641e-04,\n",
+       "         -5.00307937e-16,  1.87614581e-04, -4.16461551e-15,  1.10716865e+01,\n",
+       "          1.02455988e-14,  6.68346895e-04,  2.75989696e-15, -2.86049123e-15,\n",
+       "          4.76109200e-14,  8.29519322e-03,  4.91480671e-03,  2.24881041e-03,\n",
+       "          3.39175612e-15]),\n",
+       "  array([ 1.08641103e-06,  5.77037773e-18,  5.16412276e-01, -1.95211483e-16,\n",
+       "         -7.42817317e-06, -1.60956871e-17,  1.00000000e+00,  1.23892085e-15,\n",
+       "          4.08481723e-15,  1.00670674e-03,  4.96912767e-04,  1.38955975e-04,\n",
+       "         -4.96962096e-16,  1.80059612e-04, -4.04728744e-15,  1.09911888e+01,\n",
+       "          1.03826868e-14,  6.70654698e-04,  2.65915854e-15, -3.11673464e-15,\n",
+       "          4.56491360e-14,  7.91164382e-03,  4.69755218e-03,  2.15833442e-03,\n",
+       "          3.34584137e-15]),\n",
+       "  array([ 1.10057858e-06,  6.04201873e-18,  5.27318739e-01, -1.89980249e-16,\n",
+       "         -7.09301452e-06, -1.48169952e-17,  1.00000000e+00,  1.23557145e-15,\n",
+       "          4.12851416e-15,  1.01424209e-03,  5.01396713e-04,  1.41024913e-04,\n",
+       "         -4.93670136e-16,  1.72542354e-04, -3.92943564e-15,  1.09064634e+01,\n",
+       "          1.04624775e-14,  6.70317294e-04,  2.55743681e-15, -3.34939674e-15,\n",
+       "          4.36969287e-14,  7.53535581e-03,  4.48394598e-03,  2.06893765e-03,\n",
+       "          3.29195968e-15]),\n",
+       "  array([ 1.11582344e-06,  6.28384047e-18,  5.38136459e-01, -1.84735742e-16,\n",
+       "         -6.75923920e-06, -1.35894301e-17,  1.00000000e+00,  1.23201155e-15,\n",
+       "          4.17027171e-15,  1.02140854e-03,  5.05670819e-04,  1.43005630e-04,\n",
+       "         -4.90439137e-16,  1.65094650e-04, -3.81174804e-15,  1.08177191e+01,\n",
+       "          1.04890213e-14,  6.67550651e-04,  2.45518274e-15, -3.55990274e-15,\n",
+       "          4.17575448e-14,  7.16644636e-03,  4.27410547e-03,  1.98071761e-03,\n",
+       "          3.23099924e-15]),\n",
+       "  array([ 1.13213386e-06,  6.49549806e-18,  5.48861618e-01, -1.79502375e-16,\n",
+       "         -6.42795296e-06, -1.24129709e-17,  1.00000000e+00,  1.22826216e-15,\n",
+       "          4.21010599e-15,  1.02821356e-03,  5.09738954e-04,  1.44899394e-04,\n",
+       "         -4.87275280e-16,  1.57745167e-04, -3.69485213e-15,  1.07251598e+01,\n",
+       "          1.04667411e-14,  6.62572473e-04,  2.35297002e-15, -3.74938988e-15,\n",
+       "          3.98342832e-14,  6.80501729e-03,  4.06813582e-03,  1.89376351e-03,\n",
+       "          3.16385614e-15]),\n",
+       "  array([ 1.14949223e-06,  6.67676803e-18,  5.59490602e-01, -1.74302195e-16,\n",
+       "         -6.10015264e-06, -1.12874065e-17,  1.00000000e+00,  1.22434304e-15,\n",
+       "          4.24803645e-15,  1.03466471e-03,  5.13605085e-04,  1.46707550e-04,\n",
+       "         -4.84183854e-16,  1.50519400e-04, -3.57931121e-15,  1.06289842e+01,\n",
+       "          1.04003651e-14,  6.55600629e-04,  2.25117963e-15, -3.91911584e-15,\n",
+       "          3.79304610e-14,  6.45115576e-03,  3.86613068e-03,  1.80815668e-03,\n",
+       "          3.09142686e-15]),\n",
+       "  array([ 1.16787568e-06,  6.82753555e-18,  5.70019989e-01, -1.69154770e-16,\n",
+       "         -5.77672688e-06, -1.02122930e-17,  1.00000000e+00,  1.22027293e-15,\n",
+       "          4.28408583e-15,  1.04076965e-03,  5.17273258e-04,  1.48431521e-04,\n",
+       "         -4.81169252e-16,  1.43439707e-04, -3.46562178e-15,  1.05293862e+01,\n",
+       "          1.02948554e-14,  6.46851531e-04,  2.15027694e-15, -4.07011101e-15,\n",
+       "          3.60493794e-14,  6.10493494e-03,  3.66817266e-03,  1.72397095e-03,\n",
+       "          3.01460180e-15]),\n",
+       "  array([ 1.18725679e-06,  6.94778248e-18,  5.80446544e-01, -1.64077106e-16,\n",
+       "         -5.45845761e-06, -9.18704055e-18,  1.00000000e+00,  1.21606942e-15,\n",
+       "          4.31828012e-15,  1.04653606e-03,  5.20747592e-04,  1.50072794e-04,\n",
+       "         -4.78234995e-16,  1.36525379e-04, -3.35421213e-15,  1.04265552e+01,\n",
+       "          1.01553332e-14,  6.36538537e-04,  2.05055389e-15, -4.20351371e-15,\n",
+       "          3.41942847e-14,  5.76641446e-03,  3.47433382e-03,  1.64127299e-03,\n",
+       "          2.93425666e-15]),\n",
+       "  array([ 1.20760412e-06,  7.03757599e-18,  5.90767219e-01, -1.59083608e-16,\n",
+       "         -5.14602243e-06, -8.21094978e-18,  1.00000000e+00,  1.21174897e-15,\n",
+       "          4.35064845e-15,  1.05197170e-03,  5.24032268e-04,  1.51632917e-04,\n",
+       "         -4.75383750e-16,  1.29792728e-04, -3.24544203e-15,  1.03206754e+01,\n",
+       "          9.98700164e-15,  6.24870370e-04,  1.95222956e-15, -4.32044958e-15,\n",
+       "          3.23683309e-14,  5.43564087e-03,  3.28467597e-03,  1.56012254e-03,\n",
+       "          2.85124515e-15]),\n",
+       "  array([ 1.22888283e-06,  7.09705825e-18,  6.00979146e-01, -1.54186075e-16,\n",
+       "         -4.83999762e-06, -7.28315580e-18,  1.00000000e+00,  1.20732717e-15,\n",
+       "          4.38122299e-15,  1.05708435e-03,  5.27131519e-04,  1.53113490e-04,\n",
+       "         -4.72617359e-16,  1.23255209e-04, -3.13960362e-15,  1.02119266e+01,\n",
+       "          9.79507157e-15,  6.12049610e-04,  1.85563492e-15, -4.42180389e-15,\n",
+       "          3.05745428e-14,  5.11264798e-03,  3.09925106e-03,  1.48057266e-03,\n",
+       "          2.76639123e-15]),\n",
+       "  array([ 1.25105516e-06,  7.12643699e-18,  6.11079630e-01, -1.49393733e-16,\n",
+       "         -4.54086199e-06, -6.40269662e-18,  1.00000000e+00,  1.20281862e-15,\n",
+       "          4.41003877e-15,  1.06188181e-03,  5.30049620e-04,  1.54516159e-04,\n",
+       "         -4.69936878e-16,  1.16923557e-04, -3.03692321e-15,  1.01004837e+01,\n",
+       "          9.58468668e-15,  5.98271271e-04,  1.76096421e-15, -4.50854504e-15,\n",
+       "          2.88157791e-14,  4.79745722e-03,  2.91810138e-03,  1.40266988e-03,\n",
+       "          2.68048056e-15]),\n",
+       "  array([ 1.27408099e-06,  7.12597711e-18,  6.21066147e-01, -1.44713308e-16,\n",
+       "         -4.24900124e-06, -5.56852553e-18,  1.00000000e+00,  1.19823703e-15,\n",
+       "          4.43713347e-15,  1.06637189e-03,  5.32790880e-04,  1.55842614e-04,\n",
+       "         -4.67342624e-16,  1.10805945e-04, -2.93756408e-15,  9.98651713e+00,\n",
+       "          9.36085388e-15,  5.83721484e-04,  1.66838689e-15, -4.58158819e-15,\n",
+       "          2.70947003e-14,  4.49007789e-03,  2.74125989e-03,  1.32645443e-03,\n",
+       "          2.59425389e-15]),\n",
+       "  array([ 1.29791821e-06,  7.09599337e-18,  6.30936340e-01, -1.40149121e-16,\n",
+       "         -3.96471308e-06, -4.77952407e-18,  1.00000000e+00,  1.19359523e-15,\n",
+       "          4.46254721e-15,  1.07056239e-03,  5.35359630e-04,  1.57094574e-04,\n",
+       "         -4.64834224e-16,  1.04908161e-04, -2.84163017e-15,  9.87019277e+00,\n",
+       "          9.12837806e-15,  5.68576321e-04,  1.57804640e-15, -4.64180365e-15,\n",
+       "          2.54137383e-14,  4.19050749e-03,  2.56875038e-03,  1.25196039e-03,\n",
+       "          2.50840053e-15]),\n",
+       "  array([ 1.32252317e-06,  7.03684405e-18,  6.40688012e-01, -1.35703221e-16,\n",
+       "         -3.68821270e-06, -4.03451444e-18,  1.00000000e+00,  1.18890521e-15,\n",
+       "          4.48632228e-15,  1.07446113e-03,  5.37760218e-04,  1.58273790e-04,\n",
+       "         -4.62410671e-16,  9.92337902e-05, -2.74917033e-15,  9.75167196e+00,\n",
+       "          8.89180295e-15,  5.53000759e-04,  1.49006151e-15, -4.69002168e-15,\n",
+       "          2.37750710e-14,  3.89873206e-03,  2.40058783e-03,  1.17921584e-03,\n",
+       "          2.42355264e-15]),\n",
+       "  array([ 1.34785108e-06,  6.94892569e-18,  6.50319123e-01, -1.31375543e-16,\n",
+       "         -3.41963880e-06, -3.33227064e-18,  1.00000000e+00,  1.18417817e-15,\n",
+       "          4.50850288e-15,  1.07807585e-03,  5.39996997e-04,  1.59382033e-04,\n",
+       "         -4.60070391e-16,  9.37844137e-05, -2.66018333e-15,  9.63111165e+00,\n",
+       "          8.65535881e-15,  5.37147809e-04,  1.40452857e-15, -4.72703553e-15,\n",
+       "          2.21806008e-14,  3.61472643e-03,  2.23677854e-03,  1.10824306e-03,\n",
+       "          2.34028049e-15]),\n",
+       "  array([ 1.37385625e-06,  6.83266872e-18,  6.59827788e-01, -1.27164086e-16,\n",
+       "         -3.15905989e-06, -2.67152851e-18,  1.00000000e+00,  1.17942457e-15,\n",
+       "          4.52913482e-15,  1.08141431e-03,  5.42074317e-04,  1.60421092e-04,\n",
+       "         -4.57811302e-16,  8.85598090e-05, -2.57462318e-15,  9.50866437e+00,\n",
+       "          8.42291762e-15,  5.21157822e-04,  1.32152393e-15, -4.75360385e-15,\n",
+       "          2.06319380e-14,  3.33845467e-03,  2.07732052e-03,  1.03905867e-03,\n",
+       "          2.25908872e-15]),\n",
+       "  array([ 1.40049247e-06,  6.68853407e-18,  6.69212266e-01, -1.23065109e-16,\n",
+       "         -2.90648091e-06, -2.05099428e-18,  1.00000000e+00,  1.17465412e-15,\n",
+       "          4.54826521e-15,  1.08448418e-03,  5.43996521e-04,  1.61392766e-04,\n",
+       "         -4.55630888e-16,  8.35581543e-05, -2.49240486e-15,  9.38447837e+00,\n",
+       "          8.19795638e-15,  5.05157959e-04,  1.24110680e-15, -4.77045204e-15,\n",
+       "          1.91303892e-14,  3.06987040e-03,  1.92220372e-03,  9.71673884e-04,\n",
+       "          2.18041370e-15]),\n",
+       "  array([ 1.42771321e-06,  6.51701047e-18,  6.78470964e-01, -1.19073346e-16,\n",
+       "         -2.66184998e-06, -1.46935217e-18,  1.00000000e+00,  1.16987584e-15,\n",
+       "          4.56594216e-15,  1.08729309e-03,  5.45767931e-04,  1.62298860e-04,\n",
+       "         -4.53526266e-16,  7.87762323e-05, -2.41341015e-15,  9.25869764e+00,\n",
+       "          7.98352874e-15,  4.89261859e-04,  1.16332123e-15, -4.77827418e-15,\n",
+       "          1.76769504e-14,  2.80891728e-03,  1.77141038e-03,  9.06094676e-04,\n",
+       "          2.10462190e-15]),\n",
+       "  array([ 1.45547186e-06,  6.31861259e-18,  6.87602426e-01, -1.15182224e-16,\n",
+       "         -2.42506525e-06, -9.25270843e-19,  1.00000000e+00,  1.16509811e-15,\n",
+       "          4.58221446e-15,  1.08984862e-03,  5.47392847e-04,  1.63141182e-04,\n",
+       "         -4.51494257e-16,  7.42096310e-05, -2.33749358e-15,  9.13146195e+00,\n",
+       "          7.78224501e-15,  4.73569465e-04,  1.08819832e-15, -4.77773422e-15,\n",
+       "          1.62723054e-14,  2.55552945e-03,  1.62491537e-03,  8.42322035e-04,\n",
+       "          2.03200936e-15]),\n",
+       "  array([ 1.48372195e-06,  6.09387970e-18,  6.96605333e-01, -1.11384095e-16,\n",
+       "         -2.19598172e-06, -4.17408972e-19,  1.00000000e+00,  1.16032864e-15,\n",
+       "          4.59713129e-15,  1.09215826e-03,  5.48875533e-04,  1.63921535e-04,\n",
+       "         -4.49531455e-16,  6.98529383e-05, -2.26448833e-15,  9.00290698e+00,\n",
+       "          7.59626053e-15,  4.58167043e-04,  1.01575809e-15, -4.76946706e-15,\n",
+       "          1.49168285e-14,  2.30963205e-03,  1.48268659e-03,  7.80352211e-04,\n",
+       "          1.96280224e-15]),\n",
+       "  array([ 1.51241723e-06,  5.84337487e-18,  7.05478497e-01, -1.07670460e-16,\n",
+       "         -1.97441805e-06,  5.55800062e-20,  1.00000000e+00,  1.15557456e-15,\n",
+       "          4.61074188e-15,  1.09422940e-03,  5.50220219e-04,  1.64641712e-04,\n",
+       "         -4.47634296e-16,  6.56999296e-05, -2.19421187e-15,  8.87316430e+00,\n",
+       "          7.42727222e-15,  4.43127355e-04,  9.46011003e-16, -4.75407964e-15,\n",
+       "          1.36105919e-14,  2.07114174e-03,  1.34468538e-03,  7.20176984e-04,\n",
+       "          1.89715832e-15]),\n",
+       "  array([ 1.54151192e-06,  5.56768459e-18,  7.14220858e-01, -1.04032199e-16,\n",
+       "         -1.76016305e-06,  4.95043781e-19,  1.00000000e+00,  1.15084241e-15,\n",
+       "          4.62309526e-15,  1.09606936e-03,  5.51431086e-04,  1.65303496e-04,\n",
+       "         -4.45799127e-16,  6.17437436e-05, -2.12647148e-15,  8.74236149e+00,\n",
+       "          7.27652281e-15,  4.28509996e-04,  8.78959321e-16, -4.73215174e-15,\n",
+       "          1.23533773e-14,  1.83996734e-03,  1.21086695e-03,  6.61783949e-04,\n",
+       "          1.83516943e-15]),\n",
+       "  array([ 1.57096073e-06,  5.26741871e-18,  7.22831480e-01, -1.00459794e-16,\n",
+       "         -1.55298211e-06,  9.02327621e-19,  1.00000000e+00,  1.14613817e-15,\n",
+       "          4.63423995e-15,  1.09768537e-03,  5.52512266e-04,  1.65908652e-04,\n",
+       "         -4.44022262e-16,  5.79770483e-05, -2.06106924e-15,  8.61062218e+00,\n",
+       "          7.14481243e-15,  4.14361872e-04,  8.14598211e-16, -4.70423677e-15,\n",
+       "          1.11446910e-14,  1.61601040e-03,  1.08118082e-03,  6.05156827e-04,\n",
+       "          1.77686470e-15]),\n",
+       "  array([ 1.60071901e-06,  4.94321047e-18,  7.31309547e-01, -9.69435365e-17,\n",
+       "         -1.35262320e-06,  1.27877127e-18,  1.00000000e+00,  1.14146731e-15,\n",
+       "          4.64422373e-15,  1.09908454e-03,  5.53467838e-04,  1.66458928e-04,\n",
+       "         -4.42300048e-16,  5.43921927e-05, -1.99780681e-15,  8.47806613e+00,\n",
+       "          7.03251677e-15,  4.00717819e-04,  7.52916639e-16, -4.67086236e-15,\n",
+       "          9.98378272e-15,  1.39916583e-03,  9.55571344e-04,  5.50275773e-04,\n",
+       "          1.72221467e-15]),\n",
+       "  array([ 1.63074281e-06,  4.59571682e-18,  7.39654356e-01, -9.34737316e-17,\n",
+       "         -1.15882254e-06,  1.62570623e-18,  1.00000000e+00,  1.13683478e-15,\n",
+       "          4.65309340e-15,  1.10027386e-03,  5.54301816e-04,  1.66956046e-04,\n",
+       "         -4.40628912e-16,  5.09813444e-05, -1.93648955e-15,  8.34480926e+00,\n",
+       "          6.93961128e-15,  3.87601325e-04,  6.93898093e-16, -4.63253085e-15,\n",
+       "          8.86966711e-15,  1.18932263e-03,  8.33978183e-04,  4.97117715e-04,\n",
+       "          1.67113591e-15]),\n",
+       "  array([ 1.66098899e-06,  4.22561855e-18,  7.47865320e-01, -9.00408819e-17,\n",
+       "         -9.71309858e-07,  1.94445323e-18,  1.00000000e+00,  1.13224506e-15,\n",
+       "          4.66089455e-15,  1.10126023e-03,  5.55018153e-04,  1.67401703e-04,\n",
+       "         -4.39005415e-16,  4.77366130e-05, -1.87693025e-15,  8.21096374e+00,\n",
+       "          6.86570066e-15,  3.75025364e-04,  6.37521117e-16, -4.58971978e-15,\n",
+       "          7.80114744e-15,  9.86364481e-04,  7.16336815e-04,  4.45656684e-04,\n",
+       "          1.62349627e-15]),\n",
+       "  array([ 1.69141519e-06,  3.83362053e-18,  7.55941958e-01, -8.66358562e-17,\n",
+       "         -7.89813205e-07,  2.23632006e-18,  1.00000000e+00,  1.12770218e-15,\n",
+       "          4.66767139e-15,  1.10205040e-03,  5.55620732e-04,  1.67797567e-04,\n",
+       "         -4.37426295e-16,  4.46501581e-05, -1.81895225e-15,  8.07663806e+00,\n",
+       "          6.81005271e-15,  3.62993307e-04,  5.83759719e-16, -4.54288220e-15,\n",
+       "          6.77684143e-15,  7.90170508e-04,  6.02579057e-04,  3.95864162e-04,\n",
+       "          1.57912057e-15]),\n",
+       "  array([ 1.72197997e-06,  3.42045173e-18,  7.63883895e-01, -8.32500389e-17,\n",
+       "         -6.14063254e-07,  2.50259933e-18,  1.00000000e+00,  1.12320973e-15,\n",
+       "          4.67346660e-15,  1.10265101e-03,  5.56113365e-04,  1.68145276e-04,\n",
+       "         -4.35888498e-16,  4.17142813e-05, -1.76239206e-15,  7.94193707e+00,\n",
+       "          6.77163581e-15,  3.51499901e-04,  5.32583648e-16, -4.49244697e-15,\n",
+       "          5.79520838e-15,  6.00615915e-04,  4.92633584e-04,  3.47709423e-04,\n",
+       "          1.53779654e-15]),\n",
+       "  array([ 1.75264280e-06,  2.98686510e-18,  7.71690857e-01, -7.98754598e-17,\n",
+       "         -4.43797105e-07,  2.74456651e-18,  1.00000000e+00,  1.11877091e-15,\n",
+       "          4.67832117e-15,  1.10306859e-03,  5.56499792e-04,  1.68446436e-04,\n",
+       "         -4.34389217e-16,  3.89215040e-05, -1.70710139e-15,  7.80696204e+00,\n",
+       "          6.74915928e-15,  3.40532299e-04,  4.83958571e-16, -4.43881906e-15,\n",
+       "          4.85457714e-15,  4.17572695e-04,  3.86426447e-04,  3.01159882e-04,\n",
+       "          1.49928108e-15]),\n",
+       "  array([ 1.78336410e-06,  2.53363721e-18,  7.79362668e-01, -7.65049026e-17,\n",
+       "         -2.78761550e-07,  2.96347792e-18,  1.00000000e+00,  1.11438853e-15,\n",
+       "          4.68227435e-15,  1.10330950e-03,  5.56783673e-04,  1.68702618e-04,\n",
+       "         -4.32925911e-16,  3.62646302e-05, -1.65294863e-15,  7.67181078e+00,\n",
+       "          6.74111554e-15,  3.30071109e-04,  4.37846176e-16, -4.38237973e-15,\n",
+       "          3.95317451e-15,  2.40910296e-04,  2.83881577e-04,  2.56181430e-04,\n",
+       "          1.46330654e-15]),\n",
+       "  array([ 1.81410527e-06,  2.06156761e-18,  7.86899245e-01, -7.31319914e-17,\n",
+       "         -1.18715814e-07,  3.16056872e-18,  1.00000000e+00,  1.11006505e-15,\n",
+       "          4.68536350e-15,  1.10337999e-03,  5.56968595e-04,  1.68915356e-04,\n",
+       "         -4.31496324e-16,  3.37367943e-05, -1.59981986e-15,  7.53657761e+00,\n",
+       "          6.74582343e-15,  3.20091474e-04,  3.94204210e-16, -4.32348680e-15,\n",
+       "          3.08915353e-15,  7.04962743e-05,  1.84921288e-04,  2.12738767e-04,\n",
+       "          1.42958701e-15]),\n",
+       "  array([ 1.84482875e-06,  1.57147797e-18,  7.94300599e-01, -6.97512562e-17,\n",
+       "          3.65662496e-08,  3.33705101e-18,  1.00000000e+00,  1.10580257e-15,\n",
+       "          4.68762412e-15,  1.10328619e-03,  5.57058061e-04,  1.69086152e-04,\n",
+       "         -4.30098499e-16,  3.13314973e-05, -1.54761927e-15,  7.40135351e+00,\n",
+       "          6.76147153e-15,  3.10564126e-04,  3.52986492e-16, -4.26247486e-15,\n",
+       "          2.26062099e-15, -9.38030714e-05,  8.94667535e-05,  1.70795723e-04,\n",
+       "          1.39782455e-15]),\n",
+       "  array([ 1.87549801e-06,  1.06421086e-18,  8.01566825e-01, -6.63581754e-17,\n",
+       "          1.87294481e-07,  3.49411135e-18,  1.00000000e+00,  1.10160291e-15,\n",
+       "          4.68908979e-15,  1.10303407e-03,  5.57055500e-04,  1.69216468e-04,\n",
+       "         -4.28730784e-16,  2.90426291e-05, -1.49626922e-15,  7.26622614e+00,\n",
+       "          6.78616254e-15,  3.01456463e-04,  3.14141964e-16, -4.19965665e-15,\n",
+       "          1.46566553e-15, -2.52122080e-04, -2.56153022e-06,  1.30315567e-04,\n",
+       "          1.36771526e-15]),\n",
+       "  array([ 1.90607757e-06,  5.40628293e-19,  8.08698105e-01, -6.29491990e-17,\n",
+       "          3.33661249e-07,  3.63290975e-18,  1.00000000e+00,  1.09746759e-15,\n",
+       "          4.68979217e-15,  1.10262947e-03,  5.56964257e-04,  1.69307729e-04,\n",
+       "         -4.27391829e-16,  2.68644802e-05, -1.44570986e-15,  7.13127990e+00,\n",
+       "          6.81795380e-15,  2.92733535e-04,  2.77617490e-16, -4.13531983e-15,\n",
+       "          7.02381847e-16, -4.04595183e-04, -9.12433100e-05,  9.12612950e-05,\n",
+       "          1.33895502e-15]),\n",
+       "  array([ 1.93653307e-06,  1.60994227e-21,  8.15694701e-01, -5.95217504e-17,\n",
+       "          4.75840764e-07,  3.75457641e-18,  1.00000000e+00,  1.09339786e-15,\n",
+       "          4.68976107e-15,  1.10207812e-03,  5.56787598e-04,  1.69361325e-04,\n",
+       "         -4.26080584e-16,  2.47917439e-05, -1.39589831e-15,  6.99659603e+00,\n",
+       "          6.85489817e-15,  2.84359031e-04,  2.43353511e-16, -4.06973276e-15,\n",
+       "         -3.11045314e-17, -5.51356350e-04, -1.76658170e-04,  5.35959065e-05,\n",
+       "          1.31124486e-15]),\n",
+       "  array([ 1.96683126e-06, -5.51948854e-19,  8.22556953e-01, -5.60742099e-17,\n",
+       "          6.13988858e-07,  3.86021065e-18,  1.00000000e+00,  1.08939472e-15,\n",
+       "          4.68902445e-15,  1.10138558e-03,  5.56528713e-04,  1.69378607e-04,\n",
+       "         -4.24796288e-16,  2.28195083e-05, -1.34680768e-15,  6.86225263e+00,\n",
+       "          6.89508178e-15,  2.76296188e-04,  2.11288211e-16, -4.00313961e-15,\n",
+       "         -7.36615035e-16, -6.92538603e-04, -2.58885155e-04,  1.72826528e-05,\n",
+       "          1.28429605e-15]),\n",
+       "  array([ 1.99694005e-06, -1.11913937e-18,  8.29285278e-01, -5.26058810e-17,\n",
+       "          7.48243178e-07,  3.95087860e-18,  1.00000000e+00,  1.08545896e-15,\n",
+       "          4.68760855e-15,  1.10055730e-03,  5.56190711e-04,  1.69360893e-04,\n",
+       "         -4.23538453e-16,  2.09432428e-05, -1.29842566e-15,  6.72832473e+00,\n",
+       "          6.93665889e-15,  2.68508640e-04,  1.81355207e-16, -3.93576375e-15,\n",
+       "         -1.41589790e-15, -8.28273564e-04, -3.38002424e-04, -1.77147304e-05,\n",
+       "          1.25783460e-15]),\n",
+       "  array([ 2.02682848e-06, -1.69904194e-18,  8.35880162e-01, -4.91169397e-17,\n",
+       "          8.78723769e-07,  4.02761140e-18,  1.00000000e+00,  1.08159115e-15,\n",
+       "          4.68553794e-15,  1.09959861e-03,  5.55776624e-04,  1.69309461e-04,\n",
+       "         -4.22306848e-16,  1.91587764e-05, -1.25075301e-15,  6.59488439e+00,\n",
+       "          6.97788336e-15,  2.60961183e-04,  1.53484564e-16, -3.86780711e-15,\n",
+       "         -2.07061030e-15, -9.58691048e-04, -4.14086942e-04, -5.14318173e-05,\n",
+       "          1.23160532e-15]),\n",
+       "  array([ 2.05646683e-06, -2.29072862e-18,  8.42342163e-01, -4.56083720e-17,\n",
+       "          1.00553400e-06,  4.09140203e-18,  1.00000000e+00,  1.07779170e-15,\n",
+       "          4.68283564e-15,  1.09851470e-03,  5.55289410e-04,  1.69225558e-04,\n",
+       "         -4.21101473e-16,  1.74622722e-05, -1.20380191e-15,  6.46200071e+00,\n",
+       "          7.01713643e-15,  2.53620463e-04,  1.27599882e-16, -3.79945463e-15,\n",
+       "         -2.70230286e-15, -1.08391871e-03, -4.87214210e-04, -8.39033089e-05,\n",
+       "          1.20537541e-15]),\n",
+       "  array([ 2.08582656e-06, -2.89326594e-18,  8.48671903e-01, -4.20818972e-17,\n",
+       "          1.12876179e-06,  4.14320404e-18,  1.00000000e+00,  1.07406083e-15,\n",
+       "          4.67952323e-15,  1.09731061e-03,  5.54731952e-04,  1.69110395e-04,\n",
+       "         -4.19922535e-16,  1.58501981e-05, -1.15759411e-15,  6.32973994e+00,\n",
+       "          7.05295047e-15,  2.46455571e-04,  1.03622354e-16, -3.73087000e-15,\n",
+       "         -3.31240672e-15, -1.20408174e-03, -5.57458027e-04, -1.15162876e-04,\n",
+       "          1.17893734e-15]),\n",
+       "  array([ 2.11488040e-06, -3.50571777e-18,  8.54870069e-01, -3.85398834e-17,\n",
+       "          1.24848106e-06,  4.18393110e-18,  1.00000000e+00,  1.07039863e-15,\n",
+       "          4.67562101e-15,  1.09599131e-03,  5.54107061e-04,  1.68965152e-04,\n",
+       "         -4.18770424e-16,  1.43192948e-05, -1.11215914e-15,  6.19816550e+00,\n",
+       "          7.08402845e-15,  2.39438542e-04,  8.14721832e-17, -3.66219487e-15,\n",
+       "         -3.90222317e-15, -1.31930260e-03, -6.24890292e-04, -1.45243028e-04,\n",
+       "          1.15211125e-15]),\n",
+       "  array([ 2.14360232e-06, -4.12714819e-18,  8.60937407e-01, -3.49852543e-17,\n",
+       "          1.36475344e-06,  4.21445430e-18,  1.00000000e+00,  1.06680508e-15,\n",
+       "          4.67114809e-15,  1.09456161e-03,  5.53417481e-04,  1.68790977e-04,\n",
+       "         -4.17645677e-16,  1.28665423e-05, -1.06753246e-15,  6.06733806e+00,\n",
+       "          7.10925914e-15,  2.32544765e-04,  6.10642407e-17, -3.59355569e-15,\n",
+       "         -4.47291581e-15, -1.42970079e-03, -6.89580845e-04, -1.74175006e-04,\n",
+       "          1.12474680e-15]),\n",
+       "  array([ 2.17196758e-06, -4.75662444e-18,  8.66874722e-01, -3.14213908e-17,\n",
+       "          1.47763008e-06,  4.23560015e-18,  1.00000000e+00,  1.06328001e-15,\n",
+       "          4.66612259e-15,  1.09302622e-03,  5.52665883e-04,  1.68588988e-04,\n",
+       "         -4.16548953e-16,  1.14891260e-05, -1.02375363e-15,  5.93731560e+00,\n",
+       "          7.12772783e-15,  2.25753286e-04,  4.23093153e-17, -3.52506339e-15,\n",
+       "         -5.02550537e-15, -1.53539276e-03, -7.51597343e-04, -2.01988702e-04,\n",
+       "          1.09672435e-15]),\n",
+       "  array([ 2.19995272e-06, -5.39321978e-18,  8.72682876e-01, -2.78520299e-17,\n",
+       "          1.58715359e-06,  4.24815044e-18,  1.00000000e+00,  1.05982320e-15,\n",
+       "          4.66056172e-15,  1.09138973e-03,  5.51854878e-04,  1.68360275e-04,\n",
+       "         -4.15480997e-16,  1.01844038e-05, -9.80864626e-16,  5.80815348e+00,\n",
+       "          7.13872270e-15,  2.19047024e-04,  2.51180167e-17, -3.45681000e-15,\n",
+       "         -5.56086696e-15, -1.63649169e-03, -8.11005174e-04, -2.28712601e-04,\n",
+       "          1.06795566e-15]),\n",
+       "  array([ 2.22753559e-06, -6.03601625e-18,  8.78362780e-01, -2.42811619e-17,\n",
+       "          1.69336003e-06,  4.25284006e-18,  1.00000000e+00,  1.05643433e-15,\n",
+       "          4.65448199e-15,  1.08965662e-03,  5.50987011e-04,  1.68105902e-04,\n",
+       "         -4.14442613e-16,  8.94987346e-06, -9.38908177e-16,  5.67990448e+00,\n",
+       "          7.14173688e-15,  2.12412880e-04,  9.39650430e-18, -3.38887575e-15,\n",
+       "         -6.07972972e-15, -1.73310753e-03, -8.67867403e-04, -2.54373751e-04,\n",
+       "          1.03838399e-15]),\n",
+       "  array([ 2.25469538e-06, -6.68410738e-18,  8.83915399e-01, -2.07129292e-17,\n",
+       "          1.79628092e-06,  4.25035703e-18,  1.00000000e+00,  1.05311300e-15,\n",
+       "          4.64789931e-15,  1.08783127e-03,  5.50064766e-04,  1.67826904e-04,\n",
+       "         -4.13434630e-16,  7.78314318e-06, -8.97926319e-16,  5.55261887e+00,\n",
+       "          7.13646637e-15,  2.05841764e-04, -4.94899095e-18, -3.32132507e-15,\n",
+       "         -6.58267878e-15, -1.82534688e-03, -9.22244756e-04, -2.78997752e-04,\n",
+       "          1.00798373e-15]),\n",
+       "  array([ 2.28141258e-06, -7.33660071e-18,  8.89341744e-01, -1.71515276e-17,\n",
+       "          1.89594518e-06,  4.24133976e-18,  1.00000000e+00,  1.04985879e-15,\n",
+       "          4.64082915e-15,  1.08591796e-03,  5.49090570e-04,  1.67524295e-04,\n",
+       "         -4.12457870e-16,  6.68190367e-06, -8.57959052e-16,  5.42634445e+00,\n",
+       "          7.12280400e-15,  1.99328530e-04, -1.80176179e-17, -3.25421555e-15,\n",
+       "         -7.07015936e-15, -1.91331306e-03, -9.74195636e-04, -3.02608769e-04,\n",
+       "          9.76759541e-16]),\n",
+       "  array([ 2.30766899e-06, -7.99262013e-18,  8.94642870e-01, -1.36011132e-17,\n",
+       "          1.99238109e-06,  4.22638044e-18,  1.00000000e+00,  1.04667120e-15,\n",
+       "          4.63328667e-15,  1.08392085e-03,  5.48066794e-04,  1.67199066e-04,\n",
+       "         -4.11513125e-16,  5.64390387e-06, -8.19043198e-16,  5.30112666e+00,\n",
+       "          7.10082979e-15,  1.92871820e-04, -2.99018612e-17, -3.18758451e-15,\n",
+       "         -7.54248277e-15, -1.99710616e-03, -1.02377616e-03, -3.25229566e-04,\n",
+       "          9.44745006e-16]),\n",
+       "  array([ 2.33344776e-06, -8.65130806e-18,  8.99819879e-01, -1.00657147e-17,\n",
+       "          2.08561801e-06,  4.20602445e-18,  1.00000000e+00,  1.04354974e-15,\n",
+       "          4.62528684e-15,  1.08184403e-03,  5.46995754e-04,  1.66852184e-04,\n",
+       "         -4.10601124e-16,  4.66692979e-06, -7.81211432e-16,  5.17700856e+00,\n",
+       "          7.07079784e-15,  1.86473836e-04, -4.06953562e-17, -3.12146111e-15,\n",
+       "         -7.99983423e-15, -2.07682309e-03, -1.07104024e-03, -3.46881558e-04,\n",
+       "          9.12000926e-16]),\n",
+       "  array([ 2.35873332e-06, -9.31182739e-18,  9.04873910e-01, -6.54915497e-18,\n",
+       "          2.17568803e-06,  4.18077079e-18,  1.00000000e+00,  1.04049387e-15,\n",
+       "          4.61684455e-15,  1.07969147e-03,  5.45879714e-04,  1.66484599e-04,\n",
+       "         -4.09722511e-16,  3.74878695e-06, -7.44491519e-16,  5.05403097e+00,\n",
+       "          7.03312027e-15,  1.80140042e-04, -5.04908412e-17, -3.05586578e-15,\n",
+       "         -8.44228223e-15, -2.15255776e-03, -1.11603967e-03, -3.67584879e-04,\n",
+       "          8.78613225e-16]),\n",
+       "  array([ 2.38351141e-06, -9.97336318e-18,  9.09806142e-01, -3.05498116e-18,\n",
+       "          2.26262743e-06,  4.15106918e-18,  1.00000000e+00,  1.03750305e-15,\n",
+       "          4.60797477e-15,  1.07746707e-03,  5.44720890e-04,  1.66097241e-04,\n",
+       "         -4.08877820e-16,  2.88728660e-06, -7.08905734e-16,  4.93223245e+00,\n",
+       "          6.98834846e-15,  1.73878793e-04, -5.93868772e-17, -2.99082100e-15,\n",
+       "         -8.86978929e-15, -2.22440118e-03, -1.15882426e-03, -3.87358477e-04,\n",
+       "          8.44690554e-16]),\n",
+       "  array([ 2.40776904e-06, -1.06351241e-17,  9.14617792e-01,  4.13594428e-19,\n",
+       "          2.34647788e-06,  4.11732232e-18,  1.00000000e+00,  1.03457671e-15,\n",
+       "          4.59869254e-15,  1.07517463e-03,  5.43521448e-04,  1.65691020e-04,\n",
+       "         -4.08067459e-16,  2.08023565e-06, -6.74470480e-16,  4.81164942e+00,\n",
+       "          6.93715203e-15,  1.67700912e-04, -6.74775152e-17, -2.92634032e-15,\n",
+       "         -9.28222379e-15, -2.29244167e-03, -1.19944198e-03, -4.06220207e-04,\n",
+       "          8.10361602e-16]),\n",
+       "  array([ 2.43149449e-06, -1.12963438e-17,  9.19310108e-01,  3.85374198e-18,\n",
+       "          2.42728749e-06,  4.07988855e-18,  1.00000000e+00,  1.03171428e-15,\n",
+       "          4.58901317e-15,  1.07281786e-03,  5.42283509e-04,  1.65266833e-04,\n",
+       "         -4.07291686e-16,  1.32543027e-06, -6.41196091e-16,  4.69231616e+00,\n",
+       "          6.88029595e-15,  1.61619211e-04, -7.48514620e-17, -2.86242939e-15,\n",
+       "         -9.67937287e-15, -2.35676503e-03, -1.23793909e-03, -4.24186956e-04,\n",
+       "          7.75772190e-16]),\n",
+       "  array([ 2.45467724e-06, -1.19562817e-17,  9.23884373e-01,  7.26304963e-18,\n",
+       "          2.50511148e-06,  4.03908672e-18,  1.00000000e+00,  1.02891520e-15,\n",
+       "          4.57895221e-15,  1.07040041e-03,  5.41009148e-04,  1.64825559e-04,\n",
+       "         -4.06550604e-16,  6.20653100e-07, -6.09086810e-16,  4.57426492e+00,\n",
+       "          6.81861614e-15,  1.55647977e-04, -8.15877146e-17, -2.79908252e-15,\n",
+       "         -1.00609559e-14, -2.41745479e-03, -1.27436039e-03, -4.41274767e-04,\n",
+       "          7.41082163e-16]),\n",
+       "  array([ 2.47730799e-06, -1.26142238e-17,  9.28341899e-01,  1.06395463e-17,\n",
+       "          2.58001269e-06,  3.99519480e-18,  1.00000000e+00,  1.02617890e-15,\n",
+       "          4.56852557e-15,  1.06792582e-03,  5.39700399e-04,  1.64368060e-04,\n",
+       "         -4.05844142e-16, -3.63261821e-08, -5.78140930e-16,  4.45752590e+00,\n",
+       "          6.75299408e-15,  1.49802417e-04, -8.77679957e-17, -2.73630053e-15,\n",
+       "         -1.04266389e-14, -2.47459244e-03, -1.30874933e-03, -4.57498982e-04,\n",
+       "          7.06462140e-16]),\n",
+       "  array([ 2.49937857e-06, -1.32694834e-17,  9.32684026e-01,  1.39817112e-17,\n",
+       "          2.65206173e-06,  3.94845217e-18,  1.00000000e+00,  1.02350482e-15,\n",
+       "          4.55774953e-15,  1.06539756e-03,  5.38359251e-04,  1.63895185e-04,\n",
+       "         -4.05172052e-16, -6.47747250e-07, -5.48351078e-16,  4.34212740e+00,\n",
+       "          6.68433070e-15,  1.44098082e-04, -9.34695629e-17, -2.67408348e-15,\n",
+       "         -1.07760487e-14, -2.52825769e-03, -1.34114829e-03, -4.72874388e-04,\n",
+       "          6.72090132e-16]),\n",
+       "  array([ 2.52088196e-06, -1.39214013e-17,  9.36912122e-01,  1.72884708e-17,\n",
+       "          2.72133686e-06,  3.89906528e-18,  1.00000000e+00,  1.02089239e-15,\n",
+       "          4.54664074e-15,  1.06281903e-03,  5.36987652e-04,  1.63407770e-04,\n",
+       "         -4.04533904e-16, -1.21585270e-06, -5.19704636e-16,  4.22809579e+00,\n",
+       "          6.61351998e-15,  1.38550270e-04, -9.87581715e-17, -2.61242340e-15,\n",
+       "         -1.11087881e-14, -2.57852873e-03, -1.37159878e-03, -4.87415383e-04,\n",
+       "          6.38148079e-16]),\n",
+       "  array([ 2.54181220e-06, -1.45693458e-17,  9.41027577e-01,  2.05591818e-17,\n",
+       "          2.78792358e-06,  3.84720751e-18,  1.00000000e+00,  1.01834107e-15,\n",
+       "          4.53521629e-15,  1.06019355e-03,  5.35587510e-04,  1.62906634e-04,\n",
+       "         -4.03929086e-16, -1.74287924e-06, -4.92184265e-16,  4.11545558e+00,\n",
+       "          6.54142276e-15,  1.33173430e-04, -1.03700045e-16, -2.55132133e-15,\n",
+       "         -1.14244505e-14, -2.62548252e-03, -1.40014163e-03, -5.01136132e-04,\n",
+       "          6.04818319e-16]),\n",
+       "  array([ 2.56216436e-06, -1.52127130e-17,  9.45031807e-01,  2.37936019e-17,\n",
+       "          2.85191386e-06,  3.79302426e-18,  1.00000000e+00,  1.01585030e-15,\n",
+       "          4.52349365e-15,  1.05752435e-03,  5.34160693e-04,  1.62392583e-04,\n",
+       "         -4.03356806e-16, -2.23104686e-06, -4.65768526e-16,  4.00422952e+00,\n",
+       "          6.46884096e-15,  1.27980559e-04, -1.08351087e-16, -2.49077498e-15,\n",
+       "         -1.17226354e-14, -2.66919506e-03, -1.42681730e-03, -5.14050745e-04,\n",
+       "          5.72280014e-16]),\n",
+       "  array([ 2.58193449e-06, -1.58509263e-17,  9.48926246e-01,  2.69918478e-17,\n",
+       "          2.91340517e-06,  3.73663454e-18,  1.00000000e+00,  1.01341951e-15,\n",
+       "          4.51149069e-15,  1.05481461e-03,  5.32709027e-04,  1.61866410e-04,\n",
+       "         -4.02816100e-16, -2.68254639e-06, -4.40432566e-16,  3.89443859e+00,\n",
+       "          6.39649275e-15,  1.22982623e-04, -1.12764134e-16, -2.43078938e-15,\n",
+       "         -1.20029625e-14, -2.70974170e-03, -1.45166606e-03, -5.26173445e-04,\n",
+       "          5.40705568e-16]),\n",
+       "  array([ 2.60111960e-06, -1.64834364e-17,  9.52712348e-01,  3.01543419e-17,\n",
+       "          2.97249917e-06,  3.67813500e-18,  1.00000000e+00,  1.01104814e-15,\n",
+       "          4.49922560e-15,  1.05206741e-03,  5.31234299e-04,  1.61328891e-04,\n",
+       "         -4.02305843e-16, -3.09952604e-06, -4.16148861e-16,  3.78610208e+00,\n",
+       "          6.32498897e-15,  1.18187999e-04, -1.16983840e-16, -2.37137157e-15,\n",
+       "         -1.22650873e-14, -2.74719742e-03, -1.47472826e-03, -5.37518743e-04,\n",
+       "          5.10257029e-16]),\n",
+       "  array([ 2.61971757e-06, -1.71097208e-17,  9.56391585e-01,  3.32817472e-17,\n",
+       "          3.02930015e-06,  3.61760556e-18,  1.00000000e+00,  1.00873561e-15,\n",
+       "          4.48671689e-15,  1.04928578e-03,  5.29738254e-04,  1.60780789e-04,\n",
+       "         -4.01824761e-16, -3.48407710e-06, -3.92887977e-16,  3.67923762e+00,\n",
+       "          6.25481133e-15,  1.13601961e-04, -1.21043701e-16, -2.31252782e-15,\n",
+       "         -1.25087149e-14, -2.78163711e-03, -1.49604457e-03, -5.48101606e-04,\n",
+       "          4.81082536e-16]),\n",
+       "  array([ 2.63772713e-06, -1.77292833e-17,  9.59965446e-01,  3.63748932e-17,\n",
+       "          3.08391326e-06,  3.55511419e-18,  1.00000000e+00,  1.00648134e-15,\n",
+       "          4.47398327e-15,  1.04647264e-03,  5.28222598e-04,  1.60222852e-04,\n",
+       "         -4.01371448e-16, -3.83821962e-06, -3.70619348e-16,  3.57386126e+00,\n",
+       "          6.18629270e-15,  1.09226218e-04, -1.24967637e-16, -2.25426643e-15,\n",
+       "         -1.27336149e-14, -2.81313590e-03, -1.51565617e-03, -5.57937620e-04,\n",
+       "          4.53312815e-16]),\n",
+       "  array([ 2.65514780e-06, -1.83416536e-17,  9.63435434e-01,  3.94346929e-17,\n",
+       "          3.13644252e-06,  3.49071851e-18,  1.00000000e+00,  1.00428474e-15,\n",
+       "          4.46104364e-15,  1.04363087e-03,  5.26688993e-04,  1.59655808e-04,\n",
+       "         -4.00944390e-16, -4.16388833e-06, -3.49312038e-16,  3.46998749e+00,\n",
+       "          6.11960023e-15,  1.05058534e-04, -1.28776325e-16, -2.19660652e-15,\n",
+       "         -1.29396346e-14, -2.84176934e-03, -1.53360504e-03, -5.67043140e-04,\n",
+       "          4.27057795e-16]),\n",
+       "  array([ 2.67197985e-06, -1.89463869e-17,  9.66803063e-01,  4.24620533e-17,\n",
+       "          3.18698874e-06,  3.42447073e-18,  1.00000000e+00,  1.00214517e-15,\n",
+       "          4.44791692e-15,  1.04076326e-03,  5.25139059e-04,  1.59080373e-04,\n",
+       "         -4.00541987e-16, -4.46291935e-06, -3.28935474e-16,  3.36762929e+00,\n",
+       "          6.05472158e-15,  1.01092431e-04, -1.32480542e-16, -2.13956986e-15,\n",
+       "         -1.31267126e-14, -2.86761374e-03, -1.54993405e-03, -5.75435418e-04,\n",
+       "          4.02403378e-16]),\n",
+       "  array([ 2.68822427e-06, -1.95430633e-17,  9.70069861e-01,  4.54577806e-17,\n",
+       "          3.23564725e-06,  3.35642275e-18,  1.00000000e+00,  1.00006199e-15,\n",
+       "          4.43462203e-15,  1.03787251e-03,  5.23574372e-04,  1.58497240e-04,\n",
+       "         -4.00162578e-16, -4.73703822e-06, -3.09460123e-16,  3.26679820e+00,\n",
+       "          5.99145533e-15,  9.73170153e-05, -1.36081011e-16, -2.08318086e-15,\n",
+       "         -1.32948912e-14, -2.89074632e-03, -1.56468722e-03, -5.83132711e-04,\n",
+       "          3.79408484e-16]),\n",
+       "  array([ 2.70388269e-06, -2.01312875e-17,  9.73237366e-01,  4.84224831e-17,\n",
+       "          3.28250571e-06,  3.28662732e-18,  1.00000000e+00,  9.98034509e-16,\n",
+       "          4.42117771e-15,  1.03496126e-03,  5.21996462e-04,  1.57907086e-04,\n",
+       "         -3.99804476e-16, -4.98784970e-06, -2.90858109e-16,  3.16750433e+00,\n",
+       "          5.92940587e-15,  9.37169352e-05, -1.39575918e-16, -2.02747612e-15,\n",
+       "         -1.34443277e-14, -2.91124539e-03, -1.57790975e-03, -5.90154347e-04,\n",
+       "          3.58102456e-16]),\n",
+       "  array([ 2.71895741e-06, -2.07106883e-17,  9.76307122e-01,  5.13564748e-17,\n",
+       "          3.32764196e-06,  3.21514427e-18,  1.00000000e+00,  9.96062017e-16,\n",
+       "          4.40760240e-15,  1.03203207e-03,  5.20406814e-04,  1.57310565e-04,\n",
+       "         -3.99465993e-16, -5.21682974e-06, -2.73103731e-16,  3.06975642e+00,\n",
+       "          5.86798402e-15,  9.02724960e-05, -1.42951222e-16, -1.97249162e-15,\n",
+       "         -1.35753040e-14, -2.92919048e-03, -1.58964815e-03, -5.96520758e-04,\n",
+       "          3.38482986e-16]),\n",
+       "  array([ 2.73345128e-06, -2.12809184e-17,  9.79280684e-01,  5.42596813e-17,\n",
+       "          3.37112194e-06,  3.14204419e-18,  1.00000000e+00,  9.94143749e-16,\n",
+       "          4.39391417e-15,  1.02908741e-03,  5.18806864e-04,  1.56708312e-04,\n",
+       "         -3.99145478e-16, -5.42532019e-06, -2.56173893e-16,  2.97356190e+00,\n",
+       "          5.80641393e-15,  8.69599552e-05, -1.46185309e-16, -1.91826790e-15,\n",
+       "         -1.36882343e-14, -2.94466242e-03, -1.59995017e-03, -6.02253458e-04,\n",
+       "          3.20514721e-16]),\n",
+       "  array([ 2.74736774e-06, -2.18416540e-17,  9.82159611e-01,  5.71315546e-17,\n",
+       "          3.41299794e-06,  3.06740994e-18,  1.00000000e+00,  9.92278894e-16,\n",
+       "          4.38013050e-15,  1.02612967e-03,  5.17197999e-04,  1.56100937e-04,\n",
+       "         -3.98841349e-16, -5.61452639e-06, -2.40048404e-16,  2.87892692e+00,\n",
+       "          5.74374724e-15,  8.37520085e-05, -1.49253677e-16, -1.86485495e-15,\n",
+       "         -1.37836705e-14, -2.95774324e-03, -1.60886479e-03, -6.07374964e-04,\n",
+       "          3.04128755e-16]),\n",
+       "  array([ 2.76071076e-06, -2.23925950e-17,  9.84945467e-01,  5.99709968e-17,\n",
+       "          3.45330718e-06,  2.99134043e-18,  1.00000000e+00,  9.90466590e-16,\n",
+       "          4.36626819e-15,  1.02316115e-03,  5.15581557e-04,  1.55489028e-04,\n",
+       "         -3.98552126e-16, -5.78551818e-06, -2.24710154e-16,  2.78585637e+00,\n",
+       "          5.67888529e-15,  8.06184782e-05, -1.52124240e-16, -1.81230457e-15,\n",
+       "         -1.38623029e-14, -2.96851614e-03, -1.61644202e-03, -6.11908655e-04,\n",
+       "          2.89223204e-16]),\n",
+       "  array([ 2.77348483e-06, -2.29334648e-17,  9.87639821e-01,  6.27763014e-17,\n",
+       "          3.49207078e-06,  2.91395239e-18,  1.00000000e+00,  9.88705916e-16,\n",
+       "          4.35234324e-15,  1.02018409e-03,  5.13958824e-04,  1.54873150e-04,\n",
+       "         -3.98276461e-16, -5.93923426e-06, -2.10145148e-16,  2.69435397e+00,\n",
+       "          5.61060981e-15,  7.75272001e-05, -1.54761346e-16, -1.76067349e-15,\n",
+       "         -1.39249578e-14, -2.97706523e-03, -1.62273267e-03, -6.15878571e-04,\n",
+       "          2.75665057e-16]),\n",
+       "  array([ 2.78569494e-06, -2.34640103e-17,  9.90244244e-01,  6.55451122e-17,\n",
+       "          3.52929333e-06,  2.83538201e-18,  1.00000000e+00,  9.86995895e-16,\n",
+       "          4.33837065e-15,  1.01720061e-03,  5.12331036e-04,  1.54253840e-04,\n",
+       "         -3.98013167e-16, -6.07649011e-06, -1.96342393e-16,  2.60442227e+00,\n",
+       "          5.53762235e-15,  7.44450961e-05, -1.57126107e-16, -1.71002134e-15,\n",
+       "         -1.39725898e-14, -2.98347522e-03, -1.62778804e-03, -6.19309147e-04,\n",
+       "          2.63293469e-16]),\n",
+       "  array([ 2.79734654e-06, -2.39840023e-17,  9.92760306e-01,  6.82744078e-17,\n",
+       "          3.56496303e-06,  2.75578465e-18,  1.00000000e+00,  9.85335483e-16,\n",
+       "          4.32436438e-15,  1.01421278e-03,  5.10699377e-04,  1.53631616e-04,\n",
+       "         -3.97761243e-16, -6.19798937e-06, -1.83293632e-16,  2.51606272e+00,\n",
+       "          5.45859210e-15,  7.13393998e-05, -1.59180133e-16, -1.66041244e-15,\n",
+       "         -1.40062682e-14, -2.98783106e-03, -1.63165946e-03, -6.22224897e-04,\n",
+       "          2.51924588e-16]),\n",
+       "  array([ 2.80844557e-06, -2.44932352e-17,  9.95189582e-01,  7.09605131e-17,\n",
+       "          3.59905252e-06,  2.67533455e-18,  1.00000000e+00,  9.83723570e-16,\n",
+       "          4.31033722e-15,  1.01122256e-03,  5.09064979e-04,  1.53006966e-04,\n",
+       "         -3.97519885e-16, -6.30433823e-06, -1.70992938e-16,  2.42927567e+00,\n",
+       "          5.37221123e-15,  6.81789886e-05, -1.60885706e-16, -1.61191277e-15,\n",
+       "         -1.40271574e-14, -2.99021739e-03, -1.63439789e-03, -6.24650054e-04,\n",
+       "          2.41357905e-16]),\n",
+       "  array([ 2.81899841e-06, -2.49915279e-17,  9.97533642e-01,  7.35991406e-17,\n",
+       "          3.63152040e-06,  2.59422500e-18,  1.00000000e+00,  9.82158985e-16,\n",
+       "          4.29630073e-15,  1.00823185e-03,  5.07428925e-04,  1.52380357e-04,\n",
+       "         -3.97288501e-16, -6.39606250e-06, -1.59436175e-16,  2.34406045e+00,\n",
+       "          5.27725578e-15,  6.49357567e-05, -1.62204704e-16, -1.56458505e-15,\n",
+       "         -1.40364917e-14, -2.99071803e-03, -1.63605338e-03, -6.26608198e-04,\n",
+       "          2.31383985e-16]),\n",
+       "  array([ 2.82901188e-06, -2.54787237e-17,  9.99794058e-01,  7.61854651e-17,\n",
+       "          3.66231338e-06,  2.51266563e-18,  1.00000000e+00,  9.80640492e-16,\n",
+       "          4.28226518e-15,  1.00524243e-03,  5.05792251e-04,  1.51752235e-04,\n",
+       "         -3.97066708e-16, -6.47362663e-06, -1.48620335e-16,  2.26041539e+00,\n",
+       "          5.17264973e-15,  6.15859490e-05, -1.63104494e-16, -1.51849259e-15,\n",
+       "         -1.40355443e-14, -2.98941535e-03, -1.63667457e-03, -6.28121882e-04,\n",
+       "          2.21793273e-16]),\n",
+       "  array([ 2.83849323e-06, -2.59546903e-17,  1.00197240e+00,  7.87142291e-17,\n",
+       "          3.69136906e-06,  2.43087743e-18,  1.00000000e+00,  9.79166791e-16,\n",
+       "          4.26823959e-15,  1.00225604e-03,  5.04155943e-04,  1.51123023e-04,\n",
+       "         -3.96854322e-16, -6.53745383e-06, -1.38542800e-16,  2.17833786e+00,\n",
+       "          5.05752873e-15,  5.81113679e-05, -1.63562305e-16, -1.47370131e-15,\n",
+       "         -1.40255921e-14, -2.98638966e-03, -1.63630819e-03, -6.29212297e-04,\n",
+       "          2.12385523e-16]),\n",
+       "  array([ 2.84745013e-06, -2.64193206e-17,  1.00407022e+00,  8.11798784e-17,\n",
+       "          3.71861924e-06,  2.34908875e-18,  1.00000000e+00,  9.77736517e-16,\n",
+       "          4.25423171e-15,  9.99274322e-04,  5.02520944e-04,  1.50493124e-04,\n",
+       "         -3.96651343e-16, -6.58794634e-06, -1.29200535e-16,  2.09782430e+00,\n",
+       "          4.93129940e-15,  5.45003599e-05, -1.63563434e-16, -1.43027416e-15,\n",
+       "         -1.40078782e-14, -2.98171867e-03, -1.63499867e-03, -6.29898998e-04,\n",
+       "          2.02979214e-16]),\n",
+       "  array([ 2.85589068e-06, -2.68725321e-17,  1.00608909e+00,  8.35767229e-17,\n",
+       "          3.74399349e-06,  2.26753402e-18,  1.00000000e+00,  9.76348255e-16,\n",
+       "          4.24024814e-15,  9.96298845e-04,  5.00888156e-04,  1.49862924e-04,\n",
+       "         -3.96457923e-16, -6.62550482e-06, -1.20589289e-16,  2.01887027e+00,\n",
+       "          4.79368970e-15,  5.07484976e-05, -1.63095763e-16, -1.38826133e-15,\n",
+       "         -1.39835731e-14, -2.97547694e-03, -1.63278780e-03, -6.30199715e-04,\n",
+       "          1.93420212e-16]),\n",
+       "  array([ 2.86382332e-06, -2.73142672e-17,  1.00803056e+00,  8.58991154e-17,\n",
+       "          3.76742293e-06,  2.18644886e-18,  1.00000000e+00,  9.75000548e-16,\n",
+       "          4.22629440e-15,  9.93331110e-04,  4.99258442e-04,  1.49232794e-04,\n",
+       "         -3.96274334e-16, -6.65054581e-06, -1.12702809e-16,  1.94147047e+00,\n",
+       "          4.64478583e-15,  4.68588869e-05, -1.62156840e-16, -1.34770711e-15,\n",
+       "         -1.39537394e-14, -2.96773554e-03, -1.62971454e-03, -6.30130283e-04,\n",
+       "          1.83588914e-16]),\n",
+       "  array([ 2.87125692e-06, -2.77444931e-17,  1.00989618e+00,  8.81416409e-17,\n",
+       "          3.78884396e-06,  2.10606675e-18,  1.00000000e+00,  9.73691903e-16,\n",
+       "          4.21237510e-15,  9.90372548e-04,  4.97632627e-04,  1.48603089e-04,\n",
+       "         -3.96100929e-16, -6.66351629e-06, -1.05532156e-16,  1.86561878e+00,\n",
+       "          4.48505157e-15,  4.28420556e-05, -1.60751011e-16, -1.30864496e-15,\n",
+       "         -1.39193012e-14, -2.95856177e-03, -1.62581503e-03, -6.29704682e-04,\n",
+       "          1.73405085e-16]),\n",
+       "  array([ 2.87820067e-06, -2.81632010e-17,  1.01168749e+00,  9.02993038e-17,\n",
+       "          3.80820166e-06,  2.02661189e-18,  1.00000000e+00,  9.72420797e-16,\n",
+       "          4.19849408e-15,  9.87424529e-04,  4.96011504e-04,  1.47974154e-04,\n",
+       "         -3.95938099e-16, -6.66490471e-06, -9.90651357e-17,  1.79130830e+00,\n",
+       "          4.31532652e-15,  3.87154041e-05, -1.58896779e-16, -1.27110649e-15,\n",
+       "         -1.38810220e-14, -2.94801907e-03, -1.62112265e-03, -6.28935219e-04,\n",
+       "          1.62829736e-16]),\n",
+       "  array([ 2.88466409e-06, -2.85704059e-17,  1.01340602e+00,  9.23677047e-17,\n",
+       "          3.82545279e-06,  1.94830212e-18,  1.00000000e+00,  9.71185700e-16,\n",
+       "          4.18465459e-15,  9.84488362e-04,  4.94395836e-04,  1.47346321e-04,\n",
+       "         -3.95786235e-16, -6.65524780e-06, -9.32858993e-17,  1.71853137e+00,\n",
+       "          4.13680239e-15,  3.45022556e-05, -1.56606903e-16, -1.23509655e-15,\n",
+       "         -1.38394924e-14, -2.93616715e-03, -1.61566839e-03, -6.27832808e-04,\n",
+       "          1.51863631e-16]),\n",
+       "  array([ 2.89065704e-06, -2.89661457e-17,  1.01505330e+00,  9.43431924e-17,\n",
+       "          3.84056806e-06,  1.87134193e-18,  1.00000000e+00,  9.69985080e-16,\n",
+       "          4.17085946e-15,  9.81565299e-04,  4.92786354e-04,  1.46719914e-04,\n",
+       "         -3.95645693e-16, -6.63513303e-06, -8.81747433e-17,  1.64727963e+00,\n",
+       "          3.95097620e-15,  3.02305466e-05, -1.53908057e-16, -1.20061989e-15,\n",
+       "         -1.37951307e-14, -2.92306224e-03, -1.60948119e-03, -6.26407361e-04,\n",
+       "          1.40542285e-16]),\n",
+       "  array([ 2.89618963e-06, -2.93504803e-17,  1.01663084e+00,  9.62229838e-17,\n",
+       "          3.85353369e-06,  1.79592195e-18,  1.00000000e+00,  9.68817413e-16,\n",
+       "          4.15711126e-15,  9.78656542e-04,  4.91183766e-04,  1.46095246e-04,\n",
+       "         -3.95516765e-16, -6.60519680e-06, -8.37081176e-17,  1.57754399e+00,\n",
+       "          3.75958329e-15,  2.59312575e-05, -1.50827961e-16, -1.16766699e-15,\n",
+       "         -1.37481961e-14, -2.90875749e-03, -1.60258850e-03, -6.24668232e-04,\n",
+       "          1.28927599e-16]),\n",
+       "  array([ 2.90127223e-06, -2.97234907e-17,  1.01814016e+00,  9.80052404e-17,\n",
+       "          3.86435204e-06,  1.72221938e-18,  1.00000000e+00,  9.67681199e-16,\n",
+       "          4.14341245e-15,  9.75763238e-04,  4.89588749e-04,  1.45472621e-04,\n",
+       "         -3.95399669e-16, -6.56611874e-06, -7.98588456e-17,  1.50931476e+00,\n",
+       "          3.56451387e-15,  2.16366967e-05, -1.47393497e-16, -1.13621469e-15,\n",
+       "         -1.36988143e-14, -2.89330354e-03, -1.59501688e-03, -6.22624698e-04,\n",
+       "          1.17096718e-16]),\n",
+       "  array([ 2.90591544e-06, -3.00852774e-17,  1.01958274e+00,  9.96890999e-17,\n",
+       "          3.87304143e-06,  1.65039939e-18,  1.00000000e+00,  9.66574972e-16,\n",
+       "          4.12976543e-15,  9.72886489e-04,  4.88001956e-04,  1.44852335e-04,\n",
+       "         -3.95294540e-16, -6.51861279e-06, -7.65965405e-17,  1.44258157e+00,\n",
+       "          3.36771950e-15,  1.73787702e-05, -1.43628657e-16, -1.10622705e-15,\n",
+       "         -1.36470140e-14, -2.87674908e-03, -1.58679256e-03, -6.20286421e-04,\n",
+       "          1.05128976e-16]),\n",
+       "  array([ 2.91013004e-06, -3.04359597e-17,  1.02096007e+00,  1.01274658e-16,\n",
+       "          3.87963511e-06,  1.58061759e-18,  1.00000000e+00,  9.65497315e-16,\n",
+       "          4.11617266e-15,  9.70027348e-04,  4.86424014e-04,  1.44234671e-04,\n",
+       "         -3.95201448e-16, -6.46341595e-06, -7.38881830e-17,  1.37733348e+00,\n",
+       "          3.17111663e-15,  1.31873705e-05, -1.39552646e-16, -1.07765653e-15,\n",
+       "         -1.35927702e-14, -2.85914157e-03, -1.57794204e-03, -6.17663860e-04,\n",
+       "          9.30921036e-17]),\n",
+       "  array([ 2.91392699e-06, -3.07756739e-17,  1.02227363e+00,  1.02762906e-16,\n",
+       "          3.88417962e-06,  1.51302307e-18,  1.00000000e+00,  9.64446869e-16,\n",
+       "          4.10263661e-15,  9.67186820e-04,  4.84855522e-04,  1.43619902e-04,\n",
+       "         -3.95120419e-16, -6.40127575e-06, -7.16988169e-17,  1.31355898e+00,\n",
+       "          2.97649583e-15,  9.08901659e-06, -1.35178410e-16, -1.05044579e-15,\n",
+       "         -1.35360519e-14, -2.84052774e-03, -1.56849250e-03, -6.14768589e-04,\n",
+       "          8.10290359e-17]),\n",
+       "  array([ 2.91731738e-06, -3.11045722e-17,  1.02352488e+00,  1.04155628e-16,\n",
+       "          3.88673255e-06,  1.44776204e-18,  1.00000000e+00,  9.63422340e-16,\n",
+       "          4.08915974e-15,  9.64365866e-04,  4.83297050e-04,  1.43008289e-04,\n",
+       "         -3.95051472e-16, -6.33293738e-06, -6.99923076e-17,  1.25124600e+00,\n",
+       "          2.78544488e-15,  5.10585674e-06, -1.30511771e-16, -1.02452977e-15,\n",
+       "         -1.34768688e-14, -2.82095421e-03, -1.55847218e-03, -6.11613490e-04,\n",
+       "          6.89467199e-17]),\n",
+       "  array([ 2.92031239e-06, -3.14228214e-17,  1.02471526e+00,  1.05455274e-16,\n",
+       "          3.88736011e-06,  1.38498139e-18,  1.00000000e+00,  9.62422501e-16,\n",
+       "          4.07574443e-15,  9.61565398e-04,  4.81749139e-04,  1.42400076e-04,\n",
+       "         -3.94994664e-16, -6.25913166e-06, -6.87321043e-17,  1.19038199e+00,\n",
+       "          2.59929344e-15,  1.25511957e-06, -1.25551319e-16, -9.99838205e-16,\n",
+       "         -1.34153119e-14, -2.80046782e-03, -1.54791051e-03, -6.08212790e-04,\n",
+       "          5.68082600e-17]),\n",
+       "  array([ 2.92292329e-06, -3.17306014e-17,  1.02584621e+00,  1.06664816e-16,\n",
+       "          3.88613464e-06,  1.32483199e-18,  1.00000000e+00,  9.61446203e-16,\n",
+       "          4.06239284e-15,  9.58786282e-04,  4.80212301e-04,  1.41795494e-04,\n",
+       "         -3.94950134e-16, -6.18056455e-06, -6.78819503e-17,  1.13095389e+00,\n",
+       "          2.41908489e-15, -2.45093369e-06, -1.20289134e-16, -9.76298256e-16,\n",
+       "         -1.33515847e-14, -2.77911589e-03, -1.53683806e-03, -6.04581941e-04,\n",
+       "          4.45295063e-17]),\n",
+       "  array([ 2.92516140e-06, -3.20281042e-17,  1.02691916e+00,  1.07787606e-16,\n",
+       "          3.88313237e-06,  1.26747114e-18,  1.00000000e+00,  9.60492366e-16,\n",
+       "          4.04910682e-15,  9.56029336e-04,  4.78687015e-04,  1.41194757e-04,\n",
+       "         -3.94918153e-16, -6.09790900e-06, -6.74064904e-17,  1.07294817e+00,\n",
+       "          2.24557896e-15, -6.00454542e-06, -1.14712343e-16, -9.53837147e-16,\n",
+       "         -1.32860197e-14, -2.75694619e-03, -1.52528632e-03, -6.00737327e-04,\n",
+       "          3.19808550e-17]),\n",
+       "  array([ 2.92703807e-06, -3.23155326e-17,  1.02793551e+00,  1.08827248e-16,\n",
+       "          3.87843161e-06,  1.21306386e-18,  1.00000000e+00,  9.59559981e-16,\n",
+       "          4.03588774e-15,  9.53295329e-04,  4.77173728e-04,  1.40598061e-04,\n",
+       "         -3.94899159e-16, -6.01179952e-06, -6.72717402e-17,  1.01635089e+00,\n",
+       "          2.07928523e-15, -9.40151869e-06, -1.08805466e-16, -9.32384504e-16,\n",
+       "         -1.32190797e-14, -2.73400679e-03, -1.51328721e-03, -5.96695804e-04,\n",
+       "          1.89945683e-17]),\n",
+       "  array([ 2.92856466e-06, -3.25930991e-17,  1.02889666e+00,  1.09787510e-16,\n",
+       "          3.87211167e-06,  1.16178273e-18,  1.00000000e+00,  9.58648107e-16,\n",
+       "          4.02273640e-15,  9.50584983e-04,  4.75672855e-04,  1.40005587e-04,\n",
+       "         -3.94893781e-16, -5.92282951e-06, -6.74453950e-17,  9.61147695e-01,\n",
+       "          1.92052449e-15, -1.26398731e-05, -1.02553432e-16, -9.11874251e-16,\n",
+       "         -1.31513411e-14, -2.71034565e-03, -1.50087245e-03, -5.92474111e-04,\n",
+       "          5.37740756e-18]),\n",
+       "  array([ 2.92975250e-06, -3.28610245e-17,  1.02980398e+00,  1.10672266e-16,\n",
+       "          3.86425256e-06,  1.11380589e-18,  1.00000000e+00,  9.57755861e-16,\n",
+       "          4.00965294e-15,  9.47898973e-04,  4.74184782e-04,  1.39417499e-04,\n",
+       "         -3.94902853e-16, -5.83155136e-06, -6.78969769e-17,  9.07323825e-01,\n",
+       "          1.76951163e-15, -1.57182195e-05, -9.59451057e-17, -8.92245837e-16,\n",
+       "         -1.30834619e-14, -2.68601000e-03, -1.48807277e-03, -5.88088166e-04,\n",
+       "         -9.07217101e-18]),\n",
+       "  array([ 2.93061288e-06, -3.31195371e-17,  1.03065885e+00,  1.11485491e-16,\n",
+       "          3.85493556e-06,  1.06931316e-18,  1.00000000e+00,  9.56882417e-16,\n",
+       "          3.99663681e-15,  9.45237928e-04,  4.72709865e-04,  1.38833946e-04,\n",
+       "         -3.94927397e-16, -5.73847874e-06, -6.85978368e-17,  8.54864177e-01,\n",
+       "          1.62645064e-15, -1.86340114e-05, -8.89771228e-17, -8.73444699e-16,\n",
+       "         -1.30161351e-14, -2.66104563e-03, -1.47491698e-03, -5.83552308e-04,\n",
+       "         -2.45435108e-17]),\n",
+       "  array([ 2.93115703e-06, -3.33688712e-17,  1.03146260e+00,  1.12231306e-16,\n",
+       "          3.84424463e-06,  1.02848020e-18,  1.00000000e+00,  9.56026995e-16,\n",
+       "          3.98368677e-15,  9.42602432e-04,  4.71248434e-04,  1.38255068e-04,\n",
+       "         -3.94968589e-16, -5.64409049e-06, -6.95210421e-17,  8.03753302e-01,\n",
+       "          1.49163032e-15, -2.13818579e-05, -8.16577808e-17, -8.55421897e-16,\n",
+       "         -1.29500324e-14, -2.63549611e-03, -1.46143111e-03, -5.78878535e-04,\n",
+       "         -4.11916090e-17]),\n",
+       "  array([ 2.93139609e-06, -3.36092665e-17,  1.03221658e+00,  1.12914060e-16,\n",
+       "          3.83226858e-06,  9.91470861e-19,  1.00000000e+00,  9.55188862e-16,\n",
+       "          3.97080103e-15,  9.39993030e-04,  4.69800797e-04,  1.37680992e-04,\n",
+       "         -3.95027704e-16, -5.54883528e-06, -7.06411957e-17,  7.53975434e-01,\n",
+       "          1.36550821e-15, -2.39520980e-05, -7.40107371e-17, -8.38132924e-16,\n",
+       "         -1.28857431e-14, -2.60940187e-03, -1.44763748e-03, -5.74075800e-04,\n",
+       "         -5.91152778e-17]),\n",
+       "  array([ 2.93134111e-06, -3.38409663e-17,  1.03292209e+00,  1.13538445e-16,\n",
+       "          3.81910366e-06,  9.58427867e-19,  1.00000000e+00,  9.54367326e-16,\n",
+       "          3.95797732e-15,  9.37410230e-04,  4.68367243e-04,  1.37111843e-04,\n",
+       "         -3.95106042e-16, -5.45313613e-06, -7.19342376e-17,  7.05514512e-01,\n",
+       "          1.24877041e-15, -2.63298358e-05, -6.60782309e-17, -8.21535791e-16,\n",
+       "         -1.28237126e-14, -2.58279951e-03, -1.43355398e-03, -5.69149440e-04,\n",
+       "         -7.83376636e-17]),\n",
+       "  array([ 2.93100298e-06, -3.40642166e-17,  1.03358045e+00,  1.14109623e-16,\n",
+       "          3.80485636e-06,  9.29462288e-19,  1.00000000e+00,  9.53561738e-16,\n",
+       "          3.94521313e-15,  9.34854509e-04,  4.66948049e-04,  1.36547742e-04,\n",
+       "         -3.95204833e-16, -5.35739395e-06, -7.33772798e-17,  6.58354202e-01,\n",
+       "          1.14235638e-15, -2.84946141e-05, -5.79235594e-17, -8.05588482e-16,\n",
+       "         -1.27641871e-14, -2.55572107e-03, -1.41919353e-03, -5.64100796e-04,\n",
+       "         -9.87910801e-17]),\n",
+       "  array([ 2.93039246e-06, -3.42792652e-17,  1.03419292e+00,  1.14633343e-16,\n",
+       "          3.78964592e-06,  9.04642282e-19,  1.00000000e+00,  9.52771492e-16,\n",
+       "          3.93250596e-15,  9.32326316e-04,  4.65543485e-04,  1.35988815e-04,\n",
+       "         -3.95325140e-16, -5.26198926e-06, -7.49485207e-17,  6.12477913e-01,\n",
+       "          1.04744099e-15, -3.04208685e-05, -4.96325549e-17, -7.90245938e-16,\n",
+       "         -1.27071672e-14, -2.52819365e-03, -1.40456384e-03, -5.58927085e-04,\n",
+       "         -1.20307819e-16]),\n",
+       "  array([ 2.92952011e-06, -3.44863599e-17,  1.03476079e+00,  1.15116028e-16,\n",
+       "          3.77360630e-06,  8.83981690e-19,  1.00000000e+00,  9.51996035e-16,\n",
+       "          3.91985359e-15,  9.29826076e-04,  4.64153818e-04,  1.35435193e-04,\n",
+       "         -3.95467759e-16, -5.16728168e-06, -7.66272701e-17,  5.67868824e-01,\n",
+       "          9.65369600e-16, -3.20792435e-05, -4.13138483e-17, -7.75456726e-16,\n",
+       "         -1.26523762e-14, -2.50023914e-03, -1.38966746e-03, -5.53621572e-04,\n",
+       "         -1.42618123e-16]),\n",
+       "  array([ 2.92839632e-06, -3.46857484e-17,  1.03528530e+00,  1.15564802e-16,\n",
+       "          3.75688691e-06,  8.67429188e-19,  1.00000000e+00,  9.51234875e-16,\n",
+       "          3.90725434e-15,  9.27354202e-04,  4.62779316e-04,  1.34887019e-04,\n",
+       "         -3.95633114e-16, -5.07360680e-06, -7.83941029e-17,  5.24509898e-01,\n",
+       "          8.97546915e-16, -3.34387812e-05, -3.30977675e-17, -7.61159543e-16,\n",
+       "         -1.25992425e-14, -2.47187435e-03, -1.37450229e-03, -5.48174058e-04,\n",
+       "         -1.65355896e-16]),\n",
+       "  array([ 2.92703126e-06, -3.48776766e-17,  1.03576769e+00,  1.15987444e-16,\n",
+       "          3.73965195e-06,  8.54858705e-19,  1.00000000e+00,  9.50487596e-16,\n",
+       "          3.89470745e-15,  9.24911091e-04,  4.61420253e-04,  1.34344447e-04,\n",
+       "         -3.95821186e-16, -4.98127048e-06, -8.02311361e-17,  4.82383900e-01,\n",
+       "          8.45285183e-16, -3.44699103e-05, -2.51338077e-17, -7.47279710e-16,\n",
+       "         -1.25468990e-14, -2.44311138e-03, -1.35906238e-03, -5.42571685e-04,\n",
+       "         -1.88072003e-16]),\n",
+       "  array([ 2.92543488e-06, -3.50623885e-17,  1.03620916e+00,  1.16392255e-16,\n",
+       "          3.72207792e-06,  8.46061795e-19,  1.00000000e+00,  9.49753870e-16,\n",
+       "          3.88221325e-15,  9.22497132e-04,  4.60076914e-04,  1.33807647e-04,\n",
+       "         -3.96031441e-16, -4.89054117e-06, -8.21224074e-17,  4.41473421e-01,\n",
+       "          8.09622204e-16, -3.51480731e-05, -1.75867142e-17, -7.33725844e-16,\n",
+       "         -1.24941962e-14, -2.41395828e-03, -1.34333909e-03, -5.36800036e-04,\n",
+       "         -2.10254313e-16]),\n",
+       "  array([ 2.92361688e-06, -3.52401255e-17,  1.03661092e+00,  1.16787817e-16,\n",
+       "          3.70434904e-06,  8.40742592e-19,  1.00000000e+00,  9.49033483e-16,\n",
+       "          3.86977352e-15,  9.20112712e-04,  4.58749592e-04,  1.33276803e-04,\n",
+       "         -3.96262794e-16, -4.80164081e-06, -8.40543131e-17,  4.01760891e-01,\n",
+       "          7.91123585e-16, -3.54577509e-05, -1.06313358e-17, -7.20386843e-16,\n",
+       "         -1.24397289e-14, -2.38441995e-03, -1.32732257e-03, -5.30844456e-04,\n",
+       "         -2.31352945e-16]),\n",
+       "  array([ 2.92158677e-06, -3.54111263e-17,  1.03697415e+00,  1.17182660e-16,\n",
+       "          3.68665075e-06,  8.38515801e-19,  1.00000000e+00,  9.48326354e-16,\n",
+       "          3.85739165e-15,  9.17758213e-04,  4.57438588e-04,  1.32752111e-04,\n",
+       "         -3.96513602e-16, -4.71473544e-06, -8.60160519e-17,  3.63228597e-01,\n",
+       "          7.89686668e-16, -3.53965733e-05, -4.44652263e-18, -7.07129418e-16,\n",
+       "         -1.23818717e-14, -2.35449924e-03, -1.31100336e-03, -5.24691519e-04,\n",
+       "         -2.50808685e-16]),\n",
+       "  array([ 2.91935380e-06, -3.55756273e-17,  1.03730001e+00,  1.17584843e-16,\n",
+       "          3.66916118e-06,  8.38908055e-19,  1.00000000e+00,  9.47632557e-16,\n",
+       "          3.84507283e-15,  9.15434015e-04,  4.56144214e-04,  1.32233781e-04,\n",
+       "         -3.96781685e-16, -4.62992670e-06, -8.80000111e-17,  3.25858701e-01,\n",
+       "          8.04364853e-16, -3.49791559e-05,  7.91573746e-19, -6.93796329e-16,\n",
+       "         -1.23188202e-14, -2.32419811e-03, -1.29437413e-03, -5.18330532e-04,\n",
+       "         -2.68082165e-16]),\n",
+       "  array([ 2.91692702e-06, -3.57338630e-17,  1.03758964e+00,  1.18001458e-16,\n",
+       "          3.65204103e-06,  8.41362707e-19,  1.00000000e+00,  9.46952352e-16,\n",
+       "          3.83282419e-15,  9.13140496e-04,  4.54866783e-04,  1.31722026e-04,\n",
+       "         -3.97064366e-16, -4.54724545e-06, -9.00020352e-17,  2.89633255e-01,\n",
+       "          8.33230683e-16, -3.42402885e-05,  4.91638582e-18, -6.80205533e-16,\n",
+       "         -1.22486366e-14, -2.29351888e-03, -1.27743122e-03, -5.11754943e-04,\n",
+       "         -2.82681344e-16]),\n",
+       "  array([ 2.91431528e-06, -3.58860665e-17,  1.03784418e+00,  1.18438105e-16,\n",
+       "          3.63542247e-06,  8.45247950e-19,  1.00000000e+00,  9.46286201e-16,\n",
+       "          3.82065490e-15,  9.10878031e-04,  4.53606607e-04,  1.31217062e-04,\n",
+       "         -3.97358551e-16, -4.46664879e-06, -9.20215187e-17,  2.54534218e-01,\n",
+       "          8.73293828e-16, -3.32371167e-05,  7.77759729e-18, -6.66150362e-16,\n",
+       "         -1.21692948e-14, -2.26246531e-03, -1.26017613e-03, -5.04963554e-04,\n",
+       "         -2.94184974e-16]),\n",
+       "  array([ 2.91152726e-06, -3.60324708e-17,  1.03806472e+00,  1.18898348e-16,\n",
+       "          3.61939747e-06,  8.49868003e-19,  1.00000000e+00,  9.45634800e-16,\n",
+       "          3.80857617e-15,  9.08646987e-04,  4.52363990e-04,  1.30719101e-04,\n",
+       "         -3.97660811e-16, -4.38802130e-06, -9.40612833e-17,  2.20543469e-01,\n",
+       "          9.20486328e-16, -3.20500077e-05,  9.24724924e-18, -6.51400820e-16,\n",
+       "         -1.20787256e-14, -2.23104360e-03, -1.24261657e-03, -4.97961393e-04,\n",
+       "         -3.02260173e-16]),\n",
+       "  array([ 2.90857150e-06, -3.61733098e-17,  1.03825236e+00,  1.19383210e-16,\n",
+       "          3.60400653e-06,  8.54476944e-19,  1.00000000e+00,  9.44999094e-16,\n",
+       "          3.79660131e-15,  9.06447724e-04,  4.51139223e-04,  1.30228341e-04,\n",
+       "         -3.97967484e-16, -4.31118130e-06, -9.61272152e-17,  1.87642826e-01,\n",
+       "          9.69722326e-16, -3.07818762e-05,  9.22505141e-18, -6.35705993e-16,\n",
+       "         -1.19748615e-14, -2.19926321e-03, -1.22476708e-03, -4.90760186e-04,\n",
+       "         -3.06672820e-16]),\n",
+       "  array([ 2.90545641e-06, -3.63088197e-17,  1.03840818e+00,  1.19890726e-16,\n",
+       "          3.58922860e-06,  8.58294747e-19,  1.00000000e+00,  9.44380297e-16,\n",
+       "          3.78474563e-15,  9.04280587e-04,  4.49932574e-04,  1.29744962e-04,\n",
+       "         -3.98274774e-16, -4.23589225e-06, -9.82276618e-17,  1.55814057e-01,\n",
+       "          1.01503373e-15, -2.95558558e-05,  7.64279243e-18, -6.18797549e-16,\n",
+       "         -1.18556824e-14, -2.16713733e-03, -1.20664924e-03, -4.83378340e-04,\n",
+       "         -3.07290283e-16]),\n",
+       "  array([ 2.90219034e-06, -3.64392400e-17,  1.03853321e+00,  1.20415615e-16,\n",
+       "          3.57497294e-06,  8.60525080e-19,  1.00000000e+00,  9.43779903e-16,\n",
+       "          3.77302636e-15,  9.02145904e-04,  4.48744283e-04,  1.29269122e-04,\n",
+       "         -3.98578851e-16, -4.16187902e-06, -1.00372609e-16,  1.25038893e-01,\n",
+       "          1.04977714e-15, -2.85113277e-05,  4.46785151e-18, -6.00394282e-16,\n",
+       "         -1.17192632e-14, -2.13468325e-03, -1.18829122e-03, -4.75840431e-04,\n",
+       "         -3.04076751e-16]),\n",
+       "  array([ 2.89878155e-06, -3.65648145e-17,  1.03862851e+00,  1.20949066e-16,\n",
+       "          3.56107372e-06,  8.60374424e-19,  1.00000000e+00,  9.43199695e-16,\n",
+       "          3.76146254e-15,  9.00043981e-04,  4.47574556e-04,  1.28800946e-04,\n",
+       "         -3.98875933e-16, -4.08884840e-06, -1.02572686e-16,  9.52990467e-02,\n",
+       "          1.06690185e-15, -2.77984479e-05, -2.94149875e-19, -5.80207832e-16,\n",
+       "         -1.15638263e-14, -2.10192239e-03, -1.16972701e-03, -4.68176223e-04,\n",
+       "         -2.97082238e-16]),\n",
+       "  array([ 2.89523828e-06, -3.66857925e-17,  1.03869509e+00,  1.21478698e-16,\n",
+       "          3.54728800e-06,  8.57072066e-19,  1.00000000e+00,  9.42641745e-16,\n",
+       "          3.75007474e-15,  8.97975101e-04,  4.46423561e-04,  1.28340526e-04,\n",
+       "         -3.99162360e-16, -4.01651258e-06, -1.04838047e-16,  6.65762204e-02,\n",
+       "          1.05926388e-15, -2.75714386e-05, -6.59760906e-18, -5.57949955e-16,\n",
+       "         -1.13877997e-14, -2.06888016e-03, -1.15099508e-03, -4.60419261e-04,\n",
+       "         -2.86426890e-16]),\n",
+       "  array([ 2.89156877e-06, -3.68024289e-17,  1.03873394e+00,  1.21988682e-16,\n",
+       "          3.53329749e-06,  8.49901838e-19,  1.00000000e+00,  9.42108432e-16,\n",
+       "          3.73888486e-15,  8.95939515e-04,  4.45291424e-04,  1.27887921e-04,\n",
+       "         -3.99434643e-16, -3.94461411e-06, -1.07177226e-16,  3.88521213e-02,\n",
+       "          1.01996847e-15, -2.79810123e-05, -1.43334389e-17, -5.33312617e-16,\n",
+       "         -1.11898806e-14, -2.03558570e-03, -1.13213677e-03, -4.52605164e-04,\n",
+       "         -2.72282875e-16]),\n",
+       "  array([ 2.88778120e-06, -3.69149849e-17,  1.03874605e+00,  1.22460041e-16,\n",
+       "          3.51871430e-06,  8.38201364e-19,  1.00000000e+00,  9.41602370e-16,\n",
+       "          3.72791575e-15,  8.93937444e-04,  4.44178229e-04,  1.27443152e-04,\n",
+       "         -3.99689499e-16, -3.87295068e-06, -1.09596007e-16,  1.21084730e-02,\n",
+       "          9.42717972e-16, -2.91663729e-05, -2.33940596e-17, -5.06062248e-16,\n",
+       "         -1.09691071e-14, -2.00207145e-03, -1.11319456e-03, -4.44769732e-04,\n",
+       "         -2.54855749e-16]),\n",
+       "  array([ 2.88388380e-06, -3.70237269e-17,  1.03873238e+00,  1.22871117e-16,\n",
+       "          3.50309066e-06,  8.21403578e-19,  1.00000000e+00,  9.41126425e-16,\n",
+       "          3.71719082e-15,  8.91969071e-04,  4.43084019e-04,  1.27006205e-04,\n",
+       "         -3.99923866e-16, -3.80139791e-06, -1.12096431e-16, -1.36729730e-02,\n",
+       "          8.22151172e-16, -3.12472811e-05, -3.35888526e-17, -4.75944940e-16,\n",
+       "         -1.07249275e-14, -1.96837274e-03, -1.09421014e-03, -4.36947012e-04,\n",
+       "         -2.34367758e-16]),\n",
+       "  array([ 2.87988472e-06, -3.71289266e-17,  1.03869387e+00,  1.23198190e-16,\n",
+       "          3.48593233e-06,  7.99053692e-19,  1.00000000e+00,  9.40683662e-16,\n",
+       "          3.70673355e-15,  8.90034544e-04,  4.42008796e-04,  1.26577037e-04,\n",
+       "         -4.00134911e-16, -3.72992840e-06, -1.14675972e-16, -3.85104256e-02,\n",
+       "          6.54147503e-16, -3.43166725e-05, -4.46932636e-17, -4.42763386e-16,\n",
+       "         -1.04572716e-14, -1.93452734e-03, -1.07522276e-03, -4.29167483e-04,\n",
+       "         -2.11044710e-16]),\n",
+       "  array([ 2.87579209e-06, -3.72308594e-17,  1.03863144e+00,  1.23416232e-16,\n",
+       "          3.46671518e-06,  7.70828008e-19,  1.00000000e+00,  9.40277274e-16,\n",
+       "          3.69656694e-15,  8.88133969e-04,  4.40952529e-04,  1.26155581e-04,\n",
+       "         -4.00320019e-16, -3.65862558e-06, -1.17326961e-16, -6.24220439e-02,\n",
+       "          4.36084354e-16, -3.84342908e-05, -5.64451116e-17, -4.06387259e-16,\n",
+       "         -1.01666127e-14, -1.90057502e-03, -1.05626765e-03, -4.21456488e-04,\n",
+       "         -1.85107884e-16]),\n",
+       "  array([ 2.87161397e-06, -3.73298027e-17,  1.03854602e+00,  1.23499748e-16,\n",
+       "          3.44490432e-06,  7.36551339e-19,  1.00000000e+00,  9.39910502e-16,\n",
+       "          3.68671292e-15,  8.86267412e-04,  4.39915154e-04,  1.25741748e-04,\n",
+       "         -4.00476790e-16, -3.58769129e-06, -1.20036295e-16, -8.54259267e-02,\n",
+       "          1.67032368e-16, -4.36217334e-05, -6.85473759e-17, -3.66771979e-16,\n",
+       "         -9.85401601e-15, -1.86655713e-03, -1.03737494e-03, -4.13833035e-04,\n",
+       "         -1.56771416e-16]),\n",
+       "  array([ 2.86735828e-06, -3.74260340e-17,  1.03843848e+00,  1.23423688e-16,\n",
+       "          3.41997470e-06,  6.96208970e-19,  1.00000000e+00,  9.39586516e-16,\n",
+       "          3.67719176e-15,  8.84434895e-04,  4.38896585e-04,  1.25335439e-04,\n",
+       "         -4.00603036e-16, -3.51744624e-06, -1.22785453e-16, -1.07540103e-01,\n",
+       "         -1.52121155e-16, -4.98592254e-05, -8.06791049e-17, -3.23986339e-16,\n",
+       "         -9.52116804e-15, -1.83251629e-03, -1.01856885e-03, -4.06309054e-04,\n",
+       "         -1.26245211e-16]),\n",
+       "  array([ 2.86303276e-06, -3.75198286e-17,  1.03830970e+00,  1.23164374e-16,\n",
+       "          3.39143254e-06,  6.49954265e-19,  1.00000000e+00,  9.39308282e-16,\n",
+       "          3.66802137e-15,  8.82636399e-04,  4.37896718e-04,  1.24936549e-04,\n",
+       "         -4.00696778e-16, -3.44832322e-06, -1.25550827e-16, -1.28782522e-01,\n",
+       "         -5.18626826e-16, -5.70843319e-05, -9.25041376e-17, -2.78233818e-16,\n",
+       "         -9.17038148e-15, -1.79849606e-03, -9.99867427e-04, -3.98889158e-04,\n",
+       "         -9.37426967e-17]),\n",
+       "  array([ 2.85864496e-06, -3.76114570e-17,  1.03816053e+00,  1.22700420e-16,\n",
+       "          3.35883618e-06,  5.98107876e-19,  1.00000000e+00,  9.39078404e-16,\n",
+       "          3.65921680e-15,  8.80871859e-04,  4.36915435e-04,  1.24544978e-04,\n",
+       "         -4.00756271e-16, -3.38085325e-06, -1.28304348e-16, -1.49171046e-01,\n",
+       "         -9.27908189e-16, -6.51927133e-05, -1.03687895e-16, -2.29878323e-16,\n",
+       "         -8.80457361e-15, -1.76454066e-03, -9.81282750e-04, -3.91570923e-04,\n",
+       "         -5.94922158e-17]),\n",
+       "  array([ 2.85420214e-06, -3.77011824e-17,  1.03799180e+00,  1.22013582e-16,\n",
+       "          3.32181573e-06,  5.41147478e-19,  1.00000000e+00,  9.38898939e-16,\n",
+       "          3.65078958e-15,  8.79141164e-04,  4.35952613e-04,  1.24160633e-04,\n",
+       "         -4.00780021e-16, -3.31564536e-06, -1.31014379e-16, -1.68723439e-01,\n",
+       "         -1.37367597e-15, -7.40409100e-05, -1.13916326e-16, -1.79464556e-16,\n",
+       "         -8.42721691e-15, -1.73069475e-03, -9.62821531e-04, -3.84345650e-04,\n",
+       "         -2.37504970e-17]),\n",
+       "  array([ 2.84971120e-06, -3.77892578e-17,  1.03780434e+00,  1.21089523e-16,\n",
+       "          3.28009021e-06,  4.79690050e-19,  1.00000000e+00,  9.38771216e-16,\n",
+       "          3.64274732e-15,  8.77444161e-04,  4.35008127e-04,  1.23783433e-04,\n",
+       "         -4.00766837e-16, -3.25336114e-06, -1.33646836e-16, -1.87457364e-01,\n",
+       "         -1.84811721e-15, -8.34510384e-05, -1.22910812e-16, -1.27723174e-16,\n",
+       "         -8.04226400e-15, -1.69700317e-03, -9.44486129e-04, -3.77199567e-04,\n",
+       "          1.31835810e-17]),\n",
+       "  array([ 2.84517869e-06, -3.78759235e-17,  1.03759895e+00,  1.19918447e-16,\n",
+       "          3.23348161e-06,  4.14465487e-19,  1.00000000e+00,  9.38695648e-16,\n",
+       "          3.63509327e-15,  8.75780650e-04,  4.34081851e-04,  1.23413318e-04,\n",
+       "         -4.00715881e-16, -3.19468549e-06, -1.36166461e-16, -2.05390369e-01,\n",
+       "         -2.34215199e-15, -9.32171867e-05, -1.30445520e-16, -7.55678015e-17,\n",
+       "         -7.65405067e-15, -1.66351084e-03, -9.26275860e-04, -3.70115365e-04,\n",
+       "          5.09566295e-17]),\n",
+       "  array([ 2.84061071e-06, -3.79614051e-17,  1.03737641e+00,  1.18495574e-16,\n",
+       "          3.18192504e-06,  3.46288531e-19,  1.00000000e+00,  9.38671586e-16,\n",
+       "          3.62782609e-15,  8.74150387e-04,  4.33173663e-04,  1.23050244e-04,\n",
+       "         -4.00626729e-16, -3.14029521e-06, -1.38538205e-16, -2.22539886e-01,\n",
+       "         -2.84574530e-15, -1.03113154e-04, -1.36350749e-16, -2.40624119e-17,\n",
+       "         -7.26718076e-15, -1.63026246e-03, -9.08188493e-04, -3.63073956e-04,\n",
+       "          8.91514245e-17]),\n",
+       "  array([ 2.83601290e-06, -3.80459111e-17,  1.03713749e+00,  1.16821442e-16,\n",
+       "          3.12547442e-06,  2.76015856e-19,  1.00000000e+00,  9.38697174e-16,\n",
+       "          3.62093969e-15,  8.72553085e-04,  4.32283441e-04,  1.22694188e-04,\n",
+       "         -4.00499447e-16, -3.09082721e-06, -1.40728625e-16, -2.38923220e-01,\n",
+       "         -3.34826428e-15, -1.12901239e-04, -1.40542626e-16,  2.55877939e-17,\n",
+       "         -6.88640215e-15, -1.59730249e-03, -8.90221855e-04, -3.56056344e-04,\n",
+       "          1.27281942e-16]),\n",
+       "  array([ 2.83139040e-06, -3.81296313e-17,  1.03688293e+00,  1.14902010e-16,\n",
+       "          3.06430363e-06,  2.04508883e-19,  1.00000000e+00,  9.38769280e-16,\n",
+       "          3.61442321e-15,  8.70988410e-04,  4.31411066e-04,  1.22345142e-04,\n",
+       "         -4.00334654e-16, -3.04684813e-06, -1.42707244e-16, -2.54557544e-01,\n",
+       "         -3.83886205e-15, -1.22341566e-04, -1.43011651e-16,  7.21064260e-17,\n",
+       "         -6.51647699e-15, -1.56467486e-03, -8.72375391e-04, -3.49045474e-04,\n",
+       "          1.64793532e-16]),\n",
+       "  array([ 2.82674783e-06, -3.82127364e-17,  1.03661347e+00,  1.12748574e-16,\n",
+       "          2.99870288e-06,  1.32608926e-19,  1.00000000e+00,  9.38883518e-16,\n",
+       "          3.60826116e-15,  8.69455987e-04,  4.30556414e-04,  1.22003114e-04,\n",
+       "         -4.00133585e-16, -3.00882708e-06, -1.44447793e-16, -2.69459895e-01,\n",
+       "         -4.30687214e-15, -1.31201504e-04, -1.43798037e-16,  1.14237463e-16,\n",
+       "         -6.16205354e-15, -1.53242292e-03, -8.54651593e-04, -3.42027923e-04,\n",
+       "          2.01068879e-16]),\n",
+       "  array([ 2.82208932e-06, -3.82953766e-17,  1.03632983e+00,  1.10377476e-16,\n",
+       "          2.92907052e-06,  6.10944445e-20,  1.00000000e+00,  9.39034278e-16,\n",
+       "          3.60243361e-15,  8.67955398e-04,  4.29719357e-04,  1.21668119e-04,\n",
+       "         -3.99898146e-16, -2.97711300e-06, -1.45929270e-16, -2.83647164e-01,\n",
+       "         -4.74219530e-15, -1.39264720e-04, -1.43027481e-16,  1.50760285e-16,\n",
+       "         -5.82754405e-15, -1.50058912e-03, -8.37057171e-04, -3.34995333e-04,\n",
+       "          2.35439015e-16]),\n",
+       "  array([ 2.81741848e-06, -3.83776821e-17,  1.03603269e+00,  1.07809646e-16,\n",
+       "          2.85590082e-06, -9.33923565e-21,  1.00000000e+00,  9.39214881e-16,\n",
+       "          3.59691660e-15,  8.66486183e-04,  4.28899753e-04,  1.21340173e-04,\n",
+       "         -3.99630946e-16, -2.95191768e-06, -1.47136770e-16, -2.97136095e-01,\n",
+       "         -5.13566002e-15, -1.46339408e-04, -1.40866250e-16,  1.80602976e-16,\n",
+       "         -5.51701277e-15, -1.46921483e-03, -8.19603898e-04, -3.27945495e-04,\n",
+       "          2.67200525e-16]),\n",
+       "  array([ 2.81273844e-06, -3.84597636e-17,  1.03572275e+00,  1.05069976e-16,\n",
+       "          2.77976818e-06, -7.80939920e-20,  1.00000000e+00,  9.39417786e-16,\n",
+       "          3.59168252e-15,  8.65047843e-04,  4.28097444e-04,  1.21019290e-04,\n",
+       "         -3.99335309e-16, -2.93330550e-06, -1.48062047e-16, -3.09943278e-01,\n",
+       "         -5.47933971e-15, -1.52265273e-04, -1.37508745e-16,  2.02904920e-16,\n",
+       "         -5.23407602e-15, -1.43833988e-03, -8.02309033e-04, -3.20882987e-04,\n",
+       "          2.95636545e-16]),\n",
+       "  array([ 2.80805187e-06, -3.85417131e-17,  1.03540066e+00,  1.02186570e-16,\n",
+       "          2.70130869e-06, -1.44673056e-19,  1.00000000e+00,  9.39634862e-16,\n",
+       "          3.58670071e-15,  8.63639841e-04,  4.27312249e-04,  1.20705471e-04,\n",
+       "         -3.99015268e-16, -2.92119007e-06, -1.48703776e-16, -3.22085142e-01,\n",
+       "         -5.76681161e-15, -1.56918975e-04, -1.33157670e-16,  2.17075784e-16,\n",
+       "         -4.98181650e-15, -1.40800218e-03, -7.85195312e-04, -3.13819362e-04,\n",
+       "          3.20041166e-16]),\n",
+       "  array([ 2.80336106e-06, -3.86236059e-17,  1.03506708e+00,  9.91898970e-17,\n",
+       "          2.62119982e-06, -2.08676588e-19,  1.00000000e+00,  9.39857697e-16,\n",
+       "          3.58193799e-15,  8.62261604e-04,  4.26543958e-04,  1.20398698e-04,\n",
+       "         -3.98675522e-16, -2.91533794e-06, -1.49067513e-16, -3.33577952e-01,\n",
+       "         -5.99334583e-15, -1.60217756e-04, -1.28006883e-16,  2.22835060e-16,\n",
+       "         -4.76271245e-15, -1.37823706e-03, -7.68290475e-04, -3.06772845e-04,\n",
+       "          3.39745724e-16]),\n",
+       "  array([ 2.79866793e-06, -3.87055019e-17,  1.03472265e+00,  9.61118881e-17,\n",
+       "          2.54013923e-06, -2.69788690e-19,  1.00000000e+00,  9.40077931e-16,\n",
+       "          3.57735941e-15,  8.60912527e-04,  4.25792332e-04,  1.20098931e-04,\n",
+       "         -3.98321377e-16, -2.91537878e-06, -1.49165373e-16, -3.44437807e-01,\n",
+       "         -6.15601731e-15, -1.62121162e-04, -1.22224259e-16,  2.20234149e-16,\n",
+       "         -4.57858273e-15, -1.34907656e-03, -7.51626363e-04, -2.99767578e-04,\n",
+       "          3.54145532e-16]),\n",
+       "  array([ 2.79397407e-06, -3.87874483e-17,  1.03436797e+00,  9.29850190e-17,\n",
+       "          2.45882382e-06, -3.27760057e-19,  1.00000000e+00,  9.40287581e-16,\n",
+       "          3.57292886e-15,  8.59591979e-04,  4.25057094e-04,  1.19806098e-04,\n",
+       "         -3.97958651e-16, -2.92082140e-06, -1.49015433e-16, -3.54680630e-01,\n",
+       "         -6.25373786e-15, -1.62630827e-04, -1.15942989e-16,  2.09650430e-16,\n",
+       "         -4.43054816e-15, -1.32054871e-03, -7.35237644e-04, -2.92832475e-04,\n",
+       "          3.62725358e-16]),\n",
+       "  array([ 2.78928086e-06, -3.88694815e-17,  1.03400364e+00,  8.98414134e-17,\n",
+       "          2.37792960e-06, -3.82387679e-19,  1.00000000e+00,  9.40479344e-16,\n",
+       "          3.56860985e-15,  8.58299302e-04,  4.24337934e-04,  1.19520098e-04,\n",
+       "         -3.97593569e-16, -2.93107434e-06, -1.48640925e-16, -3.64322168e-01,\n",
+       "         -6.28721083e-15, -1.61788436e-04, -1.09255659e-16,  1.91762220e-16,\n",
+       "         -4.31901008e-15, -1.29267659e-03, -7.19160251e-04, -2.85999739e-04,\n",
+       "          3.65082322e-16]),\n",
+       "  array([ 2.78458946e-06, -3.89516296e-17,  1.03363027e+00,  8.67120059e-17,\n",
+       "          2.29809357e-06, -4.33494682e-19,  1.00000000e+00,  9.40646847e-16,\n",
+       "          3.56436621e-15,  8.57033825e-04,  4.23634504e-04,  1.19240795e-04,\n",
+       "         -3.97232624e-16, -2.94546991e-06, -1.48069247e-16, -3.73377988e-01,\n",
+       "         -6.25881481e-15, -1.59672070e-04, -1.02214543e-16,  1.67503252e-16,\n",
+       "         -4.24364676e-15, -1.26547759e-03, -7.03429629e-04, -2.79303186e-04,\n",
+       "          3.60944773e-16]),\n",
+       "  array([ 2.77990092e-06, -3.90339147e-17,  1.03324840e+00,  8.36257922e-17,\n",
+       "          2.21989795e-06, -4.80912787e-19,  1.00000000e+00,  9.40784849e-16,\n",
+       "          3.56016278e-15,  8.55794862e-04,  4.22946425e-04,  1.18968019e-04,\n",
+       "         -3.96882438e-16, -2.96329004e-06, -1.47330871e-16, -3.81863472e-01,\n",
+       "         -6.17242700e-15, -1.56391239e-04, -9.48368346e-17,  1.38002267e-16,\n",
+       "         -4.20342828e-15, -1.23896259e-03, -6.88078936e-04, -2.72776446e-04,\n",
+       "          3.50186099e-16]),\n",
+       "  array([ 2.77521616e-06, -3.91163551e-17,  1.03285861e+00,  8.06091923e-17,\n",
+       "          2.14385748e-06, -5.24469246e-19,  1.00000000e+00,  9.40889363e-16,\n",
+       "          3.55596613e-15,  8.54581727e-04,  4.22273288e-04,  1.18701568e-04,\n",
+       "         -3.96549605e-16, -2.98379271e-06, -1.46458191e-16, -3.89793813e-01,\n",
+       "         -6.03319960e-15, -1.52080931e-04, -8.71135934e-17,  1.04513648e-16,\n",
+       "         -4.19665029e-15, -1.21313538e-03, -6.73137300e-04, -2.66451196e-04,\n",
+       "          3.32832691e-16]),\n",
+       "  array([ 2.77053608e-06, -3.91989674e-17,  1.03246142e+00,  7.76855402e-17,\n",
+       "          2.07040994e-06, -5.63979472e-19,  1.00000000e+00,  9.40957708e-16,\n",
+       "          3.55174514e-15,  8.53393734e-04,  4.21614660e-04,  1.18441212e-04,\n",
+       "         -3.96240540e-16, -3.00623742e-06, -1.45484385e-16, -3.97184014e-01,\n",
+       "         -5.84730391e-15, -1.46895085e-04, -7.90211454e-17,  6.83451208e-17,\n",
+       "         -4.22098626e-15, -1.18799225e-03, -6.58628252e-04, -2.60355515e-04,\n",
+       "          3.09065674e-16]),\n",
+       "  array([ 2.76586157e-06, -3.92817679e-17,  1.03205738e+00,  7.48747114e-17,\n",
+       "          1.99991002e-06, -5.99245765e-19,  1.00000000e+00,  9.40988496e-16,\n",
+       "          3.54747158e-15,  8.52230213e-04,  4.20970091e-04,  1.18186700e-04,\n",
+       "         -3.95961323e-16, -3.02990872e-06, -1.44442326e-16, -4.04048881e-01,\n",
+       "         -5.62165752e-15, -1.40999841e-04, -7.05332729e-17,  3.07885374e-17,\n",
+       "         -4.27355714e-15, -1.16352177e-03, -6.44568455e-04, -2.54512469e-04,\n",
+       "          2.79216371e-16]),\n",
+       "  array([ 2.76119350e-06, -3.93647745e-17,  1.03164697e+00,  7.21928866e-17,\n",
+       "          1.93262654e-06, -6.30061803e-19,  1.00000000e+00,  9.40981555e-16,\n",
+       "          3.54312057e-15,  8.51090508e-04,  4.20339124e-04,  1.17937761e-04,\n",
+       "         -3.95717567e-16, -3.05413668e-06, -1.43363600e-16, -4.10403027e-01,\n",
+       "         -5.36364926e-15, -1.34566950e-04, -6.16327268e-17, -6.94124458e-18,\n",
+       "         -4.35101638e-15, -1.13970498e-03, -6.30966776e-04, -2.48938998e-04,\n",
+       "          2.43755867e-16]),\n",
+       "  array([ 2.75653283e-06, -3.94480075e-17,  1.03123071e+00,  6.96524492e-17,\n",
+       "          1.86874273e-06, -6.56221862e-19,  1.00000000e+00,  9.40937800e-16,\n",
+       "          3.53867092e-15,  8.49973992e-04,  4.19721301e-04,  1.17694115e-04,\n",
+       "         -3.95514288e-16, -3.07831377e-06, -1.42277662e-16, -4.16260862e-01,\n",
+       "         -5.08087462e-15, -1.27767624e-04, -5.23207130e-17, -4.37555307e-17,\n",
+       "         -4.44964744e-15, -1.11651575e-03, -6.17823778e-04, -2.43645171e-04,\n",
+       "          2.03279344e-16]),\n",
+       "  array([ 2.75188052e-06, -3.95314905e-17,  1.03080907e+00,  6.72620029e-17,\n",
+       "          1.80835919e-06, -6.77533550e-19,  1.00000000e+00,  9.40859072e-16,\n",
+       "          3.53410545e-15,  8.48880070e-04,  4.19116169e-04,  1.17455482e-04,\n",
+       "         -3.95355802e-16, -3.10190761e-06, -1.41211141e-16, -4.21636595e-01,\n",
+       "         -4.78089242e-15, -1.20767095e-04, -4.26238980e-17, -7.87273550e-17,\n",
+       "         -4.56546990e-15, -1.09392147e-03, -6.05131628e-04, -2.38633813e-04,\n",
+       "          1.58486177e-16]),\n",
+       "  array([ 2.74723761e-06, -3.96152509e-17,  1.03038253e+00,  6.50264974e-17,\n",
+       "          1.75149917e-06, -6.93832275e-19,  1.00000000e+00,  9.40747960e-16,\n",
+       "          3.52941110e-15,  8.47808186e-04,  4.18523295e-04,  1.17221581e-04,\n",
+       "         -3.95245645e-16, -3.12446966e-06, -1.40187325e-16, -4.26544231e-01,\n",
+       "         -4.47101087e-15, -1.13720034e-04, -3.25978865e-17, -1.11112041e-16,\n",
+       "         -4.69435022e-15, -1.07188402e-03, -5.92874418e-04, -2.33900518e-04,\n",
+       "          1.10156845e-16]),\n",
+       "  array([ 2.74260520e-06, -3.96993202e-17,  1.02995153e+00,  6.29474434e-17,\n",
+       "          1.69811569e-06, -7.04995929e-19,  1.00000000e+00,  9.40607606e-16,\n",
+       "          3.52457899e-15,  8.46757826e-04,  4.17942266e-04,  1.16992147e-04,\n",
+       "         -3.95186517e-16, -3.14563967e-06, -1.39225810e-16, -4.30997569e-01,\n",
+       "         -4.15810794e-15, -1.06766953e-04, -2.23276489e-17, -1.40354139e-16,\n",
+       "         -4.83211226e-15, -1.05036084e-03, -5.81028858e-04, -2.29434019e-04,\n",
+       "          5.91279844e-17]),\n",
+       "  array([ 2.73798441e-06, -3.97837341e-17,  1.02951652e+00,  6.10231989e-17,\n",
+       "          1.64809989e-06, -7.10958333e-19,  1.00000000e+00,  9.40441524e-16,\n",
+       "          3.51960434e-15,  8.45728519e-04,  4.17372700e-04,  1.16766930e-04,\n",
+       "         -3.95180250e-16, -3.16514662e-06, -1.38342311e-16, -4.35010201e-01,\n",
+       "         -3.84848899e-15, -1.00031594e-04, -1.19250453e-17, -1.66082338e-16,\n",
+       "         -4.97464343e-15, -1.02930627e-03, -5.69565277e-04, -2.25216863e-04,\n",
+       "          6.26677215e-18]),\n",
+       "  array([ 2.73337644e-06, -3.98685317e-17,  1.02907793e+00,  5.92493080e-17,\n",
+       "          1.60129024e-06, -7.11720240e-19,  1.00000000e+00,  9.40253429e-16,\n",
+       "          3.51448635e-15,  8.44719846e-04,  4.16814252e-04,  1.16545704e-04,\n",
+       "         -3.95227804e-16, -3.18280617e-06, -1.37548631e-16, -4.38595510e-01,\n",
+       "         -3.54778166e-15, -9.36193036e-05, -1.52394890e-18, -1.88094764e-16,\n",
+       "         -5.11799231e-15, -1.00867286e-03, -5.58448862e-04, -2.21226321e-04,\n",
+       "         -4.75541716e-17]),\n",
+       "  array([ 2.72878248e-06, -3.99537560e-17,  1.02863616e+00,  5.76188747e-17,\n",
+       "          1.55748209e-06, -7.07357081e-19,  1.00000000e+00,  9.40047091e-16,\n",
+       "          3.50922790e-15,  8.43731434e-04,  4.16266611e-04,  1.16328268e-04,\n",
+       "         -3.95329285e-16, -3.19851557e-06, -1.36852748e-16, -4.41766668e-01,\n",
+       "         -3.26086665e-15, -8.76162986e-05,  8.72628688e-18, -2.06337554e-16,\n",
+       "         -5.25845450e-15, -9.88412736e-04, -5.47641041e-04, -2.17435490e-04,\n",
+       "         -1.01480331e-16]),\n",
+       "  array([ 2.72420377e-06, -4.00394526e-17,  1.02819162e+00,  5.61229540e-17,\n",
+       "          1.51643724e-06, -6.98022985e-19,  1.00000000e+00,  9.39826212e-16,\n",
+       "          3.50383525e-15,  8.42762955e-04,  4.15729510e-04,  1.16114454e-04,\n",
+       "         -3.95483981e-16, -3.21224638e-06, -1.36259021e-16, -4.44536636e-01,\n",
+       "         -2.99184123e-15, -8.20897126e-05,  1.86682623e-17, -2.20879507e-16,\n",
+       "         -5.39264410e-15, -9.68478904e-04, -5.37100940e-04, -2.13814477e-04,\n",
+       "         -1.54696448e-16]),\n",
+       "  array([ 2.71964151e-06, -4.01256695e-17,  1.02774471e+00,  5.47509483e-17,\n",
+       "          1.47789309e-06, -6.83950984e-19,  1.00000000e+00,  9.39594327e-16,\n",
+       "          3.49831770e-15,  8.41814128e-04,  4.15202723e-04,  1.15904122e-04,\n",
+       "         -3.95690426e-16, -3.22403576e-06, -1.35768475e-16, -4.46918164e-01,\n",
+       "         -2.74401142e-15, -7.70883001e-05,  2.81441686e-17, -2.31885360e-16,\n",
+       "         -5.51754938e-15, -9.48826431e-04, -5.26786825e-04, -2.10331621e-04,\n",
+       "         -2.06444646e-16]),\n",
+       "  array([ 2.71509692e-06, -4.02124562e-17,  1.02729578e+00,  5.34909940e-17,\n",
+       "          1.44157126e-06, -6.65449578e-19,  1.00000000e+00,  9.39354737e-16,\n",
+       "          3.49268713e-15,  8.40884715e-04,  4.14686065e-04,  1.15697168e-04,\n",
+       "         -3.95946465e-16, -3.23397683e-06, -1.35379151e-16, -4.48923788e-01,\n",
+       "         -2.51990854e-15, -7.26436473e-05,  3.70030651e-17, -2.39589709e-16,\n",
+       "         -5.63057188e-15, -9.29413494e-04, -5.16657458e-04, -2.06954683e-04,\n",
+       "         -2.56039111e-16]),\n",
+       "  array([ 2.71057116e-06, -4.02998633e-17,  1.02684522e+00,  5.23303315e-17,\n",
+       "          1.40718539e-06, -6.42896119e-19,  1.00000000e+00,  9.39110464e-16,\n",
+       "          3.48695758e-15,  8.39974513e-04,  4.14179392e-04,  1.15493516e-04,\n",
+       "         -3.96249342e-16, -3.24220869e-06, -1.35086496e-16, -4.50565833e-01,\n",
+       "         -2.32132512e-15, -6.87717527e-05,  4.51072495e-17, -2.44273262e-16,\n",
+       "         -5.72954944e-15, -9.10202224e-04, -5.06673324e-04, -2.03651937e-04,\n",
+       "         -3.02877144e-16]),\n",
+       "  array([ 2.70606535e-06, -4.03879411e-17,  1.02639336e+00,  5.12556486e-17,\n",
+       "          1.37444796e-06, -6.16727564e-19,  1.00000000e+00,  9.38864221e-16,\n",
+       "          3.48114482e-15,  8.39083353e-04,  4.13682594e-04,  1.15293122e-04,\n",
+       "         -3.96595789e-16, -3.24890642e-06, -1.34883778e-16, -4.51856407e-01,\n",
+       "         -2.14936585e-15, -6.54748462e-05,  5.23375127e-17, -2.46242270e-16,\n",
+       "         -5.81276382e-15, -8.91159369e-04, -4.96797678e-04, -2.00393142e-04,\n",
+       "         -3.46446577e-16]),\n",
+       "  array([ 2.70158057e-06, -4.04767395e-17,  1.02594055e+00,  5.02533940e-17,\n",
+       "          1.34307630e-06, -5.87429304e-19,  1.00000000e+00,  9.38618409e-16,\n",
+       "          3.47526588e-15,  8.38211096e-04,  4.13195597e-04,  1.15095972e-04,\n",
+       "         -3.96982118e-16, -3.25427166e-06, -1.34762498e-16, -4.52807409e-01,\n",
+       "         -2.00450916e-15, -6.27433299e-05,  5.85969794e-17, -2.45811830e-16,\n",
+       "         -5.87893492e-15, -8.72256736e-04, -4.86997381e-04, -1.97150349e-04,\n",
+       "         -3.86329723e-16]),\n",
+       "  array([ 2.69711779e-06, -4.05663072e-17,  1.02548712e+00,  4.93100562e-17,\n",
+       "          1.31279743e-06, -5.55522727e-19,  1.00000000e+00,  9.38375117e-16,\n",
+       "          3.46933868e-15,  8.37357625e-04,  4.12718353e-04,  1.14902074e-04,\n",
+       "         -3.97404323e-16, -3.25852367e-06, -1.34712805e-16, -4.53430520e-01,\n",
+       "         -1.88667568e-15, -6.05577432e-05,  6.38136629e-17, -2.43292931e-16,\n",
+       "         -5.92720316e-15, -8.53471442e-04, -4.77243527e-04, -1.93898536e-04,\n",
+       "         -4.22204145e-16]),\n",
+       "  array([ 2.69267793e-06, -4.06566907e-17,  1.02503338e+00,  4.84124061e-17,\n",
+       "          1.28335209e-06, -5.21552220e-19,  1.00000000e+00,  9.38136133e-16,\n",
+       "          3.46338158e-15,  8.36522839e-04,  4.12250842e-04,  1.14711458e-04,\n",
+       "         -3.97858163e-16, -3.26189148e-06, -1.34723880e-16, -4.53737212e-01,\n",
+       "         -1.79530030e-15, -5.88906746e-05,  6.79415628e-17, -2.38983290e-16,\n",
+       "         -5.95710258e-15, -8.34785971e-04, -4.67511854e-04, -1.90616068e-04,\n",
+       "         -4.53840658e-16]),\n",
+       "  array([ 2.68826180e-06, -4.07479342e-17,  1.02457965e+00,  4.75477036e-17,\n",
+       "          1.25449781e-06, -4.86072183e-19,  1.00000000e+00,  9.37902972e-16,\n",
+       "          3.45741305e-15,  8.35706651e-04,  4.11793059e-04,  1.14524173e-04,\n",
+       "         -3.98339262e-16, -3.26460683e-06, -1.34784298e-16, -4.53738739e-01,\n",
+       "         -1.72940507e-15, -5.77085609e-05,  7.09606469e-17, -2.33161303e-16,\n",
+       "         -5.96852676e-15, -8.16188072e-04, -4.57782953e-04, -1.87284976e-04,\n",
+       "         -4.81098978e-16]),\n",
+       "  array([ 2.68387012e-06, -4.08400786e-17,  1.02412620e+00,  4.67038682e-17,\n",
+       "          1.22601114e-06, -4.49634614e-19,  1.00000000e+00,  9.37676889e-16,\n",
+       "          3.45145136e-15,  8.34908980e-04,  4.11345016e-04,  1.14340281e-04,\n",
+       "         -3.98843184e-16, -3.26689830e-06, -1.34882354e-16, -4.53446145e-01,\n",
+       "         -1.68767081e-15, -5.69733341e-05,  7.28757308e-17, -2.26082752e-16,\n",
+       "         -5.96168973e-15, -7.97670516e-04, -4.48042289e-04, -1.83891083e-04,\n",
+       "         -5.03921507e-16]),\n",
+       "  array([ 2.67950352e-06, -4.09331611e-17,  1.02367333e+00,  4.58696154e-17,\n",
+       "          1.19768920e-06, -4.12777586e-19,  1.00000000e+00,  9.37458910e-16,\n",
+       "          3.44551428e-15,  8.34129750e-04,  4.10906736e-04,  1.14159857e-04,\n",
+       "         -3.99365509e-16, -3.26898640e-06, -1.35006354e-16, -4.52870263e-01,\n",
+       "         -1.66850567e-15, -5.66438901e-05,  7.37146554e-17, -2.17979425e-16,\n",
+       "         -5.93708408e-15, -7.79230730e-04, -4.38280067e-04, -1.80423985e-04,\n",
+       "         -5.22325733e-16]),\n",
+       "  array([ 2.67516248e-06, -4.10272153e-17,  1.02322131e+00,  4.50345607e-17,\n",
+       "          1.16935051e-06, -3.76015112e-19,  1.00000000e+00,  9.37249850e-16,\n",
+       "          3.43961884e-15,  8.33368879e-04,  4.10478245e-04,  1.13982981e-04,\n",
+       "         -3.99901905e-16, -3.27107968e-06, -1.35144859e-16, -4.52021711e-01,\n",
+       "         -1.67010945e-15, -5.66773696e-05,  7.35255473e-17, -2.09059638e-16,\n",
+       "         -5.89543788e-15, -7.60870362e-04, -4.28490970e-04, -1.76876911e-04,\n",
+       "         -5.36395662e-16]),\n",
+       "  array([ 2.67084742e-06, -4.11222702e-17,  1.02277040e+00,  4.41892944e-17,\n",
+       "          1.14083539e-06, -3.39828278e-19,  1.00000000e+00,  9.37050341e-16,\n",
+       "          3.43378117e-15,  8.32626285e-04,  4.10059572e-04,  1.13809734e-04,\n",
+       "         -4.00448178e-16, -3.27337172e-06, -1.35286899e-16, -4.50910899e-01,\n",
+       "         -1.69053268e-15, -5.70302477e-05,  7.23742594e-17, -1.99508994e-16,\n",
+       "         -5.83767208e-15, -7.42594773e-04, -4.18673791e-04, -1.73246492e-04,\n",
+       "         -5.46272722e-16]),\n",
+       "  array([ 2.66655862e-06, -4.12183503e-17,  1.02232085e+00,  4.33254294e-17,\n",
+       "          1.11200577e-06, -3.04658205e-19,  1.00000000e+00,  9.36860848e-16,\n",
+       "          3.42801631e-15,  8.31901872e-04,  4.09650741e-04,  1.13640202e-04,\n",
+       "         -4.01000324e-16, -3.27603903e-06, -1.35422138e-16, -4.49548024e-01,\n",
+       "         -1.72773017e-15, -5.76592406e-05,  7.03407223e-17, -1.89492815e-16,\n",
+       "         -5.76485944e-15, -7.24412502e-04, -4.08830998e-04, -1.69532454e-04,\n",
+       "         -5.52146476e-16]),\n",
+       "  array([ 2.66229626e-06, -4.13154752e-17,  1.02187291e+00,  4.24356252e-17,\n",
+       "          1.08274475e-06, -2.70899958e-19,  1.00000000e+00,  9.36681692e-16,\n",
+       "          3.42233812e-15,  8.31195537e-04,  4.09251772e-04,  1.13474464e-04,\n",
+       "         -4.01554570e-16, -3.27923963e-06, -1.35541012e-16, -4.47943077e-01,\n",
+       "         -1.77960841e-15, -5.85220418e-05,  6.75170506e-17, -1.79156481e-16,\n",
+       "         -5.67818614e-15, -7.06334724e-04, -3.98968246e-04, -1.65737259e-04,\n",
+       "         -5.54245450e-16]),\n",
+       "  array([ 2.65806040e-06, -4.14136598e-17,  1.02142680e+00,  4.15135917e-17,\n",
+       "          1.05295580e-06, -2.38898938e-19,  1.00000000e+00,  9.36513062e-16,\n",
+       "          3.41675921e-15,  8.30507163e-04,  4.08862678e-04,  1.13312599e-04,\n",
+       "         -4.02107398e-16, -3.28311228e-06, -1.35634824e-16, -4.46105839e-01,\n",
+       "         -1.84406708e-15, -5.95779020e-05,  6.40025731e-17, -1.68629769e-16,\n",
+       "         -5.57891642e-15, -6.88374700e-04, -3.89093877e-04, -1.61865726e-04,\n",
+       "         -5.52828369e-16]),\n",
+       "  array([ 2.65385100e-06, -4.15129138e-17,  1.02098275e+00,  4.05540744e-17,\n",
+       "          1.02256176e-06, -2.08948795e-19,  1.00000000e+00,  9.36355033e-16,\n",
+       "          3.41129084e-15,  8.29836615e-04,  4.08483460e-04,  1.13154674e-04,\n",
+       "         -4.02655574e-16, -3.28777627e-06, -1.35695814e-16, -4.44045884e-01,\n",
+       "         -1.91903452e-15, -6.07880720e-05,  5.99007881e-17, -1.58028803e-16,\n",
+       "         -5.46836105e-15, -6.70547267e-04, -3.79218408e-04, -1.57924634e-04,\n",
+       "         -5.48175883e-16]),\n",
+       "  array([ 2.64966791e-06, -4.16132420e-17,  1.02054098e+00,  3.95528257e-17,\n",
+       "          9.91503699e-07, -1.81290498e-19,  1.00000000e+00,  9.36207576e-16,\n",
+       "          3.40594300e-15,  8.29183747e-04,  4.08114106e-04,  1.13000752e-04,\n",
+       "         -4.03196157e-16, -3.29333163e-06, -1.35717191e-16, -4.41772582e-01,\n",
+       "         -2.00249758e-15, -6.21161249e-05,  5.53170660e-17, -1.47457142e-16,\n",
+       "         -5.34784944e-15, -6.52868347e-04, -3.69354041e-04, -1.53922328e-04,\n",
+       "         -5.40582976e-16]),\n",
+       "  array([ 2.64551088e-06, -4.17146440e-17,  1.02010169e+00,  3.85065627e-17,\n",
+       "          9.59739610e-07, -1.56113291e-19,  1.00000000e+00,  9.36070567e-16,\n",
+       "          3.40072429e-15,  8.28548393e-04,  4.07754592e-04,  1.12850883e-04,\n",
+       "         -4.03726509e-16, -3.29985968e-06, -1.35693158e-16, -4.39295095e-01,\n",
+       "         -2.09252602e-15, -6.35281772e-05,  5.03548507e-17, -1.37008907e-16,\n",
+       "         -5.21870581e-15, -6.35354504e-04, -3.59514197e-04, -1.49868348e-04,\n",
+       "         -5.30352171e-16]),\n",
+       "  array([ 2.64137955e-06, -4.18171148e-17,  1.01966506e+00,  3.74129167e-17,\n",
+       "          9.27243098e-07, -1.33552084e-19,  1.00000000e+00,  9.35943809e-16,\n",
+       "          3.39564206e-15,  8.27930370e-04,  4.07404879e-04,  1.12705110e-04,\n",
+       "         -4.04244297e-16, -3.30742389e-06, -1.35618894e-16, -4.36622386e-01,\n",
+       "         -2.18729195e-15, -6.49930234e-05,  4.51228177e-17, -1.26758021e-16,\n",
+       "         -5.08222896e-15, -6.18022549e-04, -3.49713092e-04, -1.45773079e-04,\n",
+       "         -5.17787473e-16]),\n",
+       "  array([ 2.63727349e-06, -4.19206442e-17,  1.01923130e+00,  3.62703745e-17,\n",
+       "          8.94002000e-07, -1.13693486e-19,  1.00000000e+00,  9.35827030e-16,\n",
+       "          3.39070238e-15,  8.27329481e-04,  4.07064913e-04,  1.12563463e-04,\n",
+       "         -4.04747486e-16, -3.31607096e-06, -1.35490536e-16, -4.33763214e-01,\n",
+       "         -2.28508443e-15, -6.64821964e-05,  3.97175651e-17, -1.16778755e-16,\n",
+       "         -4.93967547e-15, -6.00889186e-04, -3.39965344e-04, -1.41647431e-04,\n",
+       "         -5.03189561e-16]),\n",
+       "  array([ 2.63319216e-06, -4.20252176e-17,  1.01880057e+00,  3.50782138e-17,\n",
+       "          8.60017003e-07, -9.65782842e-20,  1.00000000e+00,  9.35719895e-16,\n",
+       "          3.38591014e-15,  8.26745510e-04,  4.06734628e-04,  1.12425960e-04,\n",
+       "         -4.05234337e-16, -3.32583195e-06, -1.35305138e-16, -4.30726139e-01,\n",
+       "         -2.38432141e-15, -6.79699937e-05,  3.42307370e-17, -1.07135449e-16,\n",
+       "         -4.79224763e-15, -5.83970735e-04, -3.30285648e-04, -1.37502560e-04,\n",
+       "         -4.86851287e-16]),\n",
+       "  array([ 2.62913493e-06, -4.21308159e-17,  1.01837306e+00,  3.38364363e-17,\n",
+       "          8.25300297e-07, -8.22048476e-20,  1.00000000e+00,  9.35622011e-16,\n",
+       "          3.38126906e-15,  8.26178227e-04,  4.06413939e-04,  1.12292611e-04,\n",
+       "         -4.05703392e-16, -3.33672364e-06, -1.35060619e-16, -4.27519522e-01,\n",
+       "         -2.48355496e-15, -6.94334119e-05,  2.87471728e-17, -9.78838506e-17,\n",
+       "         -4.64108146e-15, -5.67282854e-04, -3.20688480e-04, -1.33349622e-04,\n",
+       "         -4.69054113e-16]),\n",
+       "  array([ 2.62510110e-06, -4.22374155e-17,  1.01794890e+00,  3.25456982e-17,\n",
+       "          7.89874252e-07, -7.05332522e-20,  1.00000000e+00,  9.35532939e-16,\n",
+       "          3.37678182e-15,  8.25627387e-04,  4.06102751e-04,  1.12163411e-04,\n",
+       "         -4.06153457e-16, -3.34874987e-06, -1.34755702e-16, -4.24151527e-01,\n",
+       "         -2.58147636e-15, -7.08520902e-05,  2.33434578e-17, -8.90723956e-17,\n",
+       "         -4.48724041e-15, -5.50840361e-04, -3.11187853e-04, -1.29199565e-04,\n",
+       "         -4.50065333e-16]),\n",
+       "  array([ 2.62108990e-06, -4.23449890e-17,  1.01752827e+00,  3.12072396e-17,\n",
+       "          7.53770147e-07, -6.14894162e-20,  1.00000000e+00,  9.35452197e-16,\n",
+       "          3.37245011e-15,  8.25092730e-04,  4.05800954e-04,  1.12038348e-04,\n",
+       "         -4.06583593e-16, -3.36190286e-06, -1.34389854e-16, -4.20630125e-01,\n",
+       "         -2.67691708e-15, -7.22082102e-05,  1.80879076e-17, -8.07418601e-17,\n",
+       "         -4.33171012e-15, -5.34657074e-04, -3.01797131e-04, -1.25062959e-04,\n",
+       "         -4.30136008e-16]),\n",
+       "  array([ 2.61710046e-06, -4.24535049e-17,  1.01711131e+00,  2.98228159e-17,\n",
+       "          7.17026959e-07, -5.49696606e-20,  1.00000000e+00,  9.35379270e-16,\n",
+       "          3.36827471e-15,  8.24573984e-04,  4.05508425e-04,  1.11917398e-04,\n",
+       "         -4.06993092e-16, -3.37616464e-06, -1.33963208e-16, -4.16963091e-01,\n",
+       "         -2.76884758e-15, -7.34863756e-05,  1.30397175e-17, -7.29263711e-17,\n",
+       "         -4.17539541e-15, -5.18745694e-04, -2.92528866e-04, -1.20949862e-04,\n",
+       "         -4.09499489e-16]),\n",
+       "  array([ 2.61313189e-06, -4.25629284e-17,  1.01669815e+00,  2.83946288e-17,\n",
+       "          6.79690219e-07, -5.08453047e-20,  1.00000000e+00,  9.35313617e-16,\n",
+       "          3.36425559e-15,  8.24070866e-04,  4.05225031e-04,  1.11800529e-04,\n",
+       "         -4.07381463e-16, -3.39150830e-06, -1.33476498e-16, -4.13158012e-01,\n",
+       "         -2.85637407e-15, -7.46734800e-05,  8.24889052e-18, -6.56536951e-17,\n",
+       "         -4.01911888e-15, -5.03117724e-04, -2.83394695e-04, -1.16869715e-04,\n",
+       "         -3.88370441e-16]),\n",
+       "  array([ 2.60918320e-06, -4.26732212e-17,  1.01628893e+00,  2.69252622e-17,\n",
+       "          6.41810942e-07, -4.89672294e-20,  1.00000000e+00,  9.35254671e-16,\n",
+       "          3.36039197e-15,  8.23583083e-04,  4.04950625e-04,  1.11687697e-04,\n",
+       "         -4.07748407e-16, -3.40789933e-06, -1.32930981e-16, -4.09222283e-01,\n",
+       "         -2.93873325e-15, -7.57585548e-05,  3.75630437e-18, -5.89455728e-17,\n",
+       "         -3.86362064e-15, -4.87783412e-04, -2.74405249e-04, -1.12831269e-04,\n",
+       "         -3.66944304e-16]),\n",
+       "  array([ 2.60525337e-06, -4.27843422e-17,  1.01588377e+00,  2.54176183e-17,\n",
+       "          6.03444619e-07, -4.91687872e-20,  1.00000000e+00,  9.35201857e-16,\n",
+       "          3.35668241e-15,  8.23110331e-04,  4.04685055e-04,  1.11578855e-04,\n",
+       "         -4.08093804e-16, -3.42529679e-06, -1.32328370e-16, -4.05163113e-01,\n",
+       "         -3.01528772e-15, -7.67326456e-05, -4.02984818e-19, -5.28142560e-17,\n",
+       "         -3.70956106e-15, -4.72751755e-04, -2.65570115e-04, -1.08842529e-04,\n",
+       "         -3.45397234e-16]),\n",
+       "  array([ 2.60134133e-06, -4.28962473e-17,  1.01548278e+00,  2.38748595e-17,\n",
+       "          5.64650297e-07, -5.12712697e-20,  1.00000000e+00,  9.35154587e-16,\n",
+       "          3.35312489e-15,  8.22652301e-04,  4.04428157e-04,  1.11473944e-04,\n",
+       "         -4.08417691e-16, -3.44365449e-06, -1.31670763e-16, -4.00987526e-01,\n",
+       "         -3.08551767e-15, -7.75886430e-05, -4.20485470e-18, -4.72698236e-17,\n",
+       "         -3.55752177e-15, -4.58030473e-04, -2.56897806e-04, -1.04910734e-04,\n",
+       "         -3.23886320e-16]),\n",
+       "  array([ 2.59744594e-06, -4.30088901e-17,  1.01508608e+00,  2.23003526e-17,\n",
+       "          5.25489727e-07, -5.50878974e-20,  1.00000000e+00,  9.35112270e-16,\n",
+       "          3.34971688e-15,  8.22208675e-04,  4.04179762e-04,  1.11372902e-04,\n",
+       "         -4.08720241e-16, -3.46292201e-06, -1.30960576e-16, -3.96702362e-01,\n",
+       "         -3.14901375e-15, -7.83211401e-05, -7.63316360e-18, -4.23174572e-17,\n",
+       "         -3.40800929e-15, -4.43626043e-04, -2.48395764e-04, -1.01042345e-04,\n",
+       "         -3.02550040e-16]),\n",
+       "  array([ 2.59356607e-06, -4.31222218e-17,  1.01469376e+00,  2.06976182e-17,\n",
+       "          4.86026584e-07, -6.04268567e-20,  1.00000000e+00,  9.35074314e-16,\n",
+       "          3.34645542e-15,  8.21779131e-04,  4.03939691e-04,  1.11275659e-04,\n",
+       "         -4.09001750e-16, -3.48304574e-06, -1.30200480e-16, -3.92314280e-01,\n",
+       "         -3.20546886e-15, -7.89262860e-05, -1.06778431e-17, -3.79561581e-17,\n",
+       "         -3.26145864e-15, -4.29543732e-04, -2.40070376e-04, -9.72430455e-05,\n",
+       "         -2.81508964e-16]),\n",
+       "  array([ 2.58970050e-06, -4.32361920e-17,  1.01430593e+00,  1.90702833e-17,\n",
+       "          4.46325763e-07, -6.70945399e-20,  1.00000000e+00,  9.35040133e-16,\n",
+       "          3.34333718e-15,  8.21363343e-04,  4.03707764e-04,  1.11182141e-04,\n",
+       "         -4.09262616e-16, -3.50396972e-06, -1.29393345e-16, -3.87829761e-01,\n",
+       "         -3.25466978e-15, -7.94016422e-05, -1.33353047e-17, -3.41805094e-17,\n",
+       "         -3.11823745e-15, -4.15787644e-04, -2.31927003e-04, -9.35177678e-05,\n",
+       "         -2.60866617e-16]),\n",
+       "  array([ 2.58584803e-06, -4.33507483e-17,  1.01392268e+00,  1.74220389e-17,\n",
+       "          4.06452741e-07, -7.48983842e-20,  1.00000000e+00,  9.35009152e-16,\n",
+       "          3.34035853e-15,  8.20960983e-04,  4.03483794e-04,  1.11092270e-04,\n",
+       "         -4.09503327e-16, -3.52563649e-06, -1.28542186e-16, -3.83255109e-01,\n",
+       "         -3.29648871e-15, -7.97460449e-05, -1.56076391e-17, -3.09809435e-17,\n",
+       "         -2.97865031e-15, -4.02360778e-04, -2.23970028e-04, -8.98707150e-05,\n",
+       "         -2.40710464e-16]),\n",
+       "  array([ 2.58200742e-06, -4.34658371e-17,  1.01354408e+00,  1.57566015e-17,\n",
+       "          3.66473005e-07, -8.36493602e-20,  1.00000000e+00,  9.34980808e-16,\n",
+       "          3.33751559e-15,  8.20571717e-04,  4.03267591e-04,  1.11005965e-04,\n",
+       "         -4.09724440e-16, -3.54798780e-06, -1.27650110e-16, -3.78596453e-01,\n",
+       "         -3.33087481e-15, -7.99594718e-05, -1.75019129e-17, -2.83441595e-17,\n",
+       "         -2.84294329e-15, -3.89265091e-04, -2.16202900e-04, -8.63053983e-05,\n",
+       "         -2.21112968e-16]),\n",
+       "  array([ 2.57817740e-06, -4.35814035e-17,  1.01317022e+00,  1.40776786e-17,\n",
+       "          3.26451547e-07, -9.31640745e-20,  1.00000000e+00,  9.34954554e-16,\n",
+       "          3.33480428e-15,  8.20195216e-04,  4.03058963e-04,  1.10923140e-04,\n",
+       "         -4.09926572e-16, -3.57096529e-06, -1.26720280e-16, -3.73859751e-01,\n",
+       "         -3.35784590e-15, -8.00429157e-05, -1.90293979e-17, -2.62534499e-17,\n",
+       "         -2.71130854e-15, -3.76501569e-04, -2.08628198e-04, -8.28246776e-05,\n",
+       "         -2.02132705e-16]),\n",
+       "  array([ 2.57435669e-06, -4.36973919e-17,  1.01280117e+00,  1.23889383e-17,\n",
+       "          2.86452415e-07, -1.03266564e-19,  1.00000000e+00,  9.34929865e-16,\n",
+       "          3.33222039e-15,  8.19831146e-04,  4.02857716e-04,  1.10843709e-04,\n",
+       "         -4.10110388e-16, -3.59451101e-06, -1.25755867e-16, -3.69050790e-01,\n",
+       "         -3.37748051e-15, -7.99982645e-05, -2.02049561e-17, -2.46892031e-17,\n",
+       "         -2.58388889e-15, -3.64070290e-04, -2.01247688e-04, -7.94308049e-05,\n",
+       "         -1.83815501e-16]),\n",
+       "  array([ 2.57054402e-06, -4.38137457e-17,  1.01243700e+00,  1.06939832e-17,\n",
+       "          2.46538321e-07, -1.13789760e-19,  1.00000000e+00,  9.34906236e-16,\n",
+       "          3.32975961e-15,  8.19479175e-04,  4.02663653e-04,  1.10767584e-04,\n",
+       "         -4.10276584e-16, -3.61856797e-06, -1.24760022e-16, -3.64175191e-01,\n",
+       "         -3.38991019e-15, -7.98281881e-05, -2.10463730e-17, -2.36292915e-17,\n",
+       "         -2.46078237e-15, -3.51970506e-04, -1.94062385e-04, -7.61254709e-05,\n",
+       "         -1.66195572e-16]),\n",
+       "  array([ 2.56673810e-06, -4.39304080e-17,  1.01207776e+00,  8.99632707e-18,\n",
+       "          2.06770305e-07, -1.24576632e-19,  1.00000000e+00,  9.34883187e-16,\n",
+       "          3.32741756e-15,  8.19138974e-04,  4.02476581e-04,  1.10694674e-04,\n",
+       "         -4.10425880e-16, -3.64308053e-06, -1.23735846e-16, -3.59238408e-01,\n",
+       "         -3.39531223e-15, -7.95360322e-05, -2.15737313e-17, -2.30494543e-17,\n",
+       "         -2.34204666e-15, -3.40200706e-04, -1.87072619e-04, -7.29098518e-05,\n",
+       "         -1.49296648e-16]),\n",
+       "  array([ 2.56293762e-06, -4.40473217e-17,  1.01172351e+00,  7.29937566e-18,\n",
+       "          1.67207445e-07, -1.35481072e-19,  1.00000000e+00,  9.34860263e-16,\n",
+       "          3.32518986e-15,  8.18810216e-04,  4.02296302e-04,  1.10624889e-04,\n",
+       "         -4.10559013e-16, -3.66799476e-06, -1.22686360e-16, -3.54245733e-01,\n",
+       "         -3.39390281e-15, -7.91257197e-05, -2.18088701e-17, -2.29237141e-17,\n",
+       "         -2.22770331e-15, -3.28758692e-04, -1.80278098e-04, -6.97846557e-05,\n",
+       "         -1.33133065e-16]),\n",
+       "  array([ 2.55914131e-06, -4.41644294e-17,  1.01137431e+00,  5.60641032e-18,\n",
+       "          1.27906615e-07, -1.46368519e-19,  1.00000000e+00,  9.34837038e-16,\n",
+       "          3.32307212e-15,  8.18492574e-04,  4.02122624e-04,  1.10558139e-04,\n",
+       "         -4.10676724e-16, -3.69325876e-06, -1.21614488e-16, -3.49202298e-01,\n",
+       "         -3.38593066e-15, -7.86016586e-05, -2.17748849e-17, -2.32247679e-17,\n",
+       "         -2.11774185e-15, -3.17641646e-04, -1.73677968e-04, -6.67501693e-05,\n",
+       "         -1.17710824e-16]),\n",
+       "  array([ 2.55534787e-06, -4.42816741e-17,  1.01103020e+00,  3.92057474e-18,\n",
+       "          8.89222868e-08, -1.57116353e-19,  1.00000000e+00,  9.34813114e-16,\n",
+       "          3.32105999e-15,  8.18185728e-04,  4.01955354e-04,  1.10494333e-04,\n",
+       "         -4.10779753e-16, -3.71882289e-06, -1.20523041e-16, -3.44113079e-01,\n",
+       "         -3.37167115e-15, -7.79686573e-05, -2.14956638e-17, -2.39243359e-17,\n",
+       "         -2.01212370e-15, -3.06846195e-04, -1.67270872e-04, -6.38063017e-05,\n",
+       "         -1.03028597e-16]),\n",
+       "  array([ 2.55155604e-06, -4.43989988e-17,  1.01069121e+00,  2.24486430e-18,\n",
+       "          5.03063637e-08, -1.67614097e-19,  1.00000000e+00,  9.34788120e-16,\n",
+       "          3.31914921e-15,  8.17889359e-04,  4.01794299e-04,  1.10433380e-04,\n",
+       "         -4.10868831e-16, -3.74463994e-06, -1.19414698e-16, -3.38982892e-01,\n",
+       "         -3.35142086e-15, -7.72318462e-05, -2.09954822e-17, -2.49934986e-17,\n",
+       "         -1.91078585e-15, -2.96368474e-04, -1.61055010e-04, -6.09526273e-05,\n",
+       "         -8.90786772e-17]),\n",
+       "  array([ 2.54776454e-06, -4.45163471e-17,  1.01035740e+00,  5.82117954e-19,\n",
+       "          1.21080603e-08, -1.77763419e-19,  1.00000000e+00,  9.34761717e-16,\n",
+       "          3.31733556e-15,  8.17603155e-04,  4.01639270e-04,  1.10375192e-04,\n",
+       "         -4.10944679e-16, -3.77066530e-06, -1.18292000e-16, -3.33816403e-01,\n",
+       "         -3.32549268e-15, -7.63966069e-05, -2.02986395e-17, -2.64029970e-17,\n",
+       "         -1.81364428e-15, -2.86204191e-04, -1.55028190e-04, -5.81884261e-05,\n",
+       "         -7.58478798e-17]),\n",
+       "  array([ 2.54397212e-06, -4.46336632e-17,  1.01002878e+00, -1.06498771e-18,\n",
+       "         -2.56261931e-08, -1.87477997e-19,  1.00000000e+00,  9.34733594e-16,\n",
+       "          3.31561497e-15,  8.17326807e-04,  4.01490083e-04,  1.10319679e-04,\n",
+       "         -4.11007998e-16, -3.79685705e-06, -1.17157340e-16, -3.28618128e-01,\n",
+       "         -3.29421132e-15, -7.54685068e-05, -1.94291520e-17, -2.81235162e-17,\n",
+       "         -1.72059727e-15, -2.76348677e-04, -1.49187879e-04, -5.55127212e-05,\n",
+       "         -6.33183775e-17]),\n",
+       "  array([ 2.54017756e-06, -4.47508917e-17,  1.00970539e+00, -2.69394239e-18,\n",
+       "         -6.28528134e-08, -1.96683248e-19,  1.00000000e+00,  9.34703468e-16,\n",
+       "          3.31398344e-15,  8.17060010e-04,  4.01346551e-04,  1.10266755e-04,\n",
+       "         -4.11059466e-16, -3.82317600e-06, -1.16012960e-16, -3.23392433e-01,\n",
+       "         -3.25790935e-15, -7.44532405e-05, -1.84104994e-17, -3.01259526e-17,\n",
+       "         -1.63152838e-15, -2.66796942e-04, -1.43531255e-04, -5.29243149e-05,\n",
+       "         -5.14684787e-17]),\n",
+       "  array([ 2.53637964e-06, -4.48679785e-17,  1.00938724e+00, -4.30240419e-18,\n",
+       "         -9.95311018e-08, -2.05315951e-19,  1.00000000e+00,  9.34671086e-16,\n",
+       "          3.31243713e-15,  8.16802466e-04,  4.01208496e-04,  1.10216333e-04,\n",
+       "         -4.11099739e-16, -3.84958575e-06, -1.14860946e-16, -3.18143540e-01,\n",
+       "         -3.21692357e-15, -7.33565769e-05, -1.72654013e-17, -3.23816365e-17,\n",
+       "         -1.54630924e-15, -2.57543727e-04, -1.38055242e-04, -5.04218206e-05,\n",
+       "         -4.02733463e-17]),\n",
+       "  array([ 2.53257716e-06, -4.49848701e-17,  1.00907437e+00, -5.88820016e-18,\n",
+       "         -1.35623258e-07, -2.13323775e-19,  1.00000000e+00,  9.34636224e-16,\n",
+       "          3.31097233e-15,  8.16553882e-04,  4.01075739e-04,  1.10168329e-04,\n",
+       "         -4.11129445e-16, -3.87605265e-06, -1.13703230e-16, -3.12875526e-01,\n",
+       "         -3.17159194e-15, -7.21843122e-05, -1.60156415e-17, -3.48625384e-17,\n",
+       "         -1.46480218e-15, -2.48583545e-04, -1.32756562e-04, -4.80036939e-05,\n",
+       "         -2.97056570e-17]),\n",
+       "  array([ 2.52876895e-06, -4.51015142e-17,  1.00876677e+00, -7.44932555e-18,\n",
+       "         -1.71094372e-07, -2.20664740e-19,  1.00000000e+00,  9.34598682e-16,\n",
+       "          3.30958546e-15,  8.16313972e-04,  4.00948108e-04,  1.10122661e-04,\n",
+       "         -4.11149181e-16, -3.90254580e-06, -1.12541586e-16, -3.07592330e-01,\n",
+       "         -3.12225076e-15, -7.09422275e-05, -1.46819253e-17, -3.75414462e-17,\n",
+       "         -1.38686259e-15, -2.39910728e-04, -1.27631761e-04, -4.56682595e-05,\n",
+       "         -1.97362048e-17]),\n",
+       "  array([ 2.52495389e-06, -4.52178596e-17,  1.00846448e+00, -8.98394172e-18,\n",
+       "         -2.05912398e-07, -2.27306628e-19,  1.00000000e+00,  9.34558290e-16,\n",
+       "          3.30827312e-15,  8.16082452e-04,  4.00825430e-04,  1.10079247e-04,\n",
+       "         -4.11159516e-16, -3.92903700e-06, -1.11377641e-16, -3.02297750e-01,\n",
+       "         -3.06923231e-15, -6.96360520e-05, -1.32837698e-17, -4.03921159e-17,\n",
+       "         -1.31234107e-15, -2.31519466e-04, -1.22677255e-04, -4.34137370e-05,\n",
+       "         -1.03344496e-17]),\n",
+       "  array([ 2.52113083e-06, -4.53338563e-17,  1.00816748e+00, -1.04903731e-17,\n",
+       "         -2.40048113e-07, -2.33226347e-19,  1.00000000e+00,  9.34514901e-16,\n",
+       "          3.30703204e-15,  8.15859048e-04,  4.00707541e-04,  1.10038009e-04,\n",
+       "         -4.11160985e-16, -3.95550063e-06, -1.10212870e-16, -2.96995450e-01,\n",
+       "         -3.01286280e-15, -6.82714307e-05, -1.18394308e-17, -4.33894088e-17,\n",
+       "         -1.24108543e-15, -2.23403840e-04, -1.17889350e-04, -4.12382638e-05,\n",
+       "         -1.46901281e-18]),\n",
+       "  array([ 2.51729871e-06, -4.54494555e-17,  1.00787579e+00, -1.19671034e-17,\n",
+       "         -2.73475061e-07, -2.38409276e-19,  1.00000000e+00,  9.34468391e-16,\n",
+       "          3.30585909e-15,  8.15643490e-04,  4.00594277e-04,  1.09998869e-04,\n",
+       "         -4.11154093e-16, -3.98191364e-06, -1.09048606e-16, -2.91688961e-01,\n",
+       "         -2.95346062e-15, -6.68538965e-05, -1.03658490e-17, -4.65093974e-17,\n",
+       "         -1.17294248e-15, -2.15557856e-04, -1.13264279e-04, -3.91399154e-05,\n",
+       "          6.89187644e-18]),\n",
+       "  array([ 2.51345645e-06, -4.55646098e-17,  1.00758941e+00, -1.34127709e-17,\n",
+       "         -3.06169484e-07, -2.42848591e-19,  1.00000000e+00,  9.34418662e-16,\n",
+       "          3.30475133e-15,  8.15435515e-04,  4.00485479e-04,  1.09961752e-04,\n",
+       "         -4.11139313e-16, -4.00825539e-06, -1.07886044e-16, -2.86381682e-01,\n",
+       "         -2.89133489e-15, -6.53888460e-05, -8.87862326e-18, -4.97294561e-17,\n",
+       "         -1.10775965e-15, -2.07975479e-04, -1.08798225e-04, -3.71167246e-05,\n",
+       "          1.47799831e-17]),\n",
+       "  array([ 2.50960304e-06, -4.56792734e-17,  1.00730833e+00, -1.48261630e-17,\n",
+       "         -3.38110244e-07, -2.46544595e-19,  1.00000000e+00,  9.34365633e-16,\n",
+       "          3.30370595e-15,  8.15234864e-04,  4.00380991e-04,  1.09926586e-04,\n",
+       "         -4.11117086e-16, -4.03450755e-06, -1.06726247e-16, -2.81076885e-01,\n",
+       "         -2.82678430e-15, -6.38815196e-05, -7.39199793e-18, -5.30283249e-17,\n",
+       "         -1.04538640e-15, -2.00650654e-04, -1.04487342e-04, -3.51666979e-05,\n",
+       "          2.22267125e-17]),\n",
+       "  array([ 2.50573747e-06, -4.57934016e-17,  1.00703256e+00, -1.62062111e-17,\n",
+       "         -3.69278736e-07, -2.49504035e-19,  1.00000000e+00,  9.34309247e-16,\n",
+       "          3.30272027e-15,  8.15041287e-04,  4.00280663e-04,  1.09893298e-04,\n",
+       "         -4.11087823e-16, -4.06065402e-06, -1.05570155e-16, -2.75777716e-01,\n",
+       "         -2.76009611e-15, -6.23369844e-05, -5.91887103e-18, -5.63861601e-17,\n",
+       "         -9.85675521e-16, -1.93577336e-04, -1.00327777e-04, -3.32878304e-05,\n",
+       "          2.92627998e-17]),\n",
+       "  array([ 2.50185877e-06, -4.59069513e-17,  1.00676207e+00, -1.75519839e-17,\n",
+       "         -3.99658797e-07, -2.51739445e-19,  1.00000000e+00,  9.34249463e-16,\n",
+       "          3.30179179e-15,  8.14854537e-04,  4.00184348e-04,  1.09861820e-04,\n",
+       "         -4.11051905e-16, -4.08668075e-06, -1.04418589e-16, -2.70487197e-01,\n",
+       "         -2.69154547e-15, -6.07601207e-05, -4.47081146e-18, -5.97845622e-17,\n",
+       "         -9.28484240e-16, -1.86749507e-04, -9.63156891e-05, -3.14781188e-05,\n",
+       "          3.59180384e-17]),\n",
+       "  array([ 2.49796603e-06, -4.60198811e-17,  1.00649686e+00, -1.88626813e-17,\n",
+       "         -4.29236602e-07, -2.53268493e-19,  1.00000000e+00,  9.34186256e-16,\n",
+       "          3.30091811e-15,  8.14674376e-04,  4.00091901e-04,  1.09832084e-04,\n",
+       "         -4.11009684e-16, -4.11257567e-06, -1.03272260e-16, -2.65208231e-01,\n",
+       "         -2.62139481e-15, -5.91556111e-05, -3.05808690e-18, -6.32065869e-17,\n",
+       "         -8.73675183e-16, -1.80161200e-04, -9.24472666e-05, -2.97355735e-05,\n",
+       "          4.22210470e-17]),\n",
+       "  array([ 2.49405833e-06, -4.61321507e-17,  1.00623692e+00, -2.01376280e-17,\n",
+       "         -4.58000568e-07, -2.54113360e-19,  1.00000000e+00,  9.34119619e-16,\n",
+       "          3.30009700e-15,  8.14500570e-04,  4.00003182e-04,  1.09804026e-04,\n",
+       "         -4.10961485e-16, -4.13832852e-06, -1.02131778e-16, -2.59943600e-01,\n",
+       "         -2.54989350e-15, -5.75279324e-05, -1.68972514e-18, -6.66367723e-17,\n",
+       "         -8.21117207e-16, -1.73806512e-04, -8.87187384e-05, -2.80582281e-05,\n",
+       "          4.81990710e-17]),\n",
+       "  array([ 2.49013482e-06, -4.62437218e-17,  1.00598222e+00, -2.13762668e-17,\n",
+       "         -4.85941243e-07, -2.54300137e-19,  1.00000000e+00,  9.34049558e-16,\n",
+       "          3.29932631e-15,  8.14332890e-04,  3.99918055e-04,  1.09777582e-04,\n",
+       "         -4.10907607e-16, -4.16393074e-06, -1.00997654e-16, -2.54695973e-01,\n",
+       "         -2.47727762e-15, -5.58813493e-05, -3.73543813e-19, -7.00611038e-17,\n",
+       "         -7.70686077e-16, -1.67679625e-04, -8.51263884e-05, -2.64441484e-05,\n",
+       "          5.38778190e-17]),\n",
+       "  array([ 2.48619466e-06, -4.63545573e-17,  1.00573275e+00, -2.25781517e-17,\n",
+       "         -5.13051199e-07, -2.53858250e-19,  1.00000000e+00,  9.33976091e-16,\n",
+       "          3.29860405e-15,  8.14171115e-04,  3.99836389e-04,  1.09752690e-04,\n",
+       "         -4.10848326e-16, -4.18937531e-06, -9.98703158e-17, -2.49467904e-01,\n",
+       "         -2.40376981e-15, -5.42199112e-05,  8.83782326e-19, -7.34670083e-17,\n",
+       "         -7.22265030e-16, -1.61774810e-04, -8.16665656e-05, -2.48914399e-05,\n",
+       "          5.92813286e-17]),\n",
+       "  array([ 2.48223706e-06, -4.64646219e-17,  1.00548849e+00, -2.37429414e-17,\n",
+       "         -5.39324923e-07, -2.52819914e-19,  1.00000000e+00,  9.33899248e-16,\n",
+       "          3.29792830e-15,  8.14015029e-04,  3.99758053e-04,  1.09729292e-04,\n",
+       "         -4.10783894e-16, -4.21465669e-06, -9.87501072e-17, -2.44261836e-01,\n",
+       "         -2.32957933e-15, -5.25474496e-05,  2.07668072e-18, -7.68432979e-17,\n",
+       "         -6.75745204e-16, -1.56086446e-04, -7.83356929e-05, -2.33982541e-05,\n",
+       "          6.44318636e-17]),\n",
+       "  array([ 2.47826125e-06, -4.65738817e-17,  1.00524941e+00, -2.48703925e-17,\n",
+       "         -5.64758712e-07, -2.51219617e-19,  1.00000000e+00,  9.33819068e-16,\n",
+       "          3.29729727e-15,  8.13864420e-04,  3.99682923e-04,  1.09707329e-04,\n",
+       "         -4.10714544e-16, -4.23977062e-06, -9.76373004e-17, -2.39080102e-01,\n",
+       "         -2.25490217e-15, -5.08675780e-05,  3.20060197e-18, -8.01801496e-17,\n",
+       "         -6.31025953e-16, -1.50609025e-04, -7.51302749e-05, -2.19627936e-05,\n",
+       "          6.93498366e-17]),\n",
+       "  array([ 2.47426651e-06, -4.66823044e-17,  1.00501549e+00, -2.59603531e-17,\n",
+       "         -5.89350559e-07, -2.49093635e-19,  1.00000000e+00,  9.33735599e-16,\n",
+       "          3.29670926e-15,  8.13719083e-04,  3.99610876e-04,  1.09686746e-04,\n",
+       "         -4.10640491e-16, -4.26471405e-06, -9.65321005e-17, -2.33924932e-01,\n",
+       "         -2.17992120e-15, -4.91836930e-05,  4.25197346e-18, -8.34690331e-17,\n",
+       "         -5.88015054e-16, -1.45337162e-04, -7.20469036e-05, -2.05833164e-05,\n",
+       "          7.40537594e-17]),\n",
+       "  array([ 2.47025215e-06, -4.67898592e-17,  1.00478669e+00, -2.70127564e-17,\n",
+       "         -6.13100047e-07, -2.46479581e-19,  1.00000000e+00,  9.33648896e-16,\n",
+       "          3.29616263e-15,  8.13578817e-04,  3.99541794e-04,  1.09667488e-04,\n",
+       "         -4.10561930e-16, -4.28948499e-06, -9.54346531e-17, -2.28798450e-01,\n",
+       "         -2.10480645e-15, -4.74989769e-05,  5.22811491e-18, -8.67026775e-17,\n",
+       "         -5.46628802e-16, -1.40265597e-04, -6.90822632e-05, -1.92581390e-05,\n",
+       "          7.85602163e-17]),\n",
+       "  array([ 2.46621749e-06, -4.68965169e-17,  1.00456299e+00, -2.80276141e-17,\n",
+       "         -6.36008248e-07, -2.43415986e-19,  1.00000000e+00,  9.33559021e-16,\n",
+       "          3.29565584e-15,  8.13443428e-04,  3.99475561e-04,  1.09649502e-04,\n",
+       "         -4.10479047e-16, -4.31408243e-06, -9.43450498e-17, -2.23702679e-01,\n",
+       "         -2.02971544e-15, -4.58164005e-05,  6.12719687e-18, -8.98749781e-17,\n",
+       "         -5.06792015e-16, -1.35389201e-04, -6.62331335e-05, -1.79856390e-05,\n",
+       "          8.28838607e-17]),\n",
+       "  array([ 2.46216192e-06, -4.70022498e-17,  1.00434435e+00, -2.90050109e-17,\n",
+       "         -6.58077612e-07, -2.39941933e-19,  1.00000000e+00,  9.33466040e-16,\n",
+       "          3.29518740e-15,  8.13312725e-04,  3.99412064e-04,  1.09632738e-04,\n",
+       "         -4.10392009e-16, -4.33850620e-06, -9.32633352e-17, -2.18639542e-01,\n",
+       "         -1.95479353e-15, -4.41387281e-05,  6.94811268e-18, -9.29810083e-17,\n",
+       "         -4.68437938e-16, -1.30702981e-04, -6.34963923e-05, -1.67642567e-05,\n",
+       "          8.70374320e-17]),\n",
+       "  array([ 2.45808485e-06, -4.71070317e-17,  1.00413074e+00, -2.99450980e-17,\n",
+       "         -6.79311873e-07, -2.36096648e-19,  1.00000000e+00,  9.33370023e-16,\n",
+       "          3.29475589e-15,  8.13186523e-04,  3.99351195e-04,  1.09617145e-04,\n",
+       "         -4.10300977e-16, -4.36275691e-06, -9.21895114e-17, -2.13610866e-01,\n",
+       "         -1.88017434e-15, -4.24685222e-05,  7.69057528e-18, -9.60167413e-17,\n",
+       "         -4.31508067e-16, -1.26202077e-04, -6.08690164e-05, -1.55924956e-05,\n",
+       "          9.10317938e-17]),\n",
+       "  array([ 2.45398570e-06, -4.72108378e-17,  1.00392212e+00, -3.08480881e-17,\n",
+       "         -6.99715948e-07, -2.31919249e-19,  1.00000000e+00,  9.33271044e-16,\n",
+       "          3.29435994e-15,  8.13064641e-04,  3.99292847e-04,  1.09602676e-04,\n",
+       "         -4.10206101e-16, -4.38683580e-06, -9.11235444e-17, -2.08618384e-01,\n",
+       "         -1.80598015e-15, -4.08081496e-05,  8.35480269e-18, -9.89792950e-17,\n",
+       "         -3.95951891e-16, -1.21881764e-04, -5.83480816e-05, -1.44689230e-05,\n",
+       "          9.48759844e-17]),\n",
+       "  array([ 2.44986396e-06, -4.73136449e-17,  1.00371845e+00, -3.17142493e-17,\n",
+       "         -7.19295841e-07, -2.27448408e-19,  1.00000000e+00,  9.33169177e-16,\n",
+       "          3.29399821e-15,  8.12946904e-04,  3.99236916e-04,  1.09589284e-04,\n",
+       "         -4.10107524e-16, -4.41074468e-06, -9.00653684e-17, -2.03663736e-01,\n",
+       "         -1.73232240e-15, -3.91597875e-05,  8.94168556e-18, -1.01866562e-16,\n",
+       "         -3.61726558e-16, -1.17737451e-04, -5.59307624e-05, -1.33921693e-05,\n",
+       "          9.85772924e-17]),\n",
+       "  array([ 2.44571912e-06, -4.74154310e-17,  1.00351970e+00, -3.25439004e-17,\n",
+       "         -7.38058557e-07, -2.22722210e-19,  1.00000000e+00,  9.33064500e-16,\n",
+       "          3.29366942e-15,  8.12833139e-04,  3.99183302e-04,  1.09576923e-04,\n",
+       "         -4.10005383e-16, -4.43448587e-06, -8.90148908e-17, -1.98748471e-01,\n",
+       "         -1.65930215e-15, -3.75254306e-05,  9.45239943e-18, -1.04677552e-16,\n",
+       "         -3.28796484e-16, -1.13764678e-04, -5.36143302e-05, -1.23609267e-05,\n",
+       "          1.02141338e-16]),\n",
+       "  array([ 2.44155072e-06, -4.75161756e-17,  1.00332583e+00, -3.33374057e-17,\n",
+       "         -7.56012005e-07, -2.17777906e-19,  1.00000000e+00,  9.32957088e-16,\n",
+       "          3.29337228e-15,  8.12723180e-04,  3.99131906e-04,  1.09565549e-04,\n",
+       "         -4.09899811e-16, -4.45806207e-06, -8.79719962e-17, -1.93874052e-01,\n",
+       "         -1.58701054e-15, -3.59068977e-05,  9.88861074e-18, -1.07411979e-16,\n",
+       "         -2.97132895e-16, -1.09959112e-04, -5.13961505e-05, -1.13739482e-05,\n",
+       "          1.05572180e-16]),\n",
+       "  array([ 2.43735832e-06, -4.76158598e-17,  1.00313679e+00, -3.40951703e-17,\n",
+       "         -7.73164925e-07, -2.12651236e-19,  1.00000000e+00,  9.32847019e-16,\n",
+       "          3.29310557e-15,  8.12616863e-04,  3.99082632e-04,  1.09555119e-04,\n",
+       "         -4.09790938e-16, -4.48147633e-06, -8.69365506e-17, -1.89041857e-01,\n",
+       "         -1.51552931e-15, -3.43058395e-05,  1.02533431e-17, -1.10069001e-16,\n",
+       "         -2.66713318e-16, -1.06316545e-04, -4.92736805e-05, -1.04300451e-05,\n",
+       "          1.08872430e-16]),\n",
+       "  array([ 2.43314152e-06, -4.77144656e-17,  1.00295254e+00, -3.48176360e-17,\n",
+       "         -7.89526798e-07, -2.07376740e-19,  1.00000000e+00,  9.32734369e-16,\n",
+       "          3.29286805e-15,  8.12514030e-04,  3.99035388e-04,  1.09545591e-04,\n",
+       "         -4.09678895e-16, -4.50473193e-06, -8.59084051e-17, -1.84253177e-01,\n",
+       "         -1.44493128e-15, -3.27237460e-05,  1.05489935e-17, -1.12649596e-16,\n",
+       "         -2.37521031e-16, -1.02832886e-04, -4.72444649e-05, -9.52808456e-06,\n",
+       "          1.12043337e-16]),\n",
+       "  array([ 2.42889994e-06, -4.78119766e-17,  1.00277303e+00, -3.55052764e-17,\n",
+       "         -8.05107775e-07, -2.01987531e-19,  1.00000000e+00,  9.32619214e-16,\n",
+       "          3.29265851e-15,  8.12414526e-04,  3.98990082e-04,  1.09536924e-04,\n",
+       "         -4.09563810e-16, -4.52783241e-06, -8.48873990e-17, -1.79509227e-01,\n",
+       "         -1.37528087e-15, -3.11619541e-05,  1.07784183e-17, -1.15155025e-16,\n",
+       "         -2.09544472e-16, -9.95041564e-05, -4.53061319e-05, -8.66698694e-06,\n",
+       "          1.15084951e-16]),\n",
+       "  array([ 2.42463323e-06, -4.79083776e-17,  1.00259822e+00, -3.61585937e-17,\n",
+       "         -8.19918603e-07, -1.96515131e-19,  1.00000000e+00,  9.32501627e-16,\n",
+       "          3.29247573e-15,  8.12318200e-04,  3.98946625e-04,  1.09529079e-04,\n",
+       "         -4.09445814e-16, -4.55078140e-06, -8.38733629e-17, -1.74811138e-01,\n",
+       "         -1.30663455e-15, -2.96216555e-05,  1.09447994e-17, -1.17586869e-16,\n",
+       "         -1.82776628e-16, -9.63264849e-05, -4.34563883e-05, -7.84572239e-06,\n",
+       "          1.17996253e-16]),\n",
+       "  array([ 2.42034108e-06, -4.80036546e-17,  1.00242806e+00, -3.67781144e-17,\n",
+       "         -8.33970555e-07, -1.90989349e-19,  1.00000000e+00,  9.32381680e-16,\n",
+       "          3.29231851e-15,  8.12224904e-04,  3.98904932e-04,  1.09522015e-04,\n",
+       "         -4.09325038e-16, -4.57358265e-06, -8.28661216e-17, -1.70159969e-01,\n",
+       "         -1.23904136e-15, -2.81039042e-05,  1.10515636e-17, -1.19947001e-16,\n",
+       "         -1.57214388e-16, -9.32960980e-05, -4.16930142e-05, -7.06330753e-06,\n",
+       "          1.20775291e-16]),\n",
+       "  array([ 2.41602318e-06, -4.80977949e-17,  1.00226250e+00, -3.73643861e-17,\n",
+       "         -8.47275367e-07, -1.85438184e-19,  1.00000000e+00,  9.32259443e-16,\n",
+       "          3.29218566e-15,  8.12134494e-04,  3.98864918e-04,  1.09515696e-04,\n",
+       "         -4.09201619e-16, -4.59623996e-06, -8.18654964e-17, -1.65556700e-01,\n",
+       "         -1.17254337e-15, -2.66096244e-05,  1.11023298e-17, -1.22237523e-16,\n",
+       "         -1.32857894e-16, -9.04093145e-05, -4.00138580e-05, -6.31880167e-06,\n",
+       "          1.23419327e-16]),\n",
+       "  array([ 2.41167927e-06, -4.81907868e-17,  1.00210150e+00, -3.79179742e-17,\n",
+       "         -8.59845176e-07, -1.79887747e-19,  1.00000000e+00,  9.32134982e-16,\n",
+       "          3.29207595e-15,  8.12046832e-04,  3.98826501e-04,  1.09510085e-04,\n",
+       "         -4.09075694e-16, -4.61875712e-06, -8.08713073e-17, -1.61002241e-01,\n",
+       "         -1.10717618e-15, -2.51396184e-05,  1.11008727e-17, -1.24460695e-16,\n",
+       "         -1.09709877e-16, -8.76625371e-05, -3.84168302e-05, -5.61130299e-06,\n",
+       "          1.25924979e-16]),\n",
+       "  array([ 2.40730911e-06, -4.82826200e-17,  1.00194500e+00, -3.84394589e-17,\n",
+       "         -8.71692463e-07, -1.74362191e-19,  1.00000000e+00,  9.32008363e-16,\n",
+       "          3.29198817e-15,  8.11961780e-04,  3.98789602e-04,  1.09505145e-04,\n",
+       "         -4.08947406e-16, -4.64113791e-06, -7.98833754e-17, -1.56497430e-01,\n",
+       "         -1.04296934e-15, -2.36945737e-05,  1.10511096e-17, -1.26618830e-16,\n",
+       "         -8.77749978e-17, -8.50522449e-05, -3.68998976e-05, -4.93994450e-06,\n",
+       "          1.28288370e-16]),\n",
+       "  array([ 2.40291249e-06, -4.83732849e-17,  1.00179296e+00, -3.89294323e-17,\n",
+       "         -8.82829999e-07, -1.68883628e-19,  1.00000000e+00,  9.31879649e-16,\n",
+       "          3.29192111e-15,  8.11879205e-04,  3.98754140e-04,  1.09500841e-04,\n",
+       "         -4.08816900e-16, -4.66338602e-06, -7.89015239e-17, -1.52043038e-01,\n",
+       "         -9.79946836e-16, -2.22750710e-05,  1.09571250e-17, -1.28714158e-16,\n",
+       "         -6.70591902e-17, -8.25749852e-05, -3.54610776e-05, -4.30388997e-06,\n",
+       "          1.30505273e-16]),\n",
+       "  array([ 2.39848921e-06, -4.84627733e-17,  1.00164532e+00, -3.93884961e-17,\n",
+       "         -8.93270794e-07, -1.63472630e-19,  1.00000000e+00,  9.31748899e-16,\n",
+       "          3.29187354e-15,  8.11798977e-04,  3.98720042e-04,  1.09497139e-04,\n",
+       "         -4.08684329e-16, -4.68550505e-06, -7.79255802e-17, -1.47639767e-01,\n",
+       "         -9.18127522e-16, -2.08815910e-05,  1.08219933e-17, -1.30750232e-16,\n",
+       "         -4.75690259e-17, -8.02273657e-05, -3.40984317e-05, -3.70232977e-06,\n",
+       "          1.32571243e-16]),\n",
+       "  array([ 2.39403910e-06, -4.85510779e-17,  1.00150203e+00, -3.98172588e-17,\n",
+       "         -9.03028055e-07, -1.58147496e-19,  1.00000000e+00,  9.31616170e-16,\n",
+       "          3.29184423e-15,  8.11720971e-04,  3.98687232e-04,  1.09494005e-04,\n",
+       "         -4.08549847e-16, -4.70749851e-06, -7.69553772e-17, -1.43288258e-01,\n",
+       "         -8.57525545e-16, -1.95145223e-05,  1.06502647e-17, -1.32728676e-16,\n",
+       "         -2.93110951e-17, -7.80060467e-05, -3.28100597e-05, -3.13447676e-06,\n",
+       "          1.34481803e-16]),\n",
+       "  array([ 2.38956201e-06, -4.86381925e-17,  1.00136304e+00, -4.02163342e-17,\n",
+       "         -9.12115139e-07, -1.52924629e-19,  1.00000000e+00,  9.31481518e-16,\n",
+       "          3.29183194e-15,  8.11645063e-04,  3.98655638e-04,  1.09491405e-04,\n",
+       "         -4.08413615e-16, -4.72936972e-06, -7.59907542e-17, -1.38989085e-01,\n",
+       "         -7.98150771e-16, -1.81741679e-05,  1.04457328e-17, -1.34651946e-16,\n",
+       "         -1.22914076e-17, -7.59077334e-05, -3.15940937e-05, -2.59956221e-06,\n",
+       "          1.36232516e-16]),\n",
+       "  array([ 2.38505783e-06, -4.87241116e-17,  1.00122830e+00, -4.05863388e-17,\n",
+       "         -9.20545516e-07, -1.47818381e-19,  1.00000000e+00,  9.31344996e-16,\n",
+       "          3.29183543e-15,  8.11571134e-04,  3.98625189e-04,  1.09489308e-04,\n",
+       "         -4.08275796e-16, -4.75112186e-06, -7.50315581e-17, -1.34742766e-01,\n",
+       "         -7.40009182e-16, -1.68607524e-05,  1.02124924e-17, -1.36521903e-16,\n",
+       "          3.48516520e-18, -7.39291684e-05, -3.04486925e-05, -2.09683184e-06,\n",
+       "          1.37819150e-16]),\n",
+       "  array([ 2.38052644e-06, -4.88088309e-17,  1.00109775e+00, -4.09278905e-17,\n",
+       "         -9.28332730e-07, -1.42841295e-19,  1.00000000e+00,  9.31206656e-16,\n",
+       "          3.29185344e-15,  8.11499067e-04,  3.98595817e-04,  1.09487683e-04,\n",
+       "         -4.08136558e-16, -4.77275794e-06, -7.40776441e-17, -1.30549757e-01,\n",
+       "         -6.83103278e-16, -1.55744285e-05,  9.95416775e-18, -1.38340727e-16,\n",
+       "          1.80154161e-17, -7.20671249e-05, -2.93720358e-05, -1.62554190e-06,\n",
+       "          1.39237780e-16]),\n",
+       "  array([ 2.37596777e-06, -4.88923469e-17,  1.00097134e+00, -4.12416067e-17,\n",
+       "         -9.35490372e-07, -1.38004090e-19,  1.00000000e+00,  9.31066546e-16,\n",
+       "          3.29188474e-15,  8.11428749e-04,  3.98567455e-04,  1.09486498e-04,\n",
+       "         -4.07996073e-16, -4.79428075e-06, -7.31288765e-17, -1.26410457e-01,\n",
+       "         -6.27432451e-16, -1.43152839e-05,  9.67440742e-18, -1.40110231e-16,\n",
+       "          3.12982843e-17, -7.03183997e-05, -2.83623190e-05, -1.18495556e-06,\n",
+       "          1.40484915e-16]),\n",
+       "  array([ 2.37138174e-06, -4.89746568e-17,  1.00084901e+00, -4.15281034e-17,\n",
+       "         -9.42032045e-07, -1.33315727e-19,  1.00000000e+00,  9.30924714e-16,\n",
+       "          3.29192808e-15,  8.11360069e-04,  3.98540037e-04,  1.09485723e-04,\n",
+       "         -4.07854515e-16, -4.81569292e-06, -7.21851292e-17, -1.22325212e-01,\n",
+       "         -5.72993351e-16, -1.30833469e-05,  9.37672190e-18, -1.41832021e-16,\n",
+       "          4.33352943e-17, -6.86798074e-05, -2.74177485e-05, -7.74339370e-07,\n",
+       "          1.41557592e-16]),\n",
+       "  array([ 2.36676832e-06, -4.90557589e-17,  1.00073072e+00, -4.17879935e-17,\n",
+       "         -9.47971342e-07, -1.28783442e-19,  1.00000000e+00,  9.30781206e-16,\n",
+       "          3.29198221e-15,  8.11292921e-04,  3.98513501e-04,  1.09485330e-04,\n",
+       "         -4.07712062e-16, -4.83699682e-06, -7.12462860e-17, -1.18294315e-01,\n",
+       "         -5.19780238e-16, -1.18785932e-05,  9.06456604e-18, -1.43507353e-16,\n",
+       "          5.41309463e-17, -6.71481745e-05, -2.65365366e-05, -3.92960010e-07,\n",
+       "          1.42453473e-16]),\n",
+       "  array([ 2.36212748e-06, -4.91356521e-17,  1.00061640e+00, -4.20218862e-17,\n",
+       "         -9.53321818e-07, -1.24412856e-19,  1.00000000e+00,  9.30636069e-16,\n",
+       "          3.29204590e-15,  8.11227200e-04,  3.98487784e-04,  1.09485290e-04,\n",
+       "         -4.07568891e-16, -4.85819463e-06, -7.03122414e-17, -1.14318005e-01,\n",
+       "         -4.67785319e-16, -1.07009513e-05,  8.74116901e-18, -1.45137321e-16,\n",
+       "          6.36930546e-17, -6.57203347e-05, -2.57168979e-05, -4.00813170e-08,\n",
+       "          1.43170922e-16]),\n",
+       "  array([ 2.35745921e-06, -4.92143362e-17,  1.00050600e+00, -4.22303857e-17,\n",
+       "         -9.58096972e-07, -1.20208035e-19,  1.00000000e+00,  9.30489346e-16,\n",
+       "          3.29211793e-15,  8.11162807e-04,  3.98462827e-04,  1.09485575e-04,\n",
+       "         -4.07425182e-16, -4.87928831e-06, -6.93829002e-17, -1.10396474e-01,\n",
+       "         -4.16999067e-16, -9.55030819e-06,  8.40963723e-18, -1.46722698e-16,\n",
+       "          7.20330332e-17, -6.43931240e-05, -2.49570451e-05,  2.85038442e-07,\n",
+       "          1.43709075e-16]),\n",
+       "  array([ 2.35276351e-06, -4.92918115e-17,  1.00039947e+00, -4.24140910e-17,\n",
+       "         -9.62310229e-07, -1.16171559e-19,  1.00000000e+00,  9.30341082e-16,\n",
+       "          3.29219710e-15,  8.11099644e-04,  3.98438571e-04,  1.09486158e-04,\n",
+       "         -4.07281114e-16, -4.90027958e-06, -6.84581780e-17, -1.06529864e-01,\n",
+       "         -3.67410526e-16, -8.42651475e-06,  8.07294913e-18, -1.48263929e-16,\n",
+       "          7.91661270e-17, -6.31633774e-05, -2.42551858e-05,  5.83148977e-07,\n",
+       "          1.44067902e-16]),\n",
+       "  array([ 2.34804041e-06, -4.93680793e-17,  1.00029675e+00, -4.25735948e-17,\n",
+       "         -9.65974924e-07, -1.12304678e-19,  1.00000000e+00,  9.30191321e-16,\n",
+       "          3.29228221e-15,  8.11037616e-04,  3.98414962e-04,  1.09487013e-04,\n",
+       "         -4.07136866e-16, -4.92116994e-06, -6.75380012e-17, -1.02718273e-01,\n",
+       "         -3.19007598e-16, -7.32939076e-06,  7.73375840e-18, -1.49761377e-16,\n",
+       "          8.51115875e-17, -6.20279254e-05, -2.36095200e-05,  8.55010058e-07,\n",
+       "          1.44248245e-16]),\n",
+       "  array([ 2.34328995e-06, -4.94431414e-17,  1.00019779e+00, -4.27094834e-17,\n",
+       "         -9.69104289e-07, -1.08607380e-19,  1.00000000e+00,  9.30040106e-16,\n",
+       "          3.29237210e-15,  8.10976632e-04,  3.98391944e-04,  1.09488115e-04,\n",
+       "         -4.06992614e-16, -4.94196067e-06, -6.66223072e-17, -9.89617542e-02,\n",
+       "         -2.71777309e-16, -6.25872969e-06,  7.39459085e-18, -1.51215068e-16,\n",
+       "          8.98927920e-17, -6.09835920e-05, -2.30182375e-05,  1.10139327e-06,\n",
+       "          1.44251863e-16]),\n",
+       "  array([ 2.33851218e-06, -4.95170002e-17,  1.00010253e+00, -4.28223365e-17,\n",
+       "         -9.71711441e-07, -1.05078463e-19,  1.00000000e+00,  9.29887481e-16,\n",
+       "          3.29246564e-15,  8.10916605e-04,  3.98369464e-04,  1.09489438e-04,\n",
+       "         -4.06848532e-16, -4.96265281e-06, -6.57110437e-17, -9.52603164e-02,\n",
+       "         -2.25706063e-16, -5.21430314e-06,  7.05783035e-18, -1.52624717e-16,\n",
+       "          9.35373092e-17, -6.00271929e-05, -2.24795162e-05,  1.32308343e-06,\n",
+       "          1.44081444e-16]),\n",
+       "  array([ 2.33370717e-06, -4.95896589e-17,  1.00001092e+00, -4.29127264e-17,\n",
+       "         -9.73809373e-07, -1.01715660e-19,  1.00000000e+00,  9.29733491e-16,\n",
+       "          3.29256172e-15,  8.10857450e-04,  3.98347473e-04,  1.09490959e-04,\n",
+       "         -4.06704792e-16, -4.98324719e-06, -6.48041693e-17, -9.16139289e-02,\n",
+       "         -1.80779870e-16, -4.19586507e-06,  6.72560177e-18, -1.53989888e-16,\n",
+       "          9.60769101e-17, -5.91555341e-05, -2.19915210e-05,  1.52087963e-06,\n",
+       "          1.43740622e-16]),\n",
+       "  array([ 2.32887500e-06, -4.96611212e-17,  9.99922895e-01, -4.29812187e-17,\n",
+       "         -9.75410951e-07, -9.85157332e-20,  1.00000000e+00,  9.29578181e-16,\n",
+       "          3.29265926e-15,  8.10799084e-04,  3.98325920e-04,  1.09492654e-04,\n",
+       "         -4.06561558e-16, -5.00374443e-06, -6.39016528e-17, -8.80225212e-02,\n",
+       "         -1.36984552e-16, -3.20315559e-06,  6.39985038e-18, -1.55309910e-16,\n",
+       "          9.75475257e-17, -5.83654122e-05, -2.15524029e-05,  1.69559597e-06,\n",
+       "          1.43233969e-16]),\n",
+       "  array([ 2.32401576e-06, -4.97313913e-17,  9.99838409e-01, -4.30283717e-17,\n",
+       "         -9.76528903e-07, -9.54746108e-20,  1.00000000e+00,  9.29421597e-16,\n",
+       "          3.29275725e-15,  8.10741431e-04,  3.98304760e-04,  1.09494502e-04,\n",
+       "         -4.06418991e-16, -5.02414491e-06, -6.30034732e-17, -8.44859849e-02,\n",
+       "         -9.43059415e-17, -2.23590446e-06,  6.08224067e-18, -1.56584028e-16,\n",
+       "          9.79891550e-17, -5.76536143e-05, -2.11602989e-05,  1.84806193e-06,\n",
+       "          1.42566983e-16]),\n",
+       "  array([ 2.31912957e-06, -4.98004740e-17,  9.99757405e-01, -4.30547367e-17,\n",
+       "         -9.77175820e-07, -9.25874392e-20,  1.00000000e+00,  9.29263786e-16,\n",
+       "          3.29285470e-15,  8.10684414e-04,  3.98283947e-04,  1.09496482e-04,\n",
+       "         -4.06277245e-16, -5.04444883e-06, -6.21096193e-17, -8.10041753e-02,\n",
+       "         -5.27300373e-17, -1.29383429e-06,  5.77433898e-18, -1.57811199e-16,\n",
+       "          9.74457243e-17, -5.70169192e-05, -2.08133321e-05,  1.97912238e-06,\n",
+       "          1.41746071e-16]),\n",
+       "  array([ 2.31421654e-06, -4.98683746e-17,  9.99679828e-01, -4.30608583e-17,\n",
+       "         -9.77364152e-07, -8.98487325e-20,  1.00000000e+00,  9.29104796e-16,\n",
+       "          3.29295066e-15,  8.10627962e-04,  3.98263437e-04,  1.09498571e-04,\n",
+       "         -4.06136466e-16, -5.06465619e-06, -6.12200895e-17, -7.75769131e-02,\n",
+       "         -1.22431564e-17, -3.76663298e-07,  5.47740915e-18, -1.58990380e-16,\n",
+       "          9.59649018e-17, -5.64520991e-05, -2.05096126e-05,  2.08963729e-06,\n",
+       "          1.40778502e-16]),\n",
+       "  array([ 2.30927681e-06, -4.99350991e-17,  9.99605624e-01, -4.30472743e-17,\n",
+       "         -9.77106206e-07, -8.72524173e-20,  1.00000000e+00,  9.28944675e-16,\n",
+       "          3.29304426e-15,  8.10572006e-04,  3.98243190e-04,  1.09500752e-04,\n",
+       "         -4.05996794e-16, -5.08476677e-06, -6.03348913e-17, -7.42039855e-02,\n",
+       "          2.71679472e-17,  5.15892239e-07,  5.19262609e-18, -1.60120288e-16,\n",
+       "          9.35978705e-17, -5.59559214e-05, -2.02472388e-05,  2.18048112e-06,\n",
+       "          1.39672376e-16]),\n",
+       "  array([ 2.30431050e-06, -5.00006536e-17,  9.99534739e-01, -4.30145163e-17,\n",
+       "         -9.76414148e-07, -8.47919794e-20,  1.00000000e+00,  9.28783476e-16,\n",
+       "          3.29313466e-15,  8.10516481e-04,  3.98223165e-04,  1.09503004e-04,\n",
+       "         -4.05858357e-16, -5.10478019e-06, -5.94540411e-17, -7.08851484e-02,\n",
+       "          6.55159826e-17,  1.38411591e-06,  4.92087144e-18, -1.61199701e-16,\n",
+       "          9.03990625e-17, -5.55251519e-05, -2.00242986e-05,  2.25254187e-06,\n",
+       "          1.38436559e-16]),\n",
+       "  array([ 2.29931778e-06, -5.00650450e-17,  9.99467119e-01, -4.29631098e-17,\n",
+       "         -9.75300003e-07, -8.24606662e-20,  1.00000000e+00,  9.28621248e-16,\n",
+       "          3.29322109e-15,  8.10461324e-04,  3.98203327e-04,  1.09505311e-04,\n",
+       "         -4.05721277e-16, -5.12469588e-06, -5.85775636e-17, -6.76201273e-02,\n",
+       "          1.02813046e-16,  2.22828947e-06,  4.66262181e-18, -1.62227633e-16,\n",
+       "          8.64258581e-17, -5.51565579e-05, -1.98388722e-05,  2.30671990e-06,\n",
+       "          1.37080629e-16]),\n",
+       "  array([ 2.29429880e-06, -5.01282804e-17,  9.99402710e-01, -4.28935745e-17,\n",
+       "         -9.73775658e-07, -8.02513545e-20,  1.00000000e+00,  9.28458045e-16,\n",
+       "          3.29330283e-15,  8.10406477e-04,  3.98183638e-04,  1.09507655e-04,\n",
+       "         -4.05585662e-16, -5.14451311e-06, -5.77054916e-17, -6.44086186e-02,\n",
+       "          1.39070568e-16,  3.04869154e-06,  4.41861885e-18, -1.63202527e-16,\n",
+       "          8.17382557e-17, -5.48469116e-05, -1.96890336e-05,  2.34392646e-06,\n",
+       "          1.35614816e-16]),\n",
+       "  array([ 2.28925374e-06, -5.01903674e-17,  9.99341460e-01, -4.28064249e-17,\n",
+       "         -9.71852859e-07, -7.81566516e-20,  1.00000000e+00,  9.28293923e-16,\n",
+       "          3.29337922e-15,  8.10351884e-04,  3.98164065e-04,  1.09510020e-04,\n",
+       "         -4.05451612e-16, -5.16423098e-06, -5.68378652e-17, -6.12502919e-02,\n",
+       "          1.74299287e-16,  3.84559662e-06,  4.18940095e-18, -1.64122885e-16,\n",
+       "          7.63985176e-17, -5.45929944e-05, -1.95728541e-05,  2.36508199e-06,\n",
+       "          1.34049913e-16]),\n",
+       "  array([ 2.28418278e-06, -5.02513140e-17,  9.99283315e-01, -4.27021703e-17,\n",
+       "         -9.69543222e-07, -7.61691263e-20,  1.00000000e+00,  9.28128935e-16,\n",
+       "          3.29344969e-15,  8.10297492e-04,  3.98144576e-04,  1.09512391e-04,\n",
+       "         -4.05319215e-16, -5.18384844e-06, -5.59747318e-17, -5.81447904e-02,\n",
+       "          2.08509235e-16,  4.61927451e-06,  3.97504566e-18, -1.64987629e-16,\n",
+       "          7.04707914e-17, -5.43916013e-05, -1.94884049e-05,  2.37111417e-06,\n",
+       "          1.32397192e-16]),\n",
+       "  array([ 2.27908609e-06, -5.03111286e-17,  9.99228223e-01, -4.25813154e-17,\n",
+       "         -9.66858227e-07, -7.42813550e-20,  1.00000000e+00,  9.27963139e-16,\n",
+       "          3.29351372e-15,  8.10243253e-04,  3.98125143e-04,  1.09514754e-04,\n",
+       "         -4.05188546e-16, -5.20336431e-06, -5.51161454e-17, -5.50917329e-02,\n",
+       "          2.41709755e-16,  5.36999005e-06,  3.77553767e-18, -1.65795678e-16,\n",
+       "          6.40207129e-17, -5.42395454e-05, -1.94337605e-05,  2.36295584e-06,\n",
+       "          1.30668337e-16]),\n",
+       "  array([ 2.27396389e-06, -5.03698198e-17,  9.99176133e-01, -4.24443606e-17,\n",
+       "         -9.63809225e-07, -7.24859807e-20,  1.00000000e+00,  9.27796593e-16,\n",
+       "          3.29357083e-15,  8.10189119e-04,  3.98105736e-04,  1.09517096e-04,\n",
+       "         -4.05059671e-16, -5.22277726e-06, -5.42621658e-17, -5.20907148e-02,\n",
+       "          2.73909537e-16,  6.09800324e-06,  3.59074339e-18, -1.66546014e-16,\n",
+       "          5.71149984e-17, -5.41336630e-05, -1.94070021e-05,  2.34154271e-06,\n",
+       "          1.28875349e-16]),\n",
+       "  array([ 2.26881636e-06, -5.04273967e-17,  9.99126991e-01, -4.22918023e-17,\n",
+       "         -9.60407441e-07, -7.07757707e-20,  1.00000000e+00,  9.27629356e-16,\n",
+       "          3.29362065e-15,  8.10135048e-04,  3.98086329e-04,  1.09519403e-04,\n",
+       "         -4.04932641e-16, -5.24208587e-06, -5.34128588e-17, -4.91413098e-02,\n",
+       "          3.05116670e-16,  6.80356966e-06,  3.42041456e-18, -1.67237720e-16,\n",
+       "          4.98210288e-17, -5.40708184e-05, -1.94062215e-05,  2.30781098e-06,\n",
+       "          1.27030456e-16]),\n",
+       "  array([ 2.26364372e-06, -5.04838687e-17,  9.99080748e-01, -4.21241329e-17,\n",
+       "         -9.56663970e-07, -6.91436583e-20,  1.00000000e+00,  9.27461486e-16,\n",
+       "          3.29366286e-15,  8.10081001e-04,  3.98066900e-04,  1.09521666e-04,\n",
+       "         -4.04807495e-16, -5.26128858e-06, -5.25682951e-17, -4.62430707e-02,\n",
+       "          3.35338716e-16,  7.48694118e-06,  3.26421946e-18, -1.67869972e-16,\n",
+       "          4.22064294e-17, -5.40479092e-05, -1.94295246e-05,  2.26269478e-06,\n",
+       "          1.25146019e-16]),\n",
+       "  array([ 2.25844619e-06, -5.05392453e-17,  9.99037353e-01, -4.19418415e-17,\n",
+       "         -9.52589786e-07, -6.75827494e-20,  1.00000000e+00,  9.27293044e-16,\n",
+       "          3.29369720e-15,  8.10026939e-04,  3.98047425e-04,  1.09523873e-04,\n",
+       "         -4.04684260e-16, -5.28038373e-06, -5.17285499e-17, -4.33955312e-02,\n",
+       "          3.64582799e-16,  8.14836701e-06,  3.12181217e-18, -1.68441988e-16,\n",
+       "          3.43386504e-17, -5.40618717e-05, -1.94750353e-05,  2.20712363e-06,\n",
+       "          1.23234444e-16]),\n",
+       "  array([ 2.25322399e-06, -5.05935366e-17,  9.98996754e-01, -4.17454137e-17,\n",
+       "         -9.48195739e-07, -6.60867397e-20,  1.00000000e+00,  9.27124090e-16,\n",
+       "          3.29372348e-15,  8.09972829e-04,  3.98027884e-04,  1.09526015e-04,\n",
+       "         -4.04562952e-16, -5.29936960e-06, -5.08937028e-17, -4.05982067e-02,\n",
+       "          3.92855710e-16,  8.78809492e-06,  2.99201392e-18, -1.68954103e-16,\n",
+       "          2.62845472e-17, -5.41096855e-05, -1.95408995e-05,  2.14201981e-06,\n",
+       "          1.21308077e-16]),\n",
+       "  array([ 2.24797735e-06, -5.06467526e-17,  9.98958904e-01, -4.15353317e-17,\n",
+       "         -9.43492553e-07, -6.46495279e-20,  1.00000000e+00,  9.26954684e-16,\n",
+       "          3.29374159e-15,  8.09918641e-04,  3.98008259e-04,  1.09528084e-04,\n",
+       "         -4.04443573e-16, -5.31824434e-06, -5.00638368e-17, -3.78505959e-02,\n",
+       "          4.20164026e-16,  9.40637280e-06,  2.87441775e-18, -1.69405760e-16,\n",
+       "          1.81099723e-17, -5.41883791e-05, -1.96252891e-05,  2.06829565e-06,\n",
+       "          1.19379148e-16]),\n",
+       "  array([ 2.24270650e-06, -5.06989039e-17,  9.98923752e-01, -4.13120745e-17,\n",
+       "         -9.38490827e-07, -6.32654118e-20,  1.00000000e+00,  9.26784887e-16,\n",
+       "          3.29375147e-15,  8.09864346e-04,  3.97988532e-04,  1.09530070e-04,\n",
+       "         -4.04326113e-16, -5.33700607e-06, -4.92390380e-17, -3.51521816e-02,\n",
+       "          4.46514243e-16,  1.00034503e-05,  2.76822649e-18, -1.69797023e-16,\n",
+       "          9.87938253e-18, -5.42950350e-05, -1.97264054e-05,  1.98685095e-06,\n",
+       "          1.17459644e-16]),\n",
+       "  array([ 2.23741168e-06, -5.07500011e-17,  9.98891249e-01, -4.10761181e-17,\n",
+       "         -9.33201037e-07, -6.19291166e-20,  1.00000000e+00,  9.26614759e-16,\n",
+       "          3.29375313e-15,  8.09809919e-04,  3.97968690e-04,  1.09531969e-04,\n",
+       "         -4.04210552e-16, -5.35565283e-06, -4.84193950e-17, -3.25024325e-02,\n",
+       "          4.71912911e-16,  1.05795808e-05,  2.67258460e-18, -1.70128177e-16,\n",
+       "          1.65545437e-18, -5.44267940e-05, -1.98424834e-05,  1.89857036e-06,\n",
+       "          1.15561245e-16]),\n",
+       "  array([ 2.23209314e-06, -5.08000551e-17,  9.98861348e-01, -4.08279347e-17,\n",
+       "         -9.27633525e-07, -6.06358167e-20,  1.00000000e+00,  9.26444359e-16,\n",
+       "          3.29374662e-15,  8.09755338e-04,  3.97948718e-04,  1.09533773e-04,\n",
+       "         -4.04096857e-16, -5.37418262e-06, -4.76049986e-17, -2.99008037e-02,\n",
+       "          4.96366784e-16,  1.11350233e-05,  2.58659385e-18, -1.70399730e-16,\n",
+       "         -6.50127864e-18, -5.45808603e-05, -1.99717950e-05,  1.80432078e-06,\n",
+       "          1.13695232e-16]),\n",
+       "  array([ 2.22675112e-06, -5.08490770e-17,  9.98834002e-01, -4.05679932e-17,\n",
+       "         -9.21798503e-07, -5.93811566e-20,  1.00000000e+00,  9.26273746e-16,\n",
+       "          3.29373209e-15,  8.09700583e-04,  3.97928605e-04,  1.09535478e-04,\n",
+       "         -4.03984984e-16, -5.39259338e-06, -4.67959412e-17, -2.73467381e-02,\n",
+       "          5.19882973e-16,  1.16700445e-05,  2.50931445e-18, -1.70612430e-16,\n",
+       "         -1.45327682e-17, -5.47545057e-05, -2.01126528e-05,  1.70494896e-06,\n",
+       "          1.11872415e-16]),\n",
+       "  array([ 2.22138588e-06, -5.08970779e-17,  9.98809162e-01, -4.02967587e-17,\n",
+       "         -9.15706043e-07, -5.81612732e-20,  1.00000000e+00,  9.26102979e-16,\n",
+       "          3.29370971e-15,  8.09645638e-04,  3.97908342e-04,  1.09537079e-04,\n",
+       "         -4.03874881e-16, -5.41088305e-06, -4.59923163e-17, -2.48396677e-02,\n",
+       "          5.42469097e-16,  1.21849212e-05,  2.43976114e-18, -1.70767293e-16,\n",
+       "         -2.23837700e-17, -5.49450737e-05, -2.02634132e-05,  1.60127913e-06,\n",
+       "          1.10103060e-16]),\n",
+       "  array([ 2.21599767e-06, -5.09440695e-17,  9.98786783e-01, -4.00146919e-17,\n",
+       "         -9.09366071e-07, -5.69728023e-20,  1.00000000e+00,  9.25932114e-16,\n",
+       "          3.29367971e-15,  8.09590488e-04,  3.97887919e-04,  1.09538574e-04,\n",
+       "         -4.03766485e-16, -5.42904951e-06, -4.51942180e-17, -2.23790144e-02,\n",
+       "          5.64133443e-16,  1.26799422e-05,  2.37693617e-18, -1.70865573e-16,\n",
+       "         -3.00021359e-17, -5.51499833e-05, -2.04224797e-05,  1.49411075e-06,\n",
+       "          1.08396818e-16]),\n",
+       "  array([ 2.21058676e-06, -5.09900631e-17,  9.98766819e-01, -3.97222494e-17,\n",
+       "         -9.02788366e-07, -5.58128776e-20,  1.00000000e+00,  9.25761205e-16,\n",
+       "          3.29364237e-15,  8.09535122e-04,  3.97867331e-04,  1.09539958e-04,\n",
+       "         -4.03659722e-16, -5.44709066e-06, -4.44017406e-17, -1.99641915e-02,\n",
+       "          5.84885119e-16,  1.31554107e-05,  2.31984386e-18, -1.70908756e-16,\n",
+       "         -3.73390793e-17, -5.53667323e-05, -2.05883054e-05,  1.38421646e-06,\n",
+       "          1.06762668e-16]),\n",
+       "  array([ 2.20515340e-06, -5.10350705e-17,  9.98749224e-01, -3.94198823e-17,\n",
+       "         -8.95982543e-07, -5.46791252e-20,  1.00000000e+00,  9.25590306e-16,\n",
+       "          3.29359802e-15,  8.09479529e-04,  3.97846572e-04,  1.09541230e-04,\n",
+       "         -4.03554513e-16, -5.46500436e-06, -4.36149780e-17, -1.75946040e-02,\n",
+       "          6.04734200e-16,  1.36116462e-05,  2.26749954e-18, -1.70898560e-16,\n",
+       "         -4.43494093e-17, -5.55929005e-05, -2.07593962e-05,  1.27234014e-06,\n",
+       "          1.05208859e-16]),\n",
+       "  array([ 2.19969787e-06, -5.10791036e-17,  9.98733955e-01, -3.91080363e-17,\n",
+       "         -8.88958050e-07, -5.35696533e-20,  1.00000000e+00,  9.25419469e-16,\n",
+       "          3.29354703e-15,  8.09423703e-04,  3.97825637e-04,  1.09542389e-04,\n",
+       "         -4.03450770e-16, -5.48278851e-06, -4.28340237e-17, -1.52696506e-02,\n",
+       "          6.23691875e-16,  1.40489866e-05,  2.21893876e-18, -1.70836930e-16,\n",
+       "         -5.09917354e-17, -5.58261520e-05, -2.09343122e-05,  1.15919523e-06,\n",
+       "          1.03742862e-16]),\n",
+       "  array([ 2.19422043e-06, -5.11221744e-17,  9.98720966e-01, -3.87871510e-17,\n",
+       "         -8.81724155e-07, -5.24830365e-20,  1.00000000e+00,  9.25248743e-16,\n",
+       "          3.29348980e-15,  8.09367638e-04,  3.97804526e-04,  1.09543435e-04,\n",
+       "         -4.03348399e-16, -5.50044099e-06, -4.20589700e-17, -1.29887238e-02,\n",
+       "          6.41770578e-16,  1.44677904e-05,  2.17322898e-18, -1.70726026e-16,\n",
+       "         -5.72286397e-17, -5.60642379e-05, -2.11116707e-05,  1.04546313e-06,\n",
+       "          1.02371329e-16]),\n",
+       "  array([ 2.18872135e-06, -5.11642948e-17,  9.98710215e-01, -3.84576590e-17,\n",
+       "         -8.74289936e-07, -5.14182926e-20,  1.00000000e+00,  9.25078175e-16,\n",
+       "          3.29342677e-15,  8.09311333e-04,  3.97783235e-04,  1.09544367e-04,\n",
+       "         -4.03247299e-16, -5.51795972e-06, -4.12899077e-17, -1.07512116e-02,\n",
+       "          6.58984116e-16,  1.48684378e-05,  2.12948355e-18, -1.70568210e-16,\n",
+       "         -6.30268164e-17, -5.63049974e-05, -2.12901470e-05,  9.31791916e-07,\n",
+       "          1.01100057e-16]),\n",
+       "  array([ 2.18320090e-06, -5.12054769e-17,  9.98701658e-01, -3.81199851e-17,\n",
+       "         -8.66664269e-07, -5.03748566e-20,  1.00000000e+00,  9.24907809e-16,\n",
+       "          3.29335841e-15,  8.09254787e-04,  3.97761767e-04,  1.09545185e-04,\n",
+       "         -4.03147365e-16, -5.53534263e-06, -4.05269257e-17, -8.55649812e-03,\n",
+       "          6.75347777e-16,  1.52513329e-05,  2.08686796e-18, -1.70366035e-16,\n",
+       "         -6.83571788e-17, -5.65463599e-05, -2.14684763e-05,  8.18795191e-07,\n",
+       "          9.99339618e-17]),\n",
+       "  array([ 2.17765936e-06, -5.12457331e-17,  9.98695254e-01, -3.77745459e-17,\n",
+       "         -8.58855817e-07, -4.93525499e-20,  1.00000000e+00,  9.24737687e-16,\n",
+       "          3.29328522e-15,  8.09198001e-04,  3.97740122e-04,  1.09545892e-04,\n",
+       "         -4.03048488e-16, -5.55258768e-06, -3.97701110e-17, -6.40396450e-03,\n",
+       "          6.90878425e-16,  1.56169046e-05,  2.04461004e-18, -1.70122228e-16,\n",
+       "         -7.31949326e-17, -5.67863450e-05, -2.16454547e-05,  7.07051204e-07,\n",
+       "          9.88770566e-17]),\n",
+       "  array([ 2.17209701e-06, -5.12850754e-17,  9.98690961e-01, -3.74217486e-17,\n",
+       "         -8.50873013e-07, -4.83515459e-20,  1.00000000e+00,  9.24567847e-16,\n",
+       "          3.29320770e-15,  8.09140978e-04,  3.97718302e-04,  1.09546490e-04,\n",
+       "         -4.02950555e-16, -5.56969289e-06, -3.90195480e-17, -4.29299007e-03,\n",
+       "          7.05594584e-16,  1.59656080e-05,  2.00200501e-18, -1.69839679e-16,\n",
+       "         -7.75196168e-17, -5.70230636e-05, -2.18199396e-05,  5.97102164e-07,\n",
+       "          9.79324407e-17]),\n",
+       "  array([ 2.16651412e-06, -5.13235163e-17,  9.98688738e-01, -3.70619903e-17,\n",
+       "         -8.42724051e-07, -4.73723331e-20,  1.00000000e+00,  9.24398326e-16,\n",
+       "          3.29312638e-15,  8.09083723e-04,  3.97696311e-04,  1.09546979e-04,\n",
+       "         -4.02853453e-16, -5.58665630e-06, -3.82753183e-17, -2.22295316e-03,\n",
+       "          7.19516503e-16,  1.62979247e-05,  1.95842340e-18, -1.69521421e-16,\n",
+       "         -8.13151121e-17, -5.72547175e-05, -2.19908503e-05,  4.89453800e-07,\n",
+       "          9.71022925e-17]),\n",
+       "  array([ 2.16091097e-06, -5.13610681e-17,  9.98688545e-01, -3.66956573e-17,\n",
+       "         -8.34416869e-07, -4.64156722e-20,  1.00000000e+00,  9.24229155e-16,\n",
+       "          3.29304181e-15,  8.09026243e-04,  3.97674154e-04,  1.09547364e-04,\n",
+       "         -4.02757065e-16, -5.60347601e-06, -3.75375007e-17, -1.93231957e-04,\n",
+       "          7.32666192e-16,  1.66143640e-05,  1.91332003e-18, -1.69170608e-16,\n",
+       "         -8.45696173e-17, -5.74795992e-05, -2.21571679e-05,  3.84575132e-07,\n",
+       "          9.63878717e-17]),\n",
+       "  array([ 2.15528783e-06, -5.13977430e-17,  9.98690342e-01, -3.63231235e-17,\n",
+       "         -8.25959137e-07, -4.54825559e-20,  1.00000000e+00,  9.24060365e-16,\n",
+       "          3.29295454e-15,  8.08968547e-04,  3.97651836e-04,  1.09547646e-04,\n",
+       "         -4.02661276e-16, -5.62015016e-06, -3.68061707e-17,  1.79679456e-03,\n",
+       "          7.45067457e-16,  1.69154624e-05,  1.86623165e-18, -1.68790506e-16,\n",
+       "         -8.72755951e-17, -5.76960906e-05, -2.23179351e-05,  2.82898482e-07,\n",
+       "          9.57895272e-17]),\n",
+       "  array([ 2.14964500e-06, -5.14335536e-17,  9.98694090e-01, -3.59447506e-17,\n",
+       "         -8.17358245e-07, -4.45741627e-20,  1.00000000e+00,  9.23891980e-16,\n",
+       "          3.29286511e-15,  8.08910644e-04,  3.97629363e-04,  1.09547831e-04,\n",
+       "         -4.02565969e-16, -5.63667696e-06, -3.60814007e-17,  3.74774578e-03,\n",
+       "          7.56745896e-16,  1.72017837e-05,  1.81678620e-18, -1.68384463e-16,\n",
+       "         -8.94296880e-17, -5.79026621e-05, -2.24722554e-05,  1.84819695e-07,\n",
+       "          9.53067129e-17]),\n",
+       "  array([ 2.14398274e-06, -5.14685121e-17,  9.98699750e-01, -3.55608861e-17,\n",
+       "         -8.08621286e-07, -4.36918118e-20,  1.00000000e+00,  9.23724024e-16,\n",
+       "          3.29277408e-15,  8.08852547e-04,  3.97606744e-04,  1.09547922e-04,\n",
+       "         -4.02471031e-16, -5.65305465e-06, -3.53632592e-17,  5.66023859e-03,\n",
+       "          7.67728889e-16,  1.74739189e-05,  1.76470235e-18, -1.67955894e-16,\n",
+       "         -9.10326058e-17, -5.80978706e-05, -2.26192922e-05,  9.06985821e-08,\n",
+       "          9.49380088e-17]),\n",
+       "  array([ 2.13830134e-06, -5.15026310e-17,  9.98707285e-01, -3.51718634e-17,\n",
+       "         -7.99755044e-07, -4.28369167e-20,  1.00000000e+00,  9.23556516e-16,\n",
+       "          3.29268199e-15,  8.08794266e-04,  3.97583986e-04,  1.09547923e-04,\n",
+       "         -4.02376350e-16, -5.66928157e-06, -3.46518116e-17,  7.53488658e-03,\n",
+       "          7.78045555e-16,  1.77324847e-05,  1.70979155e-18, -1.67508256e-16,\n",
+       "         -9.20889852e-17, -5.82803573e-05, -2.27582677e-05,  8.59571987e-10,\n",
+       "          9.46811493e-17]),\n",
+       "  array([ 2.13260108e-06, -5.15359225e-17,  9.98716657e-01, -3.47780000e-17,\n",
+       "         -7.90765982e-07, -4.20109400e-20,  1.00000000e+00,  9.23389471e-16,\n",
+       "          3.29258938e-15,  8.08735817e-04,  3.97561097e-04,  1.09547838e-04,\n",
+       "         -4.02281817e-16, -5.68535609e-06, -3.39471192e-17,  9.37229920e-03,\n",
+       "          7.87726701e-16,  1.79781227e-05,  1.65195575e-18, -1.67045034e-16,\n",
+       "         -9.26072221e-17, -5.84488457e-05, -2.28884612e-05, -8.44074395e-08,\n",
+       "          9.45330543e-17]),\n",
+       "  array([ 2.12688223e-06, -5.15683990e-17,  9.98727830e-01, -3.43795976e-17,\n",
+       "         -7.81660233e-07, -4.12153462e-20,  1.00000000e+00,  9.23222901e-16,\n",
+       "          3.29249678e-15,  8.08677215e-04,  3.97538088e-04,  1.09547674e-04,\n",
+       "         -4.02187327e-16, -5.70127666e-06, -3.32492399e-17,  1.11730810e-02,\n",
+       "          7.96804724e-16,  1.82114981e-05,  1.59119096e-18, -1.66569709e-16,\n",
+       "         -9.25993041e-17, -5.86021383e-05, -2.30092073e-05, -1.64846047e-07,\n",
+       "          9.44898669e-17]),\n",
+       "  array([ 2.12114508e-06, -5.16000729e-17,  9.98740768e-01, -3.39769409e-17,\n",
+       "         -7.72443585e-07, -4.04515577e-20,  1.00000000e+00,  9.23056815e-16,\n",
+       "          3.29240470e-15,  8.08618476e-04,  3.97514968e-04,  1.09547433e-04,\n",
+       "         -4.02092780e-16, -5.71704177e-06, -3.25582279e-17,  1.29378307e-02,\n",
+       "          8.05313497e-16,  1.84332972e-05,  1.52758115e-18, -1.66085744e-16,\n",
+       "         -9.20806167e-17, -5.87391135e-05, -2.31198938e-05, -2.40232118e-07,\n",
+       "          9.45469985e-17]),\n",
+       "  array([ 2.11538991e-06, -5.16309563e-17,  9.98755435e-01, -3.35702967e-17,\n",
+       "         -7.63121472e-07, -3.97209146e-20,  1.00000000e+00,  9.22891219e-16,\n",
+       "          3.29231363e-15,  8.08559617e-04,  3.97491748e-04,  1.09547123e-04,\n",
+       "         -4.01998081e-16, -5.73265000e-06, -3.18741338e-17,  1.46671408e-02,\n",
+       "          8.13288296e-16,  1.86442258e-05,  1.46129150e-18, -1.65596564e-16,\n",
+       "         -9.10696605e-17, -5.88587228e-05, -2.32199596e-05, -3.10372400e-07,\n",
+       "          9.46991816e-17]),\n",
+       "  array([ 2.10961699e-06, -5.16610615e-17,  9.98771797e-01, -3.31599139e-17,\n",
+       "         -7.53698969e-07, -3.90246355e-20,  1.00000000e+00,  9.22726113e-16,\n",
+       "          3.29222404e-15,  8.08500657e-04,  3.97468439e-04,  1.09546748e-04,\n",
+       "         -4.01903140e-16, -5.74809996e-06, -3.11970046e-17,  1.63615963e-02,\n",
+       "          8.20765657e-16,  1.88450066e-05,  1.39256445e-18, -1.65105535e-16,\n",
+       "         -8.95878074e-17, -5.89599862e-05, -2.33088919e-05, -3.75102990e-07,\n",
+       "          9.49405258e-17]),\n",
+       "  array([ 2.10382661e-06, -5.16904006e-17,  9.98789818e-01, -3.27460223e-17,\n",
+       "         -7.44180780e-07, -3.83637701e-20,  1.00000000e+00,  9.22561497e-16,\n",
+       "          3.29213638e-15,  8.08441615e-04,  3.97445053e-04,  1.09546314e-04,\n",
+       "         -4.01807876e-16, -5.76339035e-06, -3.05268838e-17,  1.80217746e-02,\n",
+       "          8.27783235e-16,  1.90363762e-05,  1.32173813e-18, -1.64615915e-16,\n",
+       "         -8.76590181e-17, -5.90419891e-05, -2.33862237e-05, -4.34287649e-07,\n",
+       "          9.52645589e-17]),\n",
+       "  array([ 2.09801903e-06, -5.17189858e-17,  9.98809467e-01, -3.23288326e-17,\n",
+       "         -7.34571239e-07, -3.77391861e-20,  1.00000000e+00,  9.22397367e-16,\n",
+       "          3.29205107e-15,  8.08382512e-04,  3.97421602e-04,  1.09545826e-04,\n",
+       "         -4.01712211e-16, -5.77851990e-06, -2.98638121e-17,  1.96482439e-02,\n",
+       "          8.34379440e-16,  1.92190821e-05,  1.24917643e-18, -1.64130910e-16,\n",
+       "         -8.53098202e-17, -5.91038778e-05, -2.34515309e-05, -4.87816006e-07,\n",
+       "          9.56642985e-17]),\n",
+       "  array([ 2.09219455e-06, -5.17468291e-17,  9.98830708e-01, -3.19085358e-17,\n",
+       "         -7.24874300e-07, -3.71515076e-20,  1.00000000e+00,  9.22233713e-16,\n",
+       "          3.29196850e-15,  8.08323367e-04,  3.97398097e-04,  1.09545290e-04,\n",
+       "         -4.01616079e-16, -5.79348739e-06, -2.92078266e-17,  2.12415636e-02,\n",
+       "          8.40593579e-16,  1.93938796e-05,  1.17536652e-18, -1.63653524e-16,\n",
+       "         -8.25685883e-17, -5.91448555e-05, -2.35044292e-05, -5.35601646e-07,\n",
+       "          9.61322982e-17]),\n",
+       "  array([ 2.08635342e-06, -5.17739426e-17,  9.98853510e-01, -3.14853031e-17,\n",
+       "         -7.15093535e-07, -3.66011164e-20,  1.00000000e+00,  9.22070526e-16,\n",
+       "          3.29188904e-15,  8.08264203e-04,  3.97374553e-04,  1.09544713e-04,\n",
+       "         -4.01519418e-16, -5.80829168e-06, -2.85589619e-17,  2.28022828e-02,\n",
+       "          8.46465343e-16,  1.95615282e-05,  1.10079300e-18, -1.63186691e-16,\n",
+       "         -7.94656717e-17, -5.91641775e-05, -2.35445710e-05, -5.77580108e-07,\n",
+       "          9.66607306e-17]),\n",
+       "  array([ 2.08049593e-06, -5.18003381e-17,  9.98877841e-01, -3.10592857e-17,\n",
+       "         -7.05232141e-07, -3.60881189e-20,  1.00000000e+00,  9.21907793e-16,\n",
+       "          3.29181301e-15,  8.08205041e-04,  3.97350981e-04,  1.09544099e-04,\n",
+       "         -4.01422177e-16, -5.82293164e-06, -2.79172499e-17,  2.43309396e-02,\n",
+       "          8.52034788e-16,  1.97227879e-05,  1.02600673e-18, -1.62733153e-16,\n",
+       "         -7.60328342e-17, -5.91611473e-05, -2.35716423e-05, -6.13706812e-07,\n",
+       "          9.72414412e-17]),\n",
+       "  array([ 2.07462235e-06, -5.18260274e-17,  9.98903669e-01, -3.06306147e-17,\n",
+       "         -6.95292934e-07, -3.56123111e-20,  1.00000000e+00,  9.21745498e-16,\n",
+       "          3.29174070e-15,  8.08145906e-04,  3.97327396e-04,  1.09543455e-04,\n",
+       "         -4.01324311e-16, -5.83740619e-06, -2.72827205e-17,  2.58280611e-02,\n",
+       "          8.57342081e-16,  1.98784152e-05,  9.51628383e-19, -1.62295434e-16,\n",
+       "         -7.23030040e-17, -5.91351115e-05, -2.35853591e-05, -6.43954922e-07,\n",
+       "          9.78660178e-17]),\n",
+       "  array([ 2.06873296e-06, -5.18510225e-17,  9.98930964e-01, -3.01994011e-17,\n",
+       "         -6.85278354e-07, -3.51731947e-20,  1.00000000e+00,  9.21583622e-16,\n",
+       "          3.29167239e-15,  8.08086821e-04,  3.97303810e-04,  1.09542787e-04,\n",
+       "         -4.01225785e-16, -5.85171429e-06, -2.66554013e-17,  2.72941622e-02,\n",
+       "          8.62427169e-16,  2.00291596e-05,  8.78246722e-19, -1.61875935e-16,\n",
+       "         -6.83101044e-17, -5.90854556e-05, -2.35854644e-05, -6.68313167e-07,\n",
+       "          9.85258612e-17]),\n",
+       "  array([ 2.06282801e-06, -5.18753351e-17,  9.98959693e-01, -2.97657362e-17,\n",
+       "         -6.75190475e-07, -3.47699204e-20,  1.00000000e+00,  9.21422145e-16,\n",
+       "          3.29160830e-15,  8.08027809e-04,  3.97280238e-04,  1.09542100e-04,\n",
+       "         -4.01126573e-16, -5.86585491e-06, -2.60353183e-17,  2.87297451e-02,\n",
+       "          8.67329719e-16,  2.01757591e-05,  8.06563541e-19, -1.61476728e-16,\n",
+       "         -6.40885223e-17, -5.90115994e-05, -2.35717243e-05, -6.86783639e-07,\n",
+       "          9.92122413e-17]),\n",
+       "  array([ 2.05690780e-06, -5.18989767e-17,  9.98989829e-01, -2.93296919e-17,\n",
+       "         -6.65031006e-07, -3.44013324e-20,  1.00000000e+00,  9.21261045e-16,\n",
+       "          3.29154863e-15,  8.07968896e-04,  3.97256695e-04,  1.09541400e-04,\n",
+       "         -4.01026656e-16, -5.87982706e-06, -2.54224966e-17,  3.01352987e-02,\n",
+       "          8.72088696e-16,  2.03189365e-05,  7.37191979e-19, -1.61099780e-16,\n",
+       "         -5.96730632e-17, -5.89129918e-05, -2.35439253e-05, -6.99379576e-07,\n",
+       "          9.99163695e-17]),\n",
+       "  array([ 2.05097258e-06, -5.19219591e-17,  9.99021340e-01, -2.88913208e-17,\n",
+       "         -6.54801309e-07, -3.40659565e-20,  1.00000000e+00,  9.21100299e-16,\n",
+       "          3.29149353e-15,  8.07910107e-04,  3.97233193e-04,  1.09540694e-04,\n",
+       "         -4.00926027e-16, -5.89362976e-06, -2.48169601e-17,  3.15112979e-02,\n",
+       "          8.76742238e-16,  2.04593952e-05,  6.70768773e-19, -1.60746792e-16,\n",
+       "         -5.50985048e-17, -5.87891073e-05, -2.35018704e-05, -7.06123157e-07,\n",
+       "          1.00629460e-16]),\n",
+       "  array([ 2.04502263e-06, -5.19442936e-17,  9.99054198e-01, -2.84506571e-17,\n",
+       "         -6.44502401e-07, -3.37619937e-20,  1.00000000e+00,  9.20939879e-16,\n",
+       "          3.29144313e-15,  8.07851468e-04,  3.97209747e-04,  1.09539987e-04,\n",
+       "         -4.00824684e-16, -5.90726203e-06, -2.42187322e-17,  3.28582033e-02,\n",
+       "          8.81327415e-16,  2.05978152e-05,  6.07943666e-19, -1.60419188e-16,\n",
+       "         -5.03993302e-17, -5.86394407e-05, -2.34453761e-05, -7.07043310e-07,\n",
+       "          1.01342801e-16]),\n",
+       "  array([ 2.03905820e-06, -5.19659919e-17,  9.99088375e-01, -2.80077171e-17,\n",
+       "         -6.34134976e-07, -3.34873264e-20,  1.00000000e+00,  9.20779761e-16,\n",
+       "          3.29139752e-15,  8.07793004e-04,  3.97186373e-04,  1.09539285e-04,\n",
+       "         -4.00722636e-16, -5.92072289e-06, -2.36278364e-17,  3.41764601e-02,\n",
+       "          8.85879989e-16,  2.07348492e-05,  5.49353497e-19, -1.60118127e-16,\n",
+       "         -4.56094638e-17, -5.84635032e-05, -2.33742690e-05, -7.02173567e-07,\n",
+       "          1.02047817e-16]),\n",
+       "  array([ 2.03307958e-06, -5.19870653e-17,  9.99123841e-01, -2.75625000e-17,\n",
+       "         -6.23699417e-07, -3.32395346e-20,  1.00000000e+00,  9.20619917e-16,\n",
+       "          3.29135676e-15,  8.07734743e-04,  3.97163085e-04,  1.09538594e-04,\n",
+       "         -4.00619900e-16, -5.93401137e-06, -2.30442964e-17,  3.54664981e-02,\n",
+       "          8.90434189e-16,  2.08711191e-05,  4.95603424e-19, -1.59844509e-16,\n",
+       "         -4.07620081e-17, -5.82608181e-05, -2.32883825e-05, -6.91549957e-07,\n",
+       "          1.02736124e-16]),\n",
+       "  array([ 2.02708702e-06, -5.20075252e-17,  9.99160570e-01, -2.71149887e-17,\n",
+       "         -6.13195811e-07, -3.30159068e-20,  1.00000000e+00,  9.20460318e-16,\n",
+       "          3.29132087e-15,  8.07676712e-04,  3.97139897e-04,  1.09537918e-04,\n",
+       "         -4.00516500e-16, -5.94712646e-06, -2.24681366e-17,  3.67287308e-02,\n",
+       "          8.95022511e-16,  2.10072118e-05,  4.47276497e-19, -1.59598947e-16,\n",
+       "         -3.58889776e-17, -5.80309166e-05, -2.31875541e-05, -6.75208971e-07,\n",
+       "          1.03399593e-16]),\n",
+       "  array([ 2.02108080e-06, -5.20273829e-17,  9.99198533e-01, -2.66651510e-17,\n",
+       "         -6.02623973e-07, -3.28134377e-20,  1.00000000e+00,  9.20300936e-16,\n",
+       "          3.29128985e-15,  8.07618939e-04,  3.97116825e-04,  1.09537265e-04,\n",
+       "         -4.00412470e-16, -5.96006715e-06, -2.18993827e-17,  3.79635548e-02,\n",
+       "          8.99675519e-16,  2.11436763e-05,  4.04959824e-19, -1.59381719e-16,\n",
+       "         -3.10210476e-17, -5.77733345e-05, -2.30716223e-05, -6.53185603e-07,\n",
+       "          1.04030395e-16]),\n",
+       "  array([ 2.01506117e-06, -5.20466497e-17,  9.99237705e-01, -2.62129402e-17,\n",
+       "         -5.91983463e-07, -3.26288969e-20,  1.00000000e+00,  9.20141743e-16,\n",
+       "          3.29126366e-15,  8.07561452e-04,  3.97093885e-04,  1.09536640e-04,\n",
+       "         -4.00307849e-16, -5.97283239e-06, -2.13380618e-17,  3.91713495e-02,\n",
+       "          9.04421600e-16,  2.12810203e-05,  3.69103950e-19, -1.59192936e-16,\n",
+       "         -2.61874078e-17, -5.74876077e-05, -2.29404236e-05, -6.25511474e-07,\n",
+       "          1.04621058e-16]),\n",
+       "  array([ 2.00902841e-06, -5.20653367e-17,  9.99278057e-01, -2.57582967e-17,\n",
+       "         -5.81273609e-07, -3.24588077e-20,  1.00000000e+00,  9.19982711e-16,\n",
+       "          3.29124225e-15,  8.07504278e-04,  3.97071091e-04,  1.09536047e-04,\n",
+       "         -4.00202685e-16, -5.98542110e-06, -2.07842030e-17,  4.03524764e-02,\n",
+       "          9.09286880e-16,  2.14197072e-05,  3.40201738e-19, -1.59032306e-16,\n",
+       "         -2.14154312e-17, -5.71732695e-05, -2.27937902e-05, -5.92213059e-07,\n",
+       "          1.05164500e-16]),\n",
+       "  array([ 2.00298277e-06, -5.20834552e-17,  9.99319565e-01, -2.53011493e-17,\n",
+       "         -5.70493532e-07, -3.22995879e-20,  1.00000000e+00,  9.19823811e-16,\n",
+       "          3.29122552e-15,  8.07447448e-04,  3.97048460e-04,  1.09535494e-04,\n",
+       "         -4.00097030e-16, -5.99783217e-06, -2.02378379e-17,  4.15072786e-02,\n",
+       "          9.14294916e-16,  2.15601536e-05,  3.18463401e-19, -1.58899544e-16,\n",
+       "         -1.67306885e-17, -5.68298470e-05, -2.26315475e-05, -5.53310029e-07,\n",
+       "          1.05654096e-16]),\n",
+       "  array([ 1.99692452e-06, -5.21010163e-17,  9.99362201e-01, -2.48414158e-17,\n",
+       "         -5.59642169e-07, -3.21474017e-20,  1.00000000e+00,  9.19665018e-16,\n",
+       "          3.29121336e-15,  8.07390992e-04,  3.97026006e-04,  1.09534985e-04,\n",
+       "         -3.99990947e-16, -6.01006441e-06, -1.96990007e-17,  4.26360804e-02,\n",
+       "          9.19466831e-16,  2.17027270e-05,  3.04397018e-19, -1.58793630e-16,\n",
+       "         -1.21564070e-17, -5.64568586e-05, -2.24535115e-05, -5.08813699e-07,\n",
+       "          1.06083708e-16]),\n",
+       "  array([ 1.99085393e-06, -5.21180312e-17,  9.99405940e-01, -2.43790054e-17,\n",
+       "         -5.48718297e-07, -3.19983188e-20,  1.00000000e+00,  9.19506304e-16,\n",
+       "          3.29120565e-15,  8.07334938e-04,  3.97003747e-04,  1.09534527e-04,\n",
+       "         -3.99884499e-16, -6.02211660e-06, -1.91677287e-17,  4.37391867e-02,\n",
+       "          9.24820908e-16,  2.18477434e-05,  2.98190825e-19, -1.58713602e-16,\n",
+       "         -7.71370322e-18, -5.60538109e-05, -2.22594872e-05, -4.58725612e-07,\n",
+       "          1.06447719e-16]),\n",
+       "  array([ 1.98477125e-06, -5.21345109e-17,  9.99450757e-01, -2.39138191e-17,\n",
+       "         -5.37720564e-07, -3.18482851e-20,  1.00000000e+00,  9.19347646e-16,\n",
+       "          3.29120223e-15,  8.07279318e-04,  3.96981697e-04,  1.09534124e-04,\n",
+       "         -3.99777758e-16, -6.03398745e-06, -1.86440626e-17,  4.48168827e-02,\n",
+       "          9.30372664e-16,  2.19954664e-05,  3.00093206e-19, -1.58658064e-16,\n",
+       "         -3.42120905e-18, -5.56201963e-05, -2.20492663e-05, -4.03036260e-07,\n",
+       "          1.06741056e-16]),\n",
+       "  array([ 1.97867675e-06, -5.21504666e-17,  9.99496626e-01, -2.34457518e-17,\n",
+       "         -5.26647511e-07, -3.16932630e-20,  1.00000000e+00,  9.19189020e-16,\n",
+       "          3.29120293e-15,  8.07224162e-04,  3.96959875e-04,  1.09533782e-04,\n",
+       "         -3.99670799e-16, -6.04567560e-06, -1.81280469e-17,  4.58694329e-02,\n",
+       "          9.36134623e-16,  2.21461052e-05,  3.10070399e-19, -1.58625643e-16,\n",
+       "          7.04841003e-19, -5.51554914e-05, -2.18226258e-05, -3.41723931e-07,\n",
+       "          1.06959226e-16]),\n",
+       "  array([ 1.97257070e-06, -5.21659094e-17,  9.99543523e-01, -2.29746935e-17,\n",
+       "         -5.15497604e-07, -3.15291080e-20,  1.00000000e+00,  9.19030406e-16,\n",
+       "          3.29120758e-15,  8.07169503e-04,  3.96938296e-04,  1.09533507e-04,\n",
+       "         -3.99563700e-16, -6.05717964e-06, -1.76197303e-17,  4.68970815e-02,\n",
+       "          9.42116490e-16,  2.22998141e-05,  3.28336688e-19, -1.58614315e-16,\n",
+       "          4.65100190e-18, -5.46591550e-05, -2.15793264e-05, -2.74753715e-07,\n",
+       "          1.07098335e-16]),\n",
+       "  array([ 1.96645335e-06, -5.21808503e-17,  9.99591423e-01, -2.25005311e-17,\n",
+       "         -5.04269258e-07, -3.13517020e-20,  1.00000000e+00,  9.18871784e-16,\n",
+       "          3.29121599e-15,  8.07115372e-04,  3.96916976e-04,  1.09533305e-04,\n",
+       "         -3.99456545e-16, -6.06849805e-06, -1.71191654e-17,  4.79000510e-02,\n",
+       "          9.48324893e-16,  2.24566920e-05,  3.54838983e-19, -1.58622077e-16,\n",
+       "          8.40640417e-18, -5.41306264e-05, -2.13191116e-05, -2.02076652e-07,\n",
+       "          1.07155099e-16]),\n",
+       "  array([ 1.96032498e-06, -5.21953004e-17,  9.99640302e-01, -2.20231494e-17,\n",
+       "         -4.92960867e-07, -3.11570760e-20,  1.00000000e+00,  9.18713137e-16,\n",
+       "          3.29122795e-15,  8.07061803e-04,  3.96895935e-04,  1.09533181e-04,\n",
+       "         -3.99349418e-16, -6.07962926e-06, -1.66264098e-17,  4.88785426e-02,\n",
+       "          9.54763382e-16,  2.26167821e-05,  3.89279575e-19, -1.58646934e-16,\n",
+       "          1.19628117e-17, -5.35693246e-05, -2.10417063e-05, -1.23629028e-07,\n",
+       "          1.07126858e-16]),\n",
+       "  array([ 1.95418584e-06, -5.22092710e-17,  9.99690135e-01, -2.15424330e-17,\n",
+       "         -4.81570831e-07, -3.09412296e-20,  1.00000000e+00,  9.18554451e-16,\n",
+       "          3.29124327e-15,  8.07008828e-04,  3.96875188e-04,  1.09533142e-04,\n",
+       "         -3.99242407e-16, -6.09057160e-06, -1.61415254e-17,  4.98327351e-02,\n",
+       "          9.61432678e-16,  2.27800722e-05,  4.31720515e-19, -1.58686148e-16,\n",
+       "          1.53149686e-17, -5.29746471e-05, -2.07468163e-05, -3.93318352e-08,\n",
+       "          1.07011594e-16]),\n",
+       "  array([ 1.94803621e-06, -5.22227730e-17,  9.99740897e-01, -2.10582678e-17,\n",
+       "         -4.70097583e-07, -3.07003056e-20,  1.00000000e+00,  9.18395714e-16,\n",
+       "          3.29126173e-15,  8.06956482e-04,  3.96854754e-04,  1.09533193e-04,\n",
+       "         -3.99135599e-16, -6.10132332e-06, -1.56645792e-17,  5.07627849e-02,\n",
+       "          9.68330417e-16,  2.29464955e-05,  4.81875976e-19, -1.58737161e-16,\n",
+       "          1.84602305e-17, -5.23459698e-05, -2.04341279e-05,  5.09096300e-08,\n",
+       "          1.06807923e-16]),\n",
+       "  array([ 1.94187635e-06, -5.22358177e-17,  9.99792566e-01, -2.05705421e-17,\n",
+       "         -4.58539618e-07, -3.04305433e-20,  1.00000000e+00,  9.18236917e-16,\n",
+       "          3.29128313e-15,  8.06904800e-04,  3.96834650e-04,  1.09533340e-04,\n",
+       "         -3.99029084e-16, -6.11188257e-06, -1.51956431e-17,  5.16688256e-02,\n",
+       "          9.75451379e-16,  2.31159315e-05,  5.39552778e-19, -1.58797051e-16,\n",
+       "          2.13987864e-17, -5.16826465e-05, -2.01033072e-05,  1.47206002e-07,\n",
+       "          1.06515082e-16]),\n",
+       "  array([ 1.93570652e-06, -5.22484164e-17,  9.99845117e-01, -2.00791484e-17,\n",
+       "         -4.46895514e-07, -3.01284542e-20,  1.00000000e+00,  9.18078053e-16,\n",
+       "          3.29130726e-15,  8.06853816e-04,  3.96814896e-04,  1.09533590e-04,\n",
+       "         -3.98922951e-16, -6.12224744e-06, -1.47347943e-17,  5.25509671e-02,\n",
+       "          9.82787397e-16,  2.32882072e-05,  6.04206751e-19, -1.58863125e-16,\n",
+       "          2.41334112e-17, -5.09840088e-05, -1.97540005e-05,  2.49683939e-07,\n",
+       "          1.06132930e-16]),\n",
+       "  array([ 1.92952699e-06, -5.22605801e-17,  9.99898526e-01, -1.95839846e-17,\n",
+       "         -4.35163964e-07, -2.97907305e-20,  1.00000000e+00,  9.17919121e-16,\n",
+       "          3.29133393e-15,  8.06803566e-04,  3.96795511e-04,  1.09533948e-04,\n",
+       "         -3.98817289e-16, -6.13241590e-06, -1.42821148e-17,  5.34092958e-02,\n",
+       "          9.90327623e-16,  2.34630991e-05,  6.75475861e-19, -1.58932263e-16,\n",
+       "          2.66696409e-17, -5.02493671e-05, -1.93858341e-05,  3.58486060e-07,\n",
+       "          1.05661943e-16]),\n",
+       "  array([ 1.92333804e-06, -5.22723202e-17,  9.99952770e-01, -1.90849553e-17,\n",
+       "         -4.23343797e-07, -2.94142821e-20,  1.00000000e+00,  9.17760120e-16,\n",
+       "          3.29136294e-15,  8.06754088e-04,  3.96776512e-04,  1.09534422e-04,\n",
+       "         -3.98712186e-16, -6.14238584e-06, -1.38376921e-17,  5.42438738e-02,\n",
+       "          9.98058550e-16,  2.36403351e-05,  7.52925416e-19, -1.59001279e-16,\n",
+       "          2.90155863e-17, -4.94780105e-05, -1.89984152e-05,  4.73770744e-07,\n",
+       "          1.05103196e-16]),\n",
+       "  array([ 1.91713992e-06, -5.22836481e-17,  1.00000783e+00, -1.85819733e-17,\n",
+       "         -4.11433999e-07, -2.89962825e-20,  1.00000000e+00,  9.17601053e-16,\n",
+       "          3.29139413e-15,  8.06705419e-04,  3.96757921e-04,  1.09535018e-04,\n",
+       "         -3.98607727e-16, -6.15215507e-06, -1.34016185e-17,  5.50547389e-02,\n",
+       "          1.00596414e-15,  2.38195967e-05,  8.36028051e-19, -1.59066967e-16,\n",
+       "          3.11818516e-17, -4.86692084e-05, -1.85913317e-05,  5.95711781e-07,\n",
+       "          1.04458342e-16]),\n",
+       "  array([ 1.91093292e-06, -5.22945751e-17,  1.00006367e+00, -1.80749603e-17,\n",
+       "         -3.99433738e-07, -2.85341684e-20,  1.00000000e+00,  9.17441927e-16,\n",
+       "          3.29142731e-15,  8.06657597e-04,  3.96739757e-04,  1.09535742e-04,\n",
+       "         -3.98503998e-16, -6.16172130e-06, -1.29739915e-17,  5.58419038e-02,\n",
+       "          1.01402598e-15,  2.40005215e-05,  9.24256969e-19, -1.59126016e-16,\n",
+       "          3.31814301e-17, -4.78222114e-05, -1.81641537e-05,  7.24497892e-07,\n",
+       "          1.03729583e-16]),\n",
+       "  array([ 1.90471730e-06, -5.23051127e-17,  1.00012027e+00, -1.75638486e-17,\n",
+       "         -3.87342385e-07, -2.80256885e-20,  1.00000000e+00,  9.17282752e-16,\n",
+       "          3.29146234e-15,  8.06610661e-04,  3.96722040e-04,  1.09536603e-04,\n",
+       "         -3.98401078e-16, -6.17108216e-06, -1.25549136e-17,  5.66053562e-02,\n",
+       "          1.02222342e-15,  2.41827063e-05,  1.01698846e-18, -1.59175162e-16,\n",
+       "          3.50295824e-17, -4.69362526e-05, -1.77164342e-05,  8.60332118e-07,\n",
+       "          1.02919651e-16]),\n",
+       "  array([ 1.89849334e-06, -5.23152723e-17,  1.00017762e+00, -1.70485817e-17,\n",
+       "         -3.75159530e-07, -2.74689071e-20,  1.00000000e+00,  9.17123541e-16,\n",
+       "          3.29149908e-15,  8.06564650e-04,  3.96704793e-04,  1.09537606e-04,\n",
+       "         -3.98299046e-16, -6.18023521e-06, -1.21444920e-17,  5.73450580e-02,\n",
+       "          1.03053374e-15,  2.43657100e-05,  1.11359162e-18, -1.59211103e-16,\n",
+       "          3.67437001e-17, -4.60105498e-05, -1.72477104e-05,  1.00343109e-06,\n",
+       "          1.02031773e-16]),\n",
+       "  array([ 1.89226131e-06, -5.23250656e-17,  1.00023568e+00, -1.65291155e-17,\n",
+       "         -3.62885001e-07, -2.68622082e-20,  1.00000000e+00,  9.16964310e-16,\n",
+       "          3.29153742e-15,  8.06519606e-04,  3.96688035e-04,  1.09538760e-04,\n",
+       "         -3.98197977e-16, -6.18917789e-06, -1.17428385e-17,  5.80609452e-02,\n",
+       "          1.03893233e-15,  2.45490565e-05,  1.21342653e-18, -1.59230536e-16,\n",
+       "          3.83431557e-17, -4.50443069e-05, -1.67575048e-05,  1.15402416e-06,\n",
+       "          1.01069637e-16]),\n",
+       "  array([ 1.88602149e-06, -5.23345042e-17,  1.00029443e+00, -1.60054191e-17,\n",
+       "         -3.50518882e-07, -2.62043252e-20,  1.00000000e+00,  9.16805080e-16,\n",
+       "          3.29157727e-15,  8.06475569e-04,  3.96671790e-04,  1.09540072e-04,\n",
+       "         -3.98097939e-16, -6.19790761e-06, -1.13500695e-17,  5.87529277e-02,\n",
+       "          1.04739289e-15,  2.47322385e-05,  1.31579470e-18, -1.59230245e-16,\n",
+       "          3.98491417e-17, -4.40367163e-05, -1.62453268e-05,  1.31235248e-06,\n",
+       "          1.00037362e-16]),\n",
+       "  array([ 1.87977415e-06, -5.23435997e-17,  1.00035385e+00, -1.54774753e-17,\n",
+       "         -3.38061522e-07, -2.54943518e-20,  1.00000000e+00,  9.16645873e-16,\n",
+       "          3.29161856e-15,  8.06432582e-04,  3.96656079e-04,  1.09541551e-04,\n",
+       "         -3.97999000e-16, -6.20642169e-06, -1.09663054e-17,  5.94208888e-02,\n",
+       "          1.05588759e-15,  2.49147204e-05,  1.41997543e-18, -1.59207088e-16,\n",
+       "          4.12844987e-17, -4.29869612e-05, -1.57106747e-05,  1.47866793e-06,\n",
+       "          9.89394537e-17]),\n",
+       "  array([ 1.87351958e-06, -5.23523641e-17,  1.00041392e+00, -1.49452817e-17,\n",
+       "         -3.25513551e-07, -2.47316924e-20,  1.00000000e+00,  9.16486715e-16,\n",
+       "          3.29166123e-15,  8.06390688e-04,  3.96640926e-04,  1.09543204e-04,\n",
+       "         -3.97901219e-16, -6.21471737e-06, -1.05916706e-17,  6.00646848e-02,\n",
+       "          1.06438729e-15,  2.50959423e-05,  1.52534743e-18, -1.59157868e-16,\n",
+       "          4.26735358e-17, -4.18942179e-05, -1.51530367e-05,  1.65323195e-06,\n",
+       "          9.77807703e-17]),\n",
+       "  array([ 1.86725805e-06, -5.23608090e-17,  1.00047460e+00, -1.44088508e-17,\n",
+       "         -3.12875889e-07, -2.39160983e-20,  1.00000000e+00,  9.16327635e-16,\n",
+       "          3.29170527e-15,  8.06349930e-04,  3.96626354e-04,  1.09545041e-04,\n",
+       "         -3.97804653e-16, -6.22279186e-06, -1.02262931e-17,  6.06841449e-02,\n",
+       "          1.07286172e-15,  2.52753233e-05,  1.63121675e-18, -1.59079581e-16,\n",
+       "          4.40418439e-17, -4.07576585e-05, -1.45718936e-05,  1.83631438e-06,\n",
+       "          9.65664781e-17]),\n",
+       "  array([ 1.86098984e-06, -5.23689465e-17,  1.00053588e+00, -1.38682109e-17,\n",
+       "         -3.00149757e-07, -2.30476843e-20,  1.00000000e+00,  9.16168666e-16,\n",
+       "          3.29175069e-15,  8.06310354e-04,  3.96612387e-04,  1.09547069e-04,\n",
+       "         -3.97709351e-16, -6.23064229e-06, -9.87030432e-18,  6.12790708e-02,\n",
+       "          1.08127970e-15,  2.54522647e-05,  1.73685652e-18, -1.58969392e-16,\n",
+       "          4.54161035e-17, -3.95764537e-05, -1.39667202e-05,  2.02819209e-06,\n",
+       "          9.53020100e-17]),\n",
+       "  array([ 1.85471524e-06, -5.23767886e-17,  1.00059773e+00, -1.33234063e-17,\n",
+       "         -2.87336680e-07, -2.21268714e-20,  1.00000000e+00,  9.16009842e-16,\n",
+       "          3.29179751e-15,  8.06272004e-04,  3.96599050e-04,  1.09549298e-04,\n",
+       "         -3.97615358e-16, -6.23826574e-06, -9.52383849e-18,  6.18492366e-02,\n",
+       "          1.08960930e-15,  2.56261541e-05,  1.84165404e-18, -1.58824469e-16,\n",
+       "          4.68238894e-17, -3.83497755e-05, -1.33369878e-05,  2.22914771e-06,\n",
+       "          9.39930227e-17]),\n",
+       "  array([ 1.84843453e-06, -5.23843473e-17,  1.00066012e+00, -1.27744973e-17,\n",
+       "         -2.74438496e-07, -2.11543762e-20,  1.00000000e+00,  9.15851199e-16,\n",
+       "          3.29184581e-15,  8.06234927e-04,  3.96586368e-04,  1.09551737e-04,\n",
+       "         -3.97522712e-16, -6.24565927e-06, -9.18703252e-18,  6.23943881e-02,\n",
+       "          1.09781807e-15,  2.57963686e-05,  1.94501876e-18, -1.58642127e-16,\n",
+       "          4.82934727e-17, -3.70768000e-05, -1.26821659e-05,  2.43946816e-06,\n",
+       "          9.26453525e-17]),\n",
+       "  array([ 1.84214799e-06, -5.23916347e-17,  1.00072304e+00, -1.22215607e-17,\n",
+       "         -2.61457357e-07, -2.01312168e-20,  1.00000000e+00,  9.15692779e-16,\n",
+       "          3.29189566e-15,  8.06199170e-04,  3.96574367e-04,  1.09554397e-04,\n",
+       "         -3.97431447e-16, -6.25281988e-06, -8.86002555e-18,  6.29142431e-02,\n",
+       "          1.10587321e-15,  2.59622779e-05,  2.04634688e-18, -1.58419889e-16,\n",
+       "          4.98536228e-17, -3.57567107e-05, -1.20017247e-05,  2.65944328e-06,\n",
+       "          9.12649715e-17]),\n",
+       "  array([ 1.83585592e-06, -5.23986630e-17,  1.00078645e+00, -1.16646898e-17,\n",
+       "         -2.48395733e-07, -1.90587256e-20,  1.00000000e+00,  9.15534624e-16,\n",
+       "          3.29194719e-15,  8.06164782e-04,  3.96563071e-04,  1.09557286e-04,\n",
+       "         -3.97341589e-16, -6.25974458e-06, -8.54295855e-18,  6.34084906e-02,\n",
+       "          1.11374175e-15,  2.61232477e-05,  2.14501057e-18, -1.58155523e-16,\n",
+       "          5.15334108e-17, -3.43887010e-05, -1.12951372e-05,  2.88936429e-06,\n",
+       "          8.98579445e-17]),\n",
+       "  array([ 1.82955859e-06, -5.24054446e-17,  1.00085032e+00, -1.11039944e-17,\n",
+       "         -2.35256411e-07, -1.79384740e-20,  1.00000000e+00,  9.15376777e-16,\n",
+       "          3.29200056e-15,  8.06131810e-04,  3.96552510e-04,  1.09560416e-04,\n",
+       "         -3.97253159e-16, -6.26643030e-06, -8.23597395e-18,  6.38767911e-02,\n",
+       "          1.12139074e-15,  2.62786430e-05,  2.24053116e-18, -1.57846833e-16,\n",
+       "          5.33620143e-17, -3.29719778e-05, -1.05618814e-05,  3.12952239e-06,\n",
+       "          8.84303856e-17]),\n",
+       "  array([ 1.82325631e-06, -5.24119918e-17,  1.00091464e+00, -1.05396007e-17,\n",
+       "         -2.22042496e-07, -1.67722922e-20,  1.00000000e+00,  9.15219285e-16,\n",
+       "          3.29205592e-15,  8.06100304e-04,  3.96542708e-04,  1.09563796e-04,\n",
+       "         -3.97166171e-16, -6.27287402e-06, -7.93921517e-18,  6.43187759e-02,\n",
+       "          1.12878740e-15,  2.64278305e-05,  2.33239137e-18, -1.57491917e-16,\n",
+       "          5.53685276e-17, -3.15057638e-05, -9.80144275e-06,  3.38020720e-06,\n",
+       "          8.69884158e-17]),\n",
+       "  array([ 1.81694935e-06, -5.24183168e-17,  1.00097938e+00, -9.97165108e-18,\n",
+       "         -2.08757405e-07, -1.55621937e-20,  1.00000000e+00,  9.15062196e-16,\n",
+       "          3.29211351e-15,  8.06070315e-04,  3.96533695e-04,  1.09567438e-04,\n",
+       "         -3.97080632e-16, -6.27907268e-06, -7.65282627e-18,  6.47340471e-02,\n",
+       "          1.13589927e-15,  2.65701817e-05,  2.42022478e-18, -1.57088931e-16,\n",
+       "          5.75817765e-17, -2.99893011e-05, -9.01331600e-06,  3.64170533e-06,\n",
+       "          8.55381225e-17]),\n",
+       "  array([ 1.81063800e-06, -5.24244322e-17,  1.00104450e+00, -9.40030389e-18,\n",
+       "         -1.95404867e-07, -1.43104742e-20,  1.00000000e+00,  9.14905560e-16,\n",
+       "          3.29217354e-15,  8.06041893e-04,  3.96525498e-04,  1.09571352e-04,\n",
+       "         -3.96996547e-16, -6.28502322e-06, -7.37695150e-18,  6.51221773e-02,\n",
+       "          1.14269437e-15,  2.67050751e-05,  2.50346686e-18, -1.56636550e-16,\n",
+       "          6.00301396e-17, -2.84218536e-05, -8.19700781e-06,  3.91429888e-06,\n",
+       "          8.40855194e-17]),\n",
+       "  array([ 1.80432257e-06, -5.24303505e-17,  1.00110998e+00, -8.82573323e-18,\n",
+       "         -1.81988918e-07, -1.30195208e-20,  1.00000000e+00,  9.14749427e-16,\n",
+       "          3.29223628e-15,  8.06015090e-04,  3.96518146e-04,  1.09575550e-04,\n",
+       "         -3.96913910e-16, -6.29072262e-06, -7.11173487e-18,  6.54827096e-02,\n",
+       "          1.14914132e-15,  2.68318987e-05,  2.58193449e-18, -1.56133233e-16,\n",
+       "          6.27413777e-17, -2.68027103e-05, -7.35203867e-06,  4.19826398e-06,\n",
+       "          8.26365084e-17]),\n",
+       "  array([ 1.79800333e-06, -5.24360841e-17,  1.00117580e+00, -8.24812850e-18,\n",
+       "         -1.68513892e-07, -1.16918720e-20,  1.00000000e+00,  9.14593849e-16,\n",
+       "          3.29230202e-15,  8.05989959e-04,  3.96511668e-04,  1.09580044e-04,\n",
+       "         -3.96832714e-16, -6.29616785e-06, -6.85731976e-18,  6.58151572e-02,\n",
+       "          1.15520946e-15,  2.69500518e-05,  2.65532525e-18, -1.55577862e-16,\n",
+       "          6.57424722e-17, -2.51311878e-05, -6.47794513e-06,  4.49386940e-06,\n",
+       "          8.11968440e-17]),\n",
+       "  array([ 1.79168059e-06, -5.24416456e-17,  1.00124192e+00, -7.66769404e-18,\n",
+       "         -1.54984419e-07, -1.03302211e-20,  1.00000000e+00,  9.14438879e-16,\n",
+       "          3.29237108e-15,  8.05966552e-04,  3.96506093e-04,  1.09584846e-04,\n",
+       "         -3.96752942e-16, -6.30135591e-06, -6.61384849e-18,  6.61190033e-02,\n",
+       "          1.16086893e-15,  2.70589468e-05,  2.72332936e-18, -1.54969609e-16,\n",
+       "          6.90594725e-17, -2.34066329e-05, -5.57428182e-06,  4.80137515e-06,\n",
+       "          7.97720988e-17]),\n",
+       "  array([ 1.78535462e-06, -5.24470476e-17,  1.00130831e+00, -7.08464863e-18,\n",
+       "         -1.41405413e-07, -8.93737807e-21,  1.00000000e+00,  9.14284571e-16,\n",
+       "          3.29244380e-15,  8.05944924e-04,  3.96501453e-04,  1.09589967e-04,\n",
+       "         -3.96674574e-16, -6.30628386e-06, -6.38146189e-18,  6.63937008e-02,\n",
+       "          1.16609080e-15,  2.71580109e-05,  2.78571353e-18, -1.54307822e-16,\n",
+       "          7.27173550e-17, -2.16284257e-05, -4.64062344e-06,  5.12103117e-06,\n",
+       "          7.83676322e-17]),\n",
+       "  array([ 1.77902574e-06, -5.24523027e-17,  1.00137495e+00, -6.49922507e-18,\n",
+       "         -1.27782070e-07, -7.51614272e-21,  1.00000000e+00,  9.14130979e-16,\n",
+       "          3.29252054e-15,  8.05925128e-04,  3.96497776e-04,  1.09595420e-04,\n",
+       "         -3.96597585e-16, -6.31094876e-06, -6.16029894e-18,  6.66386724e-02,\n",
+       "          1.17084713e-15,  2.72466868e-05,  2.84249818e-18, -1.53591801e-16,\n",
+       "          7.67398922e-17, -1.97959814e-05, -3.67656669e-06,  5.45307601e-06,\n",
+       "          7.69885605e-17]),\n",
+       "  array([ 1.77269422e-06, -5.24574234e-17,  1.00144180e+00, -5.91166957e-18,\n",
+       "         -1.14119853e-07, -6.06946783e-21,  1.00000000e+00,  9.13978158e-16,\n",
+       "          3.29260169e-15,  8.05907219e-04,  3.96495095e-04,  1.09601217e-04,\n",
+       "         -3.96521946e-16, -6.31534776e-06, -5.95049632e-18,  6.68533102e-02,\n",
+       "          1.17511099e-15,  2.73244344e-05,  2.89337720e-18, -1.52821531e-16,\n",
+       "          8.11495347e-17, -1.79087531e-05, -2.68173203e-06,  5.79773565e-06,\n",
+       "          7.56397310e-17]),\n",
+       "  array([ 1.76636036e-06, -5.24624225e-17,  1.00150884e+00, -5.32224129e-18,\n",
+       "         -1.00424487e-07, -4.60032027e-21,  1.00000000e+00,  9.13826161e-16,\n",
+       "          3.29268765e-15,  8.05891253e-04,  3.96493439e-04,  1.09607373e-04,\n",
+       "         -3.96447620e-16, -6.31947805e-06, -5.75218808e-18,  6.70369759e-02,\n",
+       "          1.17885657e-15,  2.73907310e-05,  2.93832252e-18, -1.51996908e-16,\n",
+       "          8.59673051e-17, -1.59662338e-05, -1.65576545e-06,  6.15522233e-06,\n",
+       "          7.43256973e-17]),\n",
+       "  array([ 1.76002445e-06, -5.24673126e-17,  1.00157603e+00, -4.73121171e-18,\n",
+       "         -8.67019513e-08, -3.11153948e-21,  1.00000000e+00,  9.13675043e-16,\n",
+       "          3.29277887e-15,  8.05877285e-04,  3.96492840e-04,  1.09613898e-04,\n",
+       "         -3.96374569e-16, -6.32333687e-06, -5.56550526e-18,  6.71890001e-02,\n",
+       "          1.18205917e-15,  2.74450719e-05,  2.97758893e-18, -1.51117719e-16,\n",
+       "          9.12127035e-17, -1.39679585e-05, -5.98340038e-07,  6.52573349e-06,\n",
+       "          7.30506979e-17]),\n",
+       "  array([ 1.75368678e-06, -5.24721061e-17,  1.00164334e+00, -4.13886410e-18,\n",
+       "         -7.29584660e-08, -1.60610477e-21,  1.00000000e+00,  9.13524859e-16,\n",
+       "          3.29287577e-15,  8.05865371e-04,  3.96493331e-04,  1.09620808e-04,\n",
+       "         -3.96302751e-16, -6.32692155e-06, -5.39057546e-18,  6.73086828e-02,\n",
+       "          1.18469521e-15,  2.74869706e-05,  3.01089676e-18, -1.50184682e-16,\n",
+       "          9.69036276e-17, -1.19135063e-05,  4.90842498e-07,  6.90945075e-06,\n",
+       "          7.18186383e-17]),\n",
+       "  array([ 1.74734764e-06, -5.24768157e-17,  1.00171073e+00, -3.54549296e-18,\n",
+       "         -5.92004866e-08, -8.66759461e-23,  1.00000000e+00,  9.13375661e-16,\n",
+       "          3.29297883e-15,  8.05855569e-04,  3.96494943e-04,  1.09628114e-04,\n",
+       "         -3.96232117e-16, -6.33022950e-06, -5.22752261e-18,  6.73952930e-02,\n",
+       "          1.18674228e-15,  2.75159587e-05,  3.03888495e-18, -1.49197569e-16,\n",
+       "          1.03056304e-16, -9.80250193e-06,  1.61205046e-06,  7.30653897e-06,\n",
+       "          7.06330747e-17]),\n",
+       "  array([ 1.74100733e-06, -5.24814540e-17,  1.00177818e+00, -2.95140342e-18,\n",
+       "         -4.54346936e-08,  1.44416998e-21,  1.00000000e+00,  9.13227504e-16,\n",
+       "          3.29308851e-15,  8.05847934e-04,  3.96497709e-04,  1.09635831e-04,\n",
+       "         -3.96162620e-16, -6.33325820e-06, -5.07646650e-18,  6.74480686e-02,\n",
+       "          1.18817908e-15,  2.75315861e-05,  3.06171912e-18, -1.48156978e-16,\n",
+       "          1.09685231e-16, -7.63461733e-06,  2.76552088e-06,  7.71714543e-06,\n",
+       "          6.94972011e-17]),\n",
+       "  array([ 1.73466612e-06, -5.24860334e-17,  1.00184564e+00, -2.35691070e-18,\n",
+       "         -3.16679837e-08,  2.98399912e-21,  1.00000000e+00,  9.13080440e-16,\n",
+       "          3.29320532e-15,  8.05842525e-04,  3.96501660e-04,  1.09643973e-04,\n",
+       "         -3.96094206e-16, -6.33600523e-06, -4.93752255e-18,  6.74662165e-02,\n",
+       "          1.18898544e-15,  2.75334198e-05,  3.07968553e-18, -1.47063549e-16,\n",
+       "          1.16803140e-16, -5.40957336e-06,  3.95145839e-06,  8.14139907e-06,\n",
+       "          6.84138395e-17]),\n",
+       "  array([ 1.72832431e-06, -5.24905664e-17,  1.00191309e+00, -1.76233956e-18,\n",
+       "         -1.79074617e-08,  4.53056166e-21,  1.00000000e+00,  9.12934522e-16,\n",
+       "          3.29332974e-15,  8.05839398e-04,  3.96506830e-04,  1.09652552e-04,\n",
+       "         -3.96026821e-16, -6.33846826e-06, -4.81080144e-18,  6.74489124e-02,\n",
+       "          1.18914226e-15,  2.75210440e-05,  3.09315228e-18, -1.45918000e-16,\n",
+       "          1.24420961e-16, -3.12714095e-06,  5.17003417e-06,  8.57940981e-06,\n",
+       "          6.73854319e-17]),\n",
+       "  array([ 1.72198218e-06, -5.24950653e-17,  1.00198049e+00, -1.16802382e-18,\n",
+       "         -4.16043236e-09,  6.08197762e-21,  1.00000000e+00,  9.12789802e-16,\n",
+       "          3.29346228e-15,  8.05838610e-04,  3.96513252e-04,  1.09661584e-04,\n",
+       "         -3.95960407e-16, -6.34064509e-06, -4.69640884e-18,  6.73953007e-02,\n",
+       "          1.18863148e-15,  2.74940588e-05,  3.10285909e-18, -1.44720736e-16,\n",
+       "          1.32547801e-16, -7.87142303e-07,  6.42138508e-06,  9.03126793e-06,\n",
+       "          6.64140357e-17]),\n",
+       "  array([ 1.71564001e-06, -5.24995425e-17,  1.00204779e+00, -5.74305800e-19,\n",
+       "          9.56560736e-09,  7.63684241e-21,  1.00000000e+00,  9.12646330e-16,\n",
+       "          3.29360347e-15,  8.05840221e-04,  3.96520957e-04,  1.09671081e-04,\n",
+       "         -3.95894906e-16, -6.34253359e-06, -4.59444513e-18,  6.73044945e-02,\n",
+       "          1.18743605e-15,  2.74520794e-05,  3.10975671e-18, -1.43472029e-16,\n",
+       "          1.41190943e-16,  1.61054808e-06,  7.70561280e-06,  9.49704361e-06,\n",
+       "          6.55013212e-17]),\n",
+       "  array([ 1.70929808e-06, -5.25040101e-17,  1.00211497e+00,  1.84641109e-20,\n",
+       "          2.32629750e-08,  9.19354628e-21,  1.00000000e+00,  9.12504156e-16,\n",
+       "          3.29375383e-15,  8.05844287e-04,  3.96529980e-04,  1.09681057e-04,\n",
+       "         -3.95830257e-16, -6.34413178e-06, -4.50500498e-18,  6.71755760e-02,\n",
+       "          1.18553982e-15,  2.73947353e-05,  3.11343482e-18, -1.42174009e-16,\n",
+       "          1.50355843e-16,  4.06600249e-06,  9.02278320e-06,  9.97678648e-06,\n",
+       "          6.46485727e-17]),\n",
+       "  array([ 1.70295667e-06, -5.25084804e-17,  1.00218198e+00,  6.09927885e-19,\n",
+       "          3.69238093e-08,  1.07508400e-20,  1.00000000e+00,  9.12363328e-16,\n",
+       "          3.29391388e-15,  8.05850866e-04,  3.96540353e-04,  1.09691528e-04,\n",
+       "         -3.95766400e-16, -6.34543778e-06, -4.42817726e-18,  6.70075957e-02,\n",
+       "          1.18292755e-15,  2.73216685e-05,  3.11461440e-18, -1.40827454e-16,\n",
+       "          1.60046143e-16,  6.57923926e-06,  1.03729258e-05,  1.04705253e-05,\n",
+       "          6.38566896e-17]),\n",
+       "  array([ 1.69661607e-06, -5.25129653e-17,  1.00224878e+00,  1.19972010e-18,\n",
+       "          5.05400726e-08,  1.23072822e-20,  1.00000000e+00,  9.12223894e-16,\n",
+       "          3.29408414e-15,  8.05860017e-04,  3.96552109e-04,  1.09702506e-04,\n",
+       "         -3.95703274e-16, -6.34644985e-06, -4.36404496e-18,  6.67995732e-02,\n",
+       "          1.17958443e-15,  2.72325267e-05,  3.11291139e-18, -1.39434664e-16,\n",
+       "          1.70263388e-16,  9.15021698e-06,  1.17560315e-05,  1.09782672e-05,\n",
+       "          6.31261719e-17]),\n",
+       "  array([ 1.69027653e-06, -5.25174768e-17,  1.00231533e+00,  1.78746875e-18,\n",
+       "          6.41035641e-08,  1.38618267e-20,  1.00000000e+00,  9.12085897e-16,\n",
+       "          3.29426515e-15,  8.05871795e-04,  3.96565281e-04,  1.09714006e-04,\n",
+       "         -3.95640817e-16, -6.34716640e-06, -4.31268379e-18,  6.65504967e-02,\n",
+       "          1.17549729e-15,  2.71269829e-05,  3.10911591e-18, -1.37996439e-16,\n",
+       "          1.81008221e-16,  1.17788537e-05,  1.31720578e-05,  1.14999984e-05,\n",
+       "          6.24571783e-17]),\n",
+       "  array([ 1.68393833e-06, -5.25220266e-17,  1.00238159e+00,  2.37279523e-18,\n",
+       "          7.76059182e-08,  1.54137610e-20,  1.00000000e+00,  9.11949383e-16,\n",
+       "          3.29445743e-15,  8.05886260e-04,  3.96579902e-04,  1.09726042e-04,\n",
+       "         -3.95578968e-16, -6.34758594e-06, -4.27416344e-18,  6.62593232e-02,\n",
+       "          1.17065296e-15,  2.70047084e-05,  3.10389541e-18, -1.36513826e-16,\n",
+       "          1.92278897e-16,  1.44649997e-05,  1.46209230e-05,  1.20356844e-05,\n",
+       "          6.18495171e-17]),\n",
+       "  array([ 1.67760175e-06, -5.25266264e-17,  1.00244751e+00,  2.95531466e-18,\n",
+       "          9.10386094e-08,  1.69626771e-20,  1.00000000e+00,  9.11814395e-16,\n",
+       "          3.29466150e-15,  8.05903469e-04,  3.96596005e-04,  1.09738627e-04,\n",
+       "         -3.95517665e-16, -6.34770717e-06, -4.24854656e-18,  6.59249787e-02,\n",
+       "          1.16503887e-15,  2.68653824e-05,  3.09785872e-18, -1.34987966e-16,\n",
+       "          2.04072059e-16,  1.72084518e-05,  1.61025073e-05,  1.25852687e-05,\n",
+       "          6.13026151e-17]),\n",
+       "  array([ 1.67126703e-06, -5.25312877e-17,  1.00251306e+00,  3.53463615e-18,\n",
+       "          1.04392955e-07,  1.85084542e-20,  1.00000000e+00,  9.11680975e-16,\n",
+       "          3.29487788e-15,  8.05923478e-04,  3.96613621e-04,  1.09751776e-04,\n",
+       "         -3.95456849e-16, -6.34752892e-06, -4.23588859e-18,  6.55463582e-02,\n",
+       "          1.15864298e-15,  2.67086902e-05,  3.09158074e-18, -1.33420040e-16,\n",
+       "          2.16382759e-16,  2.00089506e-05,  1.76166529e-05,  1.31486729e-05,\n",
+       "          6.08155513e-17]),\n",
+       "  array([ 1.66493444e-06, -5.25360218e-17,  1.00257818e+00,  4.11036298e-18,\n",
+       "          1.17660115e-07,  2.00512473e-20,  1.00000000e+00,  9.11549164e-16,\n",
+       "          3.29510709e-15,  8.05946344e-04,  3.96632784e-04,  1.09765502e-04,\n",
+       "         -3.95396462e-16, -6.34705018e-06, -4.23623746e-18,  6.51223257e-02,\n",
+       "          1.15145365e-15,  2.65343216e-05,  3.08561272e-18, -1.31811238e-16,\n",
+       "          2.29204496e-16,  2.28661811e-05,  1.91631642e-05,  1.37257972e-05,\n",
+       "          6.03870757e-17]),\n",
+       "  array([ 1.65860423e-06, -5.25408399e-17,  1.00264283e+00,  4.68209278e-18,\n",
+       "          1.30831100e-07,  2.15914766e-20,  1.00000000e+00,  9.11419001e-16,\n",
+       "          3.29534962e-15,  8.05972124e-04,  3.96653526e-04,  1.09779818e-04,\n",
+       "         -3.95336447e-16, -6.34627012e-06, -4.24963334e-18,  6.46517144e-02,\n",
+       "          1.14345961e-15,  2.63419693e-05,  3.08048482e-18, -1.30162731e-16,\n",
+       "          2.42529272e-16,  2.57797716e-05,  2.07418079e-05,  1.43165205e-05,\n",
+       "          6.00156237e-17]),\n",
+       "  array([ 1.65227666e-06, -5.25457529e-17,  1.00270696e+00,  5.24941769e-18,\n",
+       "          1.43896764e-07,  2.31298159e-20,  1.00000000e+00,  9.11290526e-16,\n",
+       "          3.29560596e-15,  8.06000873e-04,  3.96675879e-04,  1.09794739e-04,\n",
+       "         -3.95276747e-16, -6.34518806e-06, -4.27610835e-18,  6.41333268e-02,\n",
+       "          1.13464981e-15,  2.61313278e-05,  3.07670472e-18, -1.28475658e-16,\n",
+       "          2.56347649e-16,  2.87492943e-05,  2.23523131e-05,  1.49207006e-05,\n",
+       "          5.96993306e-17]),\n",
+       "  array([ 1.64595198e-06, -5.25507718e-17,  1.00277053e+00,  5.81192439e-18,\n",
+       "          1.56847810e-07,  2.46671800e-20,  1.00000000e+00,  9.11163775e-16,\n",
+       "          3.29587661e-15,  8.06032647e-04,  3.96699873e-04,  1.09810277e-04,\n",
+       "         -3.95217311e-16, -6.34380353e-06, -4.31568626e-18,  6.35659350e-02,\n",
+       "          1.12501341e-15,  2.59020914e-05,  3.07475413e-18, -1.26751110e-16,\n",
+       "          2.70648819e-16,  3.17742648e-05,  2.39943713e-05,  1.55381745e-05,\n",
+       "          5.94360462e-17]),\n",
+       "  array([ 1.63963041e-06, -5.25559069e-17,  1.00283348e+00,  6.36919422e-18,\n",
+       "          1.69674787e-07,  2.62047093e-20,  1.00000000e+00,  9.11038784e-16,\n",
+       "          3.29616203e-15,  8.06067501e-04,  3.96725541e-04,  1.09826446e-04,\n",
+       "         -3.95158088e-16, -6.34211623e-06, -4.36838222e-18,  6.29482806e-02,\n",
+       "          1.11453965e-15,  2.56539539e-05,  3.07508430e-18, -1.24990117e-16,\n",
+       "          2.85420668e-16,  3.48541423e-05,  2.56676364e-05,  1.61687581e-05,\n",
+       "          5.92233515e-17]),\n",
+       "  array([ 1.63331221e-06, -5.25611688e-17,  1.00289576e+00,  6.92080313e-18,\n",
+       "          1.82368090e-07,  2.77437522e-20,  1.00000000e+00,  9.10915591e-16,\n",
+       "          3.29646268e-15,  8.06105490e-04,  3.96752912e-04,  1.09843258e-04,\n",
+       "         -3.95099029e-16, -6.34012606e-06, -4.43420240e-18,  6.22790751e-02,\n",
+       "          1.10321783e-15,  2.53866062e-05,  3.07811121e-18, -1.23193642e-16,\n",
+       "          3.00649844e-16,  3.79883295e-05,  2.73717254e-05,  1.68122474e-05,\n",
+       "          5.90585739e-17]),\n",
+       "  array([ 1.62699760e-06, -5.25665676e-17,  1.00295732e+00,  7.46632173e-18,\n",
+       "          1.94917958e-07,  2.92858448e-20,  1.00000000e+00,  9.10794228e-16,\n",
+       "          3.29677900e-15,  8.06146666e-04,  3.96782018e-04,  1.09860726e-04,\n",
+       "         -3.95040091e-16, -6.33783312e-06, -4.51314369e-18,  6.15570001e-02,\n",
+       "          1.09103720e-15,  2.50997362e-05,  3.08421051e-18, -1.21362567e-16,\n",
+       "          3.16321833e-16,  4.11761727e-05,  2.91062181e-05,  1.74684179e-05,\n",
+       "          5.89388047e-17]),\n",
+       "  array([ 1.62068681e-06, -5.25721132e-17,  1.00301810e+00,  8.00531522e-18,\n",
+       "          2.07314471e-07,  3.08326886e-20,  1.00000000e+00,  9.10674731e-16,\n",
+       "          3.29711143e-15,  8.06191083e-04,  3.96812889e-04,  1.09878863e-04,\n",
+       "         -3.94981230e-16, -6.33523775e-06, -4.60519330e-18,  6.07807074e-02,\n",
+       "          1.07798698e-15,  2.47930272e-05,  3.09371257e-18, -1.19497688e-16,\n",
+       "          3.32421022e-16,  4.44169620e-05,  3.08706575e-05,  1.81370254e-05,\n",
+       "          5.88609152e-17]),\n",
+       "  array([ 1.61438006e-06, -5.25778152e-17,  1.00307804e+00,  8.53734332e-18,\n",
+       "          2.19547550e-07,  3.23861251e-20,  1.00000000e+00,  9.10557131e-16,\n",
+       "          3.29746036e-15,  8.06238793e-04,  3.96845554e-04,  1.09897681e-04,\n",
+       "         -3.94922408e-16, -6.33234048e-06, -4.71032839e-18,  5.99488194e-02,\n",
+       "          1.06405620e-15,  2.44661570e-05,  3.10689773e-18, -1.17599709e-16,\n",
+       "          3.48930772e-16,  4.77099309e-05,  3.26645502e-05,  1.88178062e-05,\n",
+       "          5.88215735e-17]),\n",
+       "  array([ 1.60807757e-06, -5.25836831e-17,  1.00313710e+00,  9.06196019e-18,\n",
+       "          2.31606949e-07,  3.39481087e-20,  1.00000000e+00,  9.10441462e-16,\n",
+       "          3.29782619e-15,  8.06289847e-04,  3.96880041e-04,  1.09917192e-04,\n",
+       "         -3.94863591e-16, -6.32914209e-06, -4.82851570e-18,  5.90599295e-02,\n",
+       "          1.04923375e-15,  2.41187973e-05,  3.12399169e-18, -1.15669233e-16,\n",
+       "          3.65833481e-16,  5.10542565e-05,  3.44873663e-05,  1.95104776e-05,\n",
+       "          5.88172611e-17]),\n",
+       "  array([ 1.60177953e-06, -5.25897261e-17,  1.00319522e+00,  9.57871435e-18,\n",
+       "          2.43482255e-07,  3.55206773e-20,  1.00000000e+00,  9.10327755e-16,\n",
+       "          3.29820930e-15,  8.06344296e-04,  3.96916380e-04,  1.09937406e-04,\n",
+       "         -3.94804747e-16, -6.32564363e-06, -4.95971107e-18,  5.81126019e-02,\n",
+       "          1.03350831e-15,  2.37506130e-05,  3.14516132e-18, -1.13706762e-16,\n",
+       "          3.83110652e-16,  5.44490594e-05,  3.63385399e-05,  2.02147377e-05,\n",
+       "          5.88442888e-17]),\n",
+       "  array([ 1.59548616e-06, -5.25959530e-17,  1.00325232e+00,  1.00871485e-17,\n",
+       "          2.55162886e-07,  3.71059207e-20,  1.00000000e+00,  9.10216042e-16,\n",
+       "          3.29861004e-15,  8.06402190e-04,  3.96954597e-04,  1.09958337e-04,\n",
+       "         -3.94745848e-16, -6.32184635e-06, -5.10385898e-18,  5.71053726e-02,\n",
+       "          1.01686831e-15,  2.33612613e-05,  3.17051060e-18, -1.11712688e-16,\n",
+       "          4.00742956e-16,  5.78934040e-05,  3.82174691e-05,  2.09302665e-05,\n",
+       "          5.88988123e-17]),\n",
+       "  array([ 1.58919765e-06, -5.26023724e-17,  1.00330836e+00,  1.05867995e-17,\n",
+       "          2.66638081e-07,  3.87059475e-20,  1.00000000e+00,  9.10106355e-16,\n",
+       "          3.29902875e-15,  8.06463576e-04,  3.96994721e-04,  1.09979993e-04,\n",
+       "         -3.94686871e-16, -6.31775183e-06, -5.26089211e-18,  5.60367490e-02,\n",
+       "          9.99301911e-16,  2.29503915e-05,  3.20007706e-18, -1.09687298e-16,\n",
+       "          4.18710289e-16,  6.13862975e-05,  4.01235164e-05,  2.16567256e-05,\n",
+       "          5.89768478e-17]),\n",
+       "  array([ 1.58291419e-06, -5.26089926e-17,  1.00336326e+00,  1.10771980e-17,\n",
+       "          2.77896904e-07,  4.03228502e-20,  1.00000000e+00,  9.09998724e-16,\n",
+       "          3.29946575e-15,  8.06528503e-04,  3.97036777e-04,  1.10002387e-04,\n",
+       "         -3.94627797e-16, -6.31336190e-06, -5.43073075e-18,  5.49052112e-02,\n",
+       "          9.80797007e-16,  2.25176448e-05,  3.23382854e-18, -1.07630763e-16,\n",
+       "          4.36991829e-16,  6.49266907e-05,  4.20560088e-05,  2.23937588e-05,\n",
+       "          5.90742858e-17]),\n",
+       "  array([ 1.57663595e-06, -5.26158216e-17,  1.00341697e+00,  1.15578686e-17,\n",
+       "          2.88928231e-07,  4.19586689e-20,  1.00000000e+00,  9.09893181e-16,\n",
+       "          3.29992131e-15,  8.06597016e-04,  3.97080791e-04,  1.10025528e-04,\n",
+       "         -3.94568610e-16, -6.30867868e-06, -5.61328227e-18,  5.37092115e-02,\n",
+       "          9.61341199e-16,  2.20626536e-05,  3.27166028e-18, -1.05543147e-16,\n",
+       "          4.55566090e-16,  6.85134771e-05,  4.40142377e-05,  2.31409924e-05,\n",
+       "          5.91869057e-17]),\n",
+       "  array([ 1.57036312e-06, -5.26228670e-17,  1.00346942e+00,  1.20283295e-17,\n",
+       "          2.99720752e-07,  4.36153539e-20,  1.00000000e+00,  9.09789757e-16,\n",
+       "          3.30039572e-15,  8.06669161e-04,  3.97126788e-04,  1.10049426e-04,\n",
+       "         -3.94509299e-16, -6.30370463e-06, -5.80844052e-18,  5.24471753e-02,\n",
+       "          9.40921806e-16,  2.15850419e-05,  3.31339242e-18, -1.03424402e-16,\n",
+       "          4.74410970e-16,  7.21454928e-05,  4.59974593e-05,  2.38980352e-05,\n",
+       "          5.93103883e-17]),\n",
+       "  array([ 1.56409586e-06, -5.26301363e-17,  1.00352054e+00,  1.24880924e-17,\n",
+       "          3.10262964e-07,  4.52947270e-20,  1.00000000e+00,  9.09688482e-16,\n",
+       "          3.30088923e-15,  8.06744983e-04,  3.97174793e-04,  1.10074091e-04,\n",
+       "         -3.94449859e-16, -6.29844251e-06, -6.01608517e-18,  5.11175016e-02,\n",
+       "          9.19525869e-16,  2.10844251e-05,  3.35876801e-18, -1.01274370e-16,\n",
+       "          4.93503796e-16,  7.58215163e-05,  4.80048944e-05,  2.46644794e-05,\n",
+       "          5.94403283e-17]),\n",
+       "  array([ 1.55783432e-06, -5.26376365e-17,  1.00357026e+00,  1.29366625e-17,\n",
+       "          3.20543169e-07,  4.69984419e-20,  1.00000000e+00,  9.09589389e-16,\n",
+       "          3.30140205e-15,  8.06824523e-04,  3.97224829e-04,  1.10099531e-04,\n",
+       "         -3.94390287e-16, -6.29289545e-06, -6.23608111e-18,  4.97185633e-02,\n",
+       "          8.97140167e-16,  2.05604100e-05,  3.40745144e-18, -9.90927908e-17,\n",
+       "          5.12821366e-16,  7.95402677e-05,  5.00357288e-05,  2.54399001e-05,\n",
+       "          5.95722460e-17]),\n",
+       "  array([ 1.55157867e-06, -5.26453742e-17,  1.00361851e+00,  1.33735381e-17,\n",
+       "          3.30549467e-07,  4.87279450e-20,  1.00000000e+00,  9.09492510e-16,\n",
+       "          3.30193439e-15,  8.06907824e-04,  3.97276918e-04,  1.10125754e-04,\n",
+       "         -3.94330585e-16, -6.28706692e-06, -6.46827762e-18,  4.82487077e-02,\n",
+       "          8.73751245e-16,  2.00125954e-05,  3.45902742e-18, -9.68792987e-17,\n",
+       "          5.32339990e-16,  8.33004089e-05,  5.20891127e-05,  2.62238559e-05,\n",
+       "          5.97015980e-17]),\n",
+       "  array([ 1.54532904e-06, -5.26533558e-17,  1.00366521e+00,  1.37982108e-17,\n",
+       "          3.40269753e-07,  5.04844350e-20,  1.00000000e+00,  9.09397877e-16,\n",
+       "          3.30248642e-15,  8.06994924e-04,  3.97331082e-04,  1.10152770e-04,\n",
+       "         -3.94270761e-16, -6.28096077e-06, -6.71250771e-18,  4.67062573e-02,\n",
+       "          8.49345438e-16,  1.94405721e-05,  3.51300068e-18, -9.46334319e-17,\n",
+       "          5.52035515e-16,  8.71005421e-05,  5.41641613e-05,  2.70158894e-05,\n",
+       "          5.98237869e-17]),\n",
+       "  array([ 1.53908557e-06, -5.26615873e-17,  1.00371030e+00,  1.42101653e-17,\n",
+       "          3.49691715e-07,  5.22688231e-20,  1.00000000e+00,  9.09305522e-16,\n",
+       "          3.30305831e-15,  8.07085863e-04,  3.97387342e-04,  1.10180586e-04,\n",
+       "         -3.94210827e-16, -6.27458127e-06, -6.96858729e-18,  4.50895099e-02,\n",
+       "          8.23908918e-16,  1.88439239e-05,  3.56879662e-18, -9.23546361e-17,\n",
+       "          5.71883364e-16,  9.09392101e-05,  5.62599541e-05,  2.78155266e-05,\n",
+       "          5.99341721e-17]),\n",
+       "  array([ 1.53284838e-06, -5.26700743e-17,  1.00375370e+00,  1.46088792e-17,\n",
+       "          3.58802829e-07,  5.40816866e-20,  1.00000000e+00,  9.09215480e-16,\n",
+       "          3.30365017e-15,  8.07180678e-04,  3.97445718e-04,  1.10209208e-04,\n",
+       "         -3.94150799e-16, -6.26793309e-06, -7.23631430e-18,  4.33967397e-02,\n",
+       "          7.97427750e-16,  1.82222276e-05,  3.62574697e-18, -9.00422900e-17,\n",
+       "          5.91858577e-16,  9.48148949e-05,  5.83755350e-05,  2.86222777e-05,\n",
+       "          6.00280757e-17]),\n",
+       "  array([ 1.52661760e-06, -5.26788220e-17,  1.00379532e+00,  1.49938231e-17,\n",
+       "          3.67590356e-07,  5.59232398e-20,  1.00000000e+00,  9.09127784e-16,\n",
+       "          3.30426210e-15,  8.07279404e-04,  3.97506228e-04,  1.10238644e-04,\n",
+       "         -3.94090698e-16, -6.26102136e-06, -7.51546788e-18,  4.16261978e-02,\n",
+       "          7.69887911e-16,  1.75750540e-05,  3.68312588e-18, -8.76956692e-17,\n",
+       "          6.11935788e-16,  9.87260175e-05,  6.05099124e-05,  2.94356370e-05,\n",
+       "          6.01007919e-17]),\n",
+       "  array([ 1.52039333e-06, -5.26878353e-17,  1.00383510e+00,  1.53644608e-17,\n",
+       "          3.76041340e-07,  5.77932968e-20,  1.00000000e+00,  9.09042470e-16,\n",
+       "          3.30489419e-15,  8.07382075e-04,  3.97568890e-04,  1.10268899e-04,\n",
+       "         -3.94030551e-16, -6.25385166e-06, -7.80580739e-18,  3.97761125e-02,\n",
+       "          7.41275382e-16,  1.69019690e-05,  3.74013307e-18, -8.53139784e-17,\n",
+       "          6.32089280e-16,  1.02670937e-04,  6.26620583e-05,  3.02550831e-05,\n",
+       "          6.01475941e-17]),\n",
+       "  array([ 1.51417567e-06, -5.26971188e-17,  1.00387295e+00,  1.57202489e-17,\n",
+       "          3.84142607e-07,  5.96912130e-20,  1.00000000e+00,  9.08959574e-16,\n",
+       "          3.30554648e-15,  8.07488723e-04,  3.97633721e-04,  1.10299979e-04,\n",
+       "         -3.93970387e-16, -6.24643007e-06, -8.10707145e-18,  3.78446905e-02,\n",
+       "          7.11576233e-16,  1.62025341e-05,  3.79585106e-18, -8.28964187e-17,\n",
+       "          6.52293033e-16,  1.06647949e-04,  6.48309087e-05,  3.10800787e-05,\n",
+       "          6.01637415e-17]),\n",
+       "  array([ 1.50796471e-06, -5.27066765e-17,  1.00390878e+00,  1.60606373e-17,\n",
+       "          3.91880761e-07,  6.16158632e-20,  1.00000000e+00,  9.08879132e-16,\n",
+       "          3.30621900e-15,  8.07599379e-04,  3.97700736e-04,  1.10331889e-04,\n",
+       "         -3.93910242e-16, -6.23876317e-06, -8.41897696e-18,  3.58301175e-02,\n",
+       "          6.80776663e-16,  1.54763076e-05,  3.84931862e-18, -8.04421094e-17,\n",
+       "          6.72520680e-16,  1.10655285e-04,  6.70153629e-05,  3.19100712e-05,\n",
+       "          6.01444867e-17]),\n",
+       "  array([ 1.50176053e-06, -5.27165121e-17,  1.00394251e+00,  1.63850688e-17,\n",
+       "          3.99242184e-07,  6.35656188e-20,  1.00000000e+00,  9.08801181e-16,\n",
+       "          3.30691175e-15,  8.07714070e-04,  3.97769950e-04,  1.10364634e-04,\n",
+       "         -3.93850157e-16, -6.23085809e-06, -8.74121801e-18,  3.37305588e-02,\n",
+       "          6.48863089e-16,  1.47228457e-05,  3.89952902e-18, -7.79501071e-17,\n",
+       "          6.92745535e-16,  1.14691115e-04,  6.92142833e-05,  3.27444919e-05,\n",
+       "          6.00850800e-17]),\n",
+       "  array([ 1.49556322e-06, -5.27266290e-17,  1.00397405e+00,  1.66929799e-17,\n",
+       "          4.06213036e-07,  6.55382869e-20,  1.00000000e+00,  9.08725762e-16,\n",
+       "          3.30762469e-15,  8.07832823e-04,  3.97841377e-04,  1.10398216e-04,\n",
+       "         -3.93790177e-16, -6.22272254e-06, -9.07346478e-18,  3.15441601e-02,\n",
+       "          6.15822272e-16,  1.39417041e-05,  3.94535354e-18, -7.54195219e-17,\n",
+       "          7.12940655e-16,  1.18753538e-04,  7.14264950e-05,  3.35827571e-05,\n",
+       "          5.99807737e-17]),\n",
+       "  array([ 1.48937283e-06, -5.27370300e-17,  1.00400332e+00,  1.69838006e-17,\n",
+       "          4.12779255e-07,  6.75310965e-20,  1.00000000e+00,  9.08652913e-16,\n",
+       "          3.30835777e-15,  8.07955664e-04,  3.97915027e-04,  1.10432641e-04,\n",
+       "         -3.93730350e-16, -6.21436480e-06, -9.41536240e-18,  2.92690485e-02,\n",
+       "          5.81641385e-16,  1.31324388e-05,  3.98563628e-18, -7.28494182e-17,\n",
+       "          7.33078793e-16,  1.22840590e-04,  7.36507854e-05,  3.44242673e-05,\n",
+       "          5.98268312e-17]),\n",
+       "  array([ 1.48318941e-06, -5.27477178e-17,  1.00403022e+00,  1.72569547e-17,\n",
+       "          4.18926559e-07,  6.95406880e-20,  1.00000000e+00,  9.08582674e-16,\n",
+       "          3.30911090e-15,  8.08082614e-04,  3.97990913e-04,  1.10467909e-04,\n",
+       "         -3.93670731e-16, -6.20579380e-06, -9.76652980e-18,  2.69033336e-02,\n",
+       "          5.46308114e-16,  1.22946079e-05,  4.01919976e-18, -7.02388306e-17,\n",
+       "          7.53132425e-16,  1.26950237e-04,  7.58859040e-05,  3.52684073e-05,\n",
+       "          5.96185292e-17]),\n",
+       "  array([ 1.47701301e-06, -5.27586942e-17,  1.00405467e+00,  1.75118601e-17,\n",
+       "          4.24640446e-07,  7.15630867e-20,  1.00000000e+00,  9.08515087e-16,\n",
+       "          3.30988398e-15,  8.08213694e-04,  3.98069044e-04,  1.10504024e-04,\n",
+       "         -3.93611380e-16, -6.19701910e-06, -1.01265585e-17,  2.44451077e-02,\n",
+       "          5.09810797e-16,  1.14277735e-05,  4.04481367e-18, -6.75868292e-17,\n",
+       "          7.73073775e-16,  1.31080379e-04,  7.81305616e-05,  3.61145467e-05,\n",
+       "          5.93511661e-17]),\n",
+       "  array([ 1.47084367e-06, -5.27699612e-17,  1.00407656e+00,  1.77479294e-17,\n",
+       "          4.29906197e-07,  7.35936296e-20,  1.00000000e+00,  9.08450194e-16,\n",
+       "          3.31067685e-15,  8.08348923e-04,  3.98149427e-04,  1.10540986e-04,\n",
+       "         -3.93552360e-16, -6.18805098e-06, -1.04950112e-17,  2.18924475e-02,\n",
+       "          4.72138565e-16,  1.05315026e-05,  4.06110186e-18, -6.48926658e-17,\n",
+       "          7.92874864e-16,  1.35228842e-04,  8.03834301e-05,  3.69620394e-05,\n",
+       "          5.90200655e-17]),\n",
+       "  array([ 1.46468140e-06, -5.27815198e-17,  1.00409580e+00,  1.79645701e-17,\n",
+       "          4.34708882e-07,  7.56270311e-20,  1.00000000e+00,  9.08388039e-16,\n",
+       "          3.31148936e-15,  8.08488317e-04,  3.98232071e-04,  1.10578796e-04,\n",
+       "         -3.93493739e-16, -6.17890041e-06, -1.08714208e-17,  1.92434148e-02,\n",
+       "          4.33281404e-16,  9.60536975e-06,  4.06681881e-18, -6.21554540e-17,\n",
+       "          8.12507425e-16,  1.39393384e-04,  8.26431421e-05,  3.78102237e-05,\n",
+       "          5.86205895e-17]),\n",
+       "  array([ 1.45852624e-06, -5.27933711e-17,  1.00411230e+00,  1.81611853e-17,\n",
+       "          4.39033361e-07,  7.76573058e-20,  1.00000000e+00,  9.08328664e-16,\n",
+       "          3.31232130e-15,  8.08631888e-04,  3.98316979e-04,  1.10617454e-04,\n",
+       "         -3.93435591e-16, -6.16957913e-06, -1.12552888e-17,  1.64960574e-02,\n",
+       "          3.93230370e-16,  8.64895855e-06,  4.06056495e-18, -5.93745652e-17,\n",
+       "          8.31943031e-16,  1.43571688e-04,  8.49082904e-05,  3.86584225e-05,\n",
+       "          5.81481339e-17]),\n",
+       "  array([ 1.45237818e-06, -5.28055153e-17,  1.00412595e+00,  1.83371741e-17,\n",
+       "          4.42864293e-07,  7.96778143e-20,  1.00000000e+00,  9.08272115e-16,\n",
+       "          3.31317245e-15,  8.08779650e-04,  3.98404156e-04,  1.10656960e-04,\n",
+       "         -3.93377993e-16, -6.16009968e-06, -1.16460841e-17,  1.36484103e-02,\n",
+       "          3.51977677e-16,  7.66186379e-06,  4.04103245e-18, -5.65493528e-17,\n",
+       "          8.51153032e-16,  1.47761366e-04,  8.71774275e-05,  3.95059430e-05,\n",
+       "          5.75981460e-17]),\n",
+       "  array([ 1.44623721e-06, -5.28179525e-17,  1.00413665e+00,  1.84919325e-17,\n",
+       "          4.46186140e-07,  8.16812697e-20,  1.00000000e+00,  9.08218436e-16,\n",
+       "          3.31404256e-15,  8.08931610e-04,  3.98493605e-04,  1.10697312e-04,\n",
+       "         -3.93321027e-16, -6.15047541e-06, -1.20432417e-17,  1.06984971e-02,\n",
+       "          3.09516879e-16,  6.64369375e-06,  4.00692601e-18, -5.36792926e-17,\n",
+       "          8.70108615e-16,  1.51959953e-04,  8.94490652e-05,  4.03520770e-05,\n",
+       "          5.69661268e-17]),\n",
+       "  array([ 1.44010333e-06, -5.28306824e-17,  1.00414429e+00,  1.86248541e-17,\n",
+       "          4.48983176e-07,  8.36597446e-20,  1.00000000e+00,  9.08167671e-16,\n",
+       "          3.31493134e-15,  8.09087775e-04,  3.98585327e-04,  1.10738508e-04,\n",
+       "         -3.93264779e-16, -6.14072053e-06, -1.24461612e-17,  7.64433055e-03,\n",
+       "          2.65843038e-16,  5.59407243e-06,  3.95696499e-18, -5.07640220e-17,\n",
+       "          8.88780833e-16,  1.56164910e-04,  9.17216742e-05,  4.11961007e-05,\n",
+       "          5.62476439e-17]),\n",
+       "  array([ 1.43397652e-06, -5.28437042e-17,  1.00414877e+00,  1.87353305e-17,\n",
+       "          4.51239497e-07,  8.56046888e-20,  1.00000000e+00,  9.08119868e-16,\n",
+       "          3.31583848e-15,  8.09248148e-04,  3.98679321e-04,  1.10780546e-04,\n",
+       "         -3.93209341e-16, -6.13085017e-06, -1.28542054e-17,  4.48391445e-03,\n",
+       "          2.20952893e-16,  4.51264208e-06,  3.88990351e-18, -4.78033611e-17,\n",
+       "          9.07140638e-16,  1.60373620e-04,  9.39936837e-05,  4.20372747e-05,\n",
+       "          5.54383438e-17]),\n",
+       "  array([ 1.42785674e-06, -5.28570165e-17,  1.00414999e+00,  1.88227530e-17,\n",
+       "          4.52939030e-07,  8.75069213e-20,  1.00000000e+00,  9.08075071e-16,\n",
+       "          3.31676364e-15,  8.09412732e-04,  3.98775584e-04,  1.10823420e-04,\n",
+       "         -3.93154807e-16, -6.12088037e-06, -1.32666991e-17,  1.21524440e-03,\n",
+       "          1.74845054e-16,  3.39906581e-06,  3.80448015e-18, -4.47974273e-17,\n",
+       "          9.25158935e-16,  1.64583387e-04,  9.62634809e-05,  4.28748443e-05,\n",
+       "          5.45339624e-17]),\n",
+       "  array([ 1.42174395e-06, -5.28706178e-17,  1.00414783e+00,  1.88865131e-17,\n",
+       "          4.54065545e-07,  8.93567347e-20,  1.00000000e+00,  9.08033324e-16,\n",
+       "          3.31770645e-15,  8.09581523e-04,  3.98874114e-04,  1.10867128e-04,\n",
+       "         -3.93101277e-16, -6.11082818e-06, -1.36829276e-17, -2.16369069e-03,\n",
+       "          1.27520164e-16,  2.25303031e-06,  3.69964217e-18, -4.17464047e-17,\n",
+       "          9.42806584e-16,  1.68791439e-04,  9.85294107e-05,  4.37080390e-05,\n",
+       "          5.35303433e-17]),\n",
+       "  array([ 1.41563810e-06, -5.28845062e-17,  1.00414217e+00,  1.89260037e-17,\n",
+       "          4.54602670e-07,  9.11439069e-20,  1.00000000e+00,  9.07994673e-16,\n",
+       "          3.31866650e-15,  8.09754518e-04,  3.98974903e-04,  1.10911665e-04,\n",
+       "         -3.93048853e-16, -6.10071166e-06, -1.41021351e-17, -5.65490723e-03,\n",
+       "          7.89811293e-17,  1.07424877e-06,  3.57436006e-18, -3.86508399e-17,\n",
+       "          9.60054503e-16,  1.72994920e-04,  1.00789775e-04,  4.45360733e-05,\n",
+       "          5.24234458e-17]),\n",
+       "  array([ 1.40953913e-06, -5.28986790e-17,  1.00413291e+00,  1.89406203e-17,\n",
+       "          4.54533902e-07,  9.28577842e-20,  1.00000000e+00,  9.07959162e-16,\n",
+       "          3.31964338e-15,  8.09931709e-04,  3.99077946e-04,  1.10957023e-04,\n",
+       "         -3.92997644e-16, -6.09054990e-06, -1.45235240e-17, -9.26042563e-03,\n",
+       "          2.92333192e-17, -1.37536080e-07,  3.42777036e-18, -3.55115224e-17,\n",
+       "          9.76873705e-16,  1.77190896e-04,  1.03042833e-04,  4.53581459e-05,\n",
+       "          5.12093668e-17]),\n",
+       "  array([ 1.40344697e-06, -5.29131336e-17,  1.00411993e+00,  1.89297627e-17,\n",
+       "          4.53842627e-07,  9.44874718e-20,  1.00000000e+00,  9.07926833e-16,\n",
+       "          3.32063661e-15,  8.10113085e-04,  3.99183233e-04,  1.11003196e-04,\n",
+       "         -3.92947760e-16, -6.08036313e-06, -1.49462528e-17, -1.29822688e-02,\n",
+       "         -2.17152439e-17, -1.38254875e-06,  3.25939154e-18, -3.23292744e-17,\n",
+       "          9.93235333e-16,  1.81376348e-04,  1.05286801e-04,  4.61734405e-05,\n",
+       "          4.98843634e-17]),\n",
+       "  array([ 1.39736155e-06, -5.29278668e-17,  1.00410311e+00,  1.88928359e-17,\n",
+       "          4.52512139e-07,  9.60217849e-20,  1.00000000e+00,  9.07897727e-16,\n",
+       "          3.32164572e-15,  8.10298633e-04,  3.99290753e-04,  1.11050177e-04,\n",
+       "         -3.92899315e-16, -6.07017269e-06, -1.53694354e-17, -1.68224606e-02,\n",
+       "         -7.38535732e-17, -2.66097763e-06,  3.06864304e-18, -2.91056329e-17,\n",
+       "          1.00911085e-15,  1.85548175e-04,  1.07519849e-04,  4.69811252e-05,\n",
+       "          4.84448663e-17]),\n",
+       "  array([ 1.39128278e-06, -5.29428750e-17,  1.00408232e+00,  1.88292522e-17,\n",
+       "          4.50525653e-07,  9.74493561e-20,  1.00000000e+00,  9.07871885e-16,\n",
+       "          3.32267020e-15,  8.10488336e-04,  3.99400493e-04,  1.11097958e-04,\n",
+       "         -3.92852427e-16, -6.06000113e-06, -1.57921396e-17, -2.07830245e-02,\n",
+       "         -1.27167519e-16, -3.97297140e-06,  2.85515991e-18, -2.58425238e-17,\n",
+       "          1.02447207e-15,  1.89703192e-04,  1.09740107e-04,  4.77803530e-05,\n",
+       "          4.68875148e-17]),\n",
+       "  array([ 1.38521057e-06, -5.29581542e-17,  1.00405746e+00,  1.87384324e-17,\n",
+       "          4.47866335e-07,  9.87589302e-20,  1.00000000e+00,  9.07849343e-16,\n",
+       "          3.32370949e-15,  8.10682175e-04,  3.99512439e-04,  1.11146528e-04,\n",
+       "         -3.92807218e-16, -6.04987221e-06, -1.62133860e-17, -2.48659817e-02,\n",
+       "         -1.81639560e-16, -5.31863532e-06,  2.61916653e-18, -2.25418645e-17,\n",
+       "          1.03929120e-15,  1.93838128e-04,  1.11945656e-04,  4.85702616e-05,\n",
+       "          4.52091817e-17]),\n",
+       "  array([ 1.37914482e-06, -5.29737002e-17,  1.00402838e+00,  1.86198082e-17,\n",
+       "          4.44517322e-07,  9.99395007e-20,  1.00000000e+00,  9.07830137e-16,\n",
+       "          3.32476303e-15,  8.10880124e-04,  3.99626573e-04,  1.11195878e-04,\n",
+       "         -3.92763811e-16, -6.03981094e-06, -1.66321470e-17, -2.90733496e-02,\n",
+       "         -2.37248488e-16, -6.69802719e-06,  2.36116024e-18, -1.92060449e-17,\n",
+       "          1.05354104e-15,  1.97949627e-04,  1.14134534e-04,  4.93499736e-05,\n",
+       "          4.34069945e-17]),\n",
+       "  array([ 1.37308541e-06, -5.29895084e-17,  1.00399498e+00,  1.84728236e-17,\n",
+       "          4.40461745e-07,  1.00980332e-19,  1.00000000e+00,  9.07814298e-16,\n",
+       "          3.32583022e-15,  8.11082158e-04,  3.99742878e-04,  1.11245996e-04,\n",
+       "         -3.92722333e-16, -6.02984366e-06, -1.70473457e-17, -3.34071401e-02,\n",
+       "         -2.93969094e-16, -8.11115308e-06,  2.08168358e-18, -1.58382978e-17,\n",
+       "          1.06719514e-15,  2.02034245e-04,  1.16304737e-04,  5.01185966e-05,\n",
+       "          4.14783701e-17]),\n",
+       "  array([ 1.36703223e-06, -5.30055738e-17,  1.00395711e+00,  1.82969376e-17,\n",
+       "          4.35682764e-07,  1.01871278e-19,  1.00000000e+00,  9.07801856e-16,\n",
+       "          3.32691045e-15,  8.11288247e-04,  3.99861332e-04,  1.11296872e-04,\n",
+       "         -3.92682912e-16, -6.01999805e-06, -1.74578553e-17, -3.78693578e-02,\n",
+       "         -3.51771957e-16, -9.55796262e-06,  1.78191240e-18, -1.24420337e-17,\n",
+       "          1.08022787e-15,  2.06088452e-04,  1.18454210e-04,  5.08752233e-05,\n",
+       "          3.94210627e-17]),\n",
+       "  array([ 1.36098516e-06, -5.30218912e-17,  1.00391465e+00,  1.80916261e-17,\n",
+       "          4.30163592e-07,  1.02602988e-19,  1.00000000e+00,  9.07792835e-16,\n",
+       "          3.32800307e-15,  8.11498356e-04,  3.99981913e-04,  1.11348491e-04,\n",
+       "         -3.92645678e-16, -6.01030315e-06, -1.78624979e-17, -4.24619981e-02,\n",
+       "         -4.10623098e-16, -1.10383439e-05,  1.46344279e-18, -9.02119575e-18,\n",
+       "          1.09261460e-15,  2.10108629e-04,  1.20580858e-04,  5.16189320e-05,\n",
+       "          3.72331877e-17]),\n",
+       "  array([ 1.35494407e-06, -5.30384549e-17,  1.00386746e+00,  1.78563842e-17,\n",
+       "          4.23887533e-07,  1.03167152e-19,  1.00000000e+00,  9.07787255e-16,\n",
+       "          3.32910740e-15,  8.11712447e-04,  4.00104595e-04,  1.11400839e-04,\n",
+       "         -3.92610765e-16, -6.00078946e-06, -1.82600445e-17, -4.71870456e-02,\n",
+       "         -4.70483667e-16, -1.25521174e-05,  1.12835405e-18, -5.58025757e-18,\n",
+       "          1.10433190e-15,  2.14091069e-04,  1.22682539e-04,  5.23487867e-05,\n",
+       "          3.49132679e-17]),\n",
+       "  array([ 1.34890883e-06, -5.30552593e-17,  1.00381541e+00,  1.75907294e-17,\n",
+       "          4.16838018e-07,  1.03556764e-19,  1.00000000e+00,  9.07785131e-16,\n",
+       "          3.33022276e-15,  8.11930479e-04,  4.00229353e-04,  1.11453903e-04,\n",
+       "         -3.92578305e-16, -5.99148892e-06, -1.86492142e-17, -5.20464719e-02,\n",
+       "         -5.31309600e-16, -1.40990295e-05,  7.79249446e-19, -2.12424272e-18,\n",
+       "          1.11535769e-15,  2.18031976e-04,  1.24757067e-04,  5.30638387e-05,\n",
+       "          3.24602790e-17]),\n",
+       "  array([ 1.34287929e-06, -5.30722980e-17,  1.00375837e+00,  1.72942038e-17,\n",
+       "          4.08998647e-07,  1.03766393e-19,  1.00000000e+00,  9.07786472e-16,\n",
+       "          3.33134843e-15,  8.12152406e-04,  4.00356155e-04,  1.11507666e-04,\n",
+       "         -3.92548431e-16, -5.98243498e-06, -1.90286740e-17, -5.70422334e-02,\n",
+       "         -5.93051261e-16, -1.56787439e-05,  4.19288126e-19,  1.34125518e-18,\n",
+       "          1.12567150e-15,  2.21927468e-04,  1.26802213e-04,  5.37631277e-05,\n",
+       "          2.98737011e-17]),\n",
+       "  array([ 1.33685530e-06, -5.30895649e-17,  1.00369619e+00,  1.69663773e-17,\n",
+       "          4.00353231e-07,  1.03792481e-19,  1.00000000e+00,  9.07791282e-16,\n",
+       "          3.33248368e-15,  8.12378180e-04,  4.00484970e-04,  1.11562112e-04,\n",
+       "         -3.92521278e-16, -5.97366260e-06, -1.93970392e-17, -6.21762698e-02,\n",
+       "         -6.55653040e-16, -1.72908314e-05,  5.22050571e-20,  4.81005417e-18,\n",
+       "          1.13525462e-15,  2.25773577e-04,  1.28815709e-04,  5.44456843e-05,\n",
+       "          2.71535742e-17]),\n",
+       "  array([ 1.33083672e-06, -5.31070532e-17,  1.00362874e+00,  1.66068508e-17,\n",
+       "          3.90885852e-07,  1.03633620e-19,  1.00000000e+00,  9.07799557e-16,\n",
+       "          3.33362777e-15,  8.12607746e-04,  4.00615766e-04,  1.11617223e-04,\n",
+       "         -3.92496977e-16, -5.96520834e-06, -1.97528730e-17, -6.74505016e-02,\n",
+       "         -7.19052921e-16, -1.89347573e-05, -3.17686744e-19,  8.27536800e-18,\n",
+       "          1.14409042e-15,  2.29566250e-04,  1.30795250e-04,  5.51105341e-05,\n",
+       "          2.43005633e-17]),\n",
+       "  array([ 1.32482340e-06, -5.31247563e-17,  1.00355588e+00,  1.62152598e-17,\n",
+       "          3.80580920e-07,  1.03290843e-19,  1.00000000e+00,  9.07811287e-16,\n",
+       "          3.33477994e-15,  8.12841047e-04,  4.00748504e-04,  1.11672979e-04,\n",
+       "         -3.92475661e-16, -5.95711034e-06, -2.00946876e-17, -7.28668279e-02,\n",
+       "         -7.83181988e-16, -2.06098641e-05, -6.85519480e-19,  1.17297930e-17,\n",
+       "          1.15216455e-15,  2.33301358e-04,  1.32738503e-04,  5.57567035e-05,\n",
+       "          2.13160332e-17]),\n",
+       "  array([ 1.31881517e-06, -5.31426670e-17,  1.00347745e+00,  1.57912779e-17,\n",
+       "          3.69423246e-07,  1.02767857e-19,  1.00000000e+00,  9.07826452e-16,\n",
+       "          3.33593940e-15,  8.13078022e-04,  4.00883147e-04,  1.11729362e-04,\n",
+       "         -3.92457459e-16, -5.94940841e-06, -2.04209444e-17, -7.84271241e-02,\n",
+       "         -8.47963861e-16, -2.23153487e-05, -1.04593154e-18,  1.51652970e-17,\n",
+       "          1.15946525e-15,  2.36974700e-04,  1.34643115e-04,  5.63832290e-05,\n",
+       "          1.82021371e-17]),\n",
+       "  array([ 1.31281188e-06, -5.31607784e-17,  1.00339332e+00,  1.53346209e-17,\n",
+       "          3.57398130e-07,  1.02071246e-19,  1.00000000e+00,  9.07845026e-16,\n",
+       "          3.33710539e-15,  8.13318604e-04,  4.01019654e-04,  1.11786352e-04,\n",
+       "         -3.92442497e-16, -5.94214400e-06, -2.07300556e-17, -8.41332402e-02,\n",
+       "         -9.13314026e-16, -2.40502323e-05, -1.39318050e-18,  1.85732101e-17,\n",
+       "          1.16598365e-15,  2.40582016e-04,  1.36506727e-04,  5.69891703e-05,\n",
+       "          1.49619247e-17]),\n",
+       "  array([ 1.30681335e-06, -5.31790830e-17,  1.00330333e+00,  1.48450514e-17,\n",
+       "          3.44491471e-07,  1.01210558e-19,  1.00000000e+00,  9.07866970e-16,\n",
+       "          3.33827710e-15,  8.13562723e-04,  4.01157981e-04,  1.11843925e-04,\n",
+       "         -3.92430897e-16, -5.93536030e-06, -2.10203850e-17, -8.99869973e-02,\n",
+       "         -9.79139028e-16, -2.58133177e-05, -1.72133051e-18,  2.19442156e-17,\n",
+       "          1.17171410e-15,  2.44119003e-04,  1.38327001e-04,  5.75736310e-05,\n",
+       "          1.15994757e-17]),\n",
+       "  array([ 1.30081944e-06, -5.31975734e-17,  1.00320734e+00,  1.43223837e-17,\n",
+       "          3.30689905e-07,  1.00198262e-19,  1.00000000e+00,  9.07892238e-16,\n",
+       "          3.33945375e-15,  8.13810304e-04,  4.01298083e-04,  1.11902061e-04,\n",
+       "         -3.92422777e-16, -5.92910225e-06, -2.12902501e-17, -9.59901863e-02,\n",
+       "         -1.04533547e-15, -2.76031317e-05, -2.02454244e-18,  2.52683398e-17,\n",
+       "          1.17665455e-15,  2.47581345e-04,  1.40101649e-04,  5.81357874e-05,\n",
+       "          8.12006687e-18]),\n",
+       "  array([ 1.29482997e-06, -5.32162422e-17,  1.00310519e+00,  1.37664893e-17,\n",
+       "          3.15980983e-07,  9.90494814e-20,  1.00000000e+00,  9.07920773e-16,\n",
+       "          3.34063456e-15,  8.14061269e-04,  4.01439911e-04,  1.11960736e-04,\n",
+       "         -3.92418247e-16, -5.92341660e-06, -2.15379238e-17, -1.02144565e-01,\n",
+       "         -1.11178874e-15, -2.94178441e-05, -2.29750668e-18,  2.85349363e-17,\n",
+       "          1.18080692e-15,  2.50964743e-04,  1.41828482e-04,  5.86749312e-05,\n",
+       "          4.53038172e-18]),\n",
+       "  array([ 1.28884478e-06, -5.32350818e-17,  1.00299674e+00,  1.31773036e-17,\n",
+       "          3.00353405e-07,  9.77814170e-20,  1.00000000e+00,  9.07952506e-16,\n",
+       "          3.34181874e-15,  8.14315534e-04,  4.01583417e-04,  1.12019927e-04,\n",
+       "         -3.92417408e-16, -5.91835198e-06, -2.17616367e-17, -1.08451854e-01,\n",
+       "         -1.17837144e-15, -3.12551551e-05, -2.53607094e-18,  3.17326649e-17,\n",
+       "          1.18417750e-15,  2.54264977e-04,  1.43505481e-04,  5.91905311e-05,\n",
+       "          8.38773807e-19]),\n",
+       "  array([ 1.28286369e-06, -5.32540844e-17,  1.00288183e+00,  1.25548329e-17,\n",
+       "          2.83797336e-07,  9.64123179e-20,  1.00000000e+00,  9.07987355e-16,\n",
+       "          3.34300552e-15,  8.14573012e-04,  4.01728548e-04,  1.12079609e-04,\n",
+       "         -3.92420353e-16, -5.91395893e-06, -2.19595800e-17, -1.14913738e-01,\n",
+       "         -1.24494128e-15, -3.31121380e-05, -2.73813572e-18,  3.48494616e-17,\n",
+       "          1.18677733e-15,  2.57477980e-04,  1.45130897e-04,  5.96823209e-05,\n",
+       "         -2.94440974e-18]),\n",
+       "  array([ 1.27688654e-06, -5.32732423e-17,  1.00276030e+00,  1.18991637e-17,\n",
+       "          2.66304827e-07,  9.49598285e-20,  1.00000000e+00,  9.08025228e-16,\n",
+       "          3.34419414e-15,  8.14833612e-04,  4.01875251e-04,  1.12139759e-04,\n",
+       "         -3.92427159e-16, -5.91029008e-06, -2.21299081e-17, -1.21531858e-01,\n",
+       "         -1.31133842e-15, -3.49850176e-05, -2.90491180e-18,  3.78725037e-17,\n",
+       "          1.18862253e-15,  2.60599953e-04,  1.46703392e-04,  6.01504258e-05,\n",
+       "         -6.80644216e-18]),\n",
+       "  array([ 1.27091317e-06, -5.32925479e-17,  1.00263199e+00,  1.12104727e-17,\n",
+       "          2.47870397e-07,  9.34384595e-20,  1.00000000e+00,  9.08066016e-16,\n",
+       "          3.34538387e-15,  8.15097240e-04,  4.02023473e-04,  1.12200355e-04,\n",
+       "         -3.92437891e-16, -5.90740020e-06, -2.22707427e-17, -1.28307813e-01,\n",
+       "         -1.37738201e-15, -3.68688603e-05, -3.04266615e-18,  4.07881819e-17,\n",
+       "          1.18973443e-15,  2.63627524e-04,  1.48222247e-04,  6.05955426e-05,\n",
+       "         -1.07317835e-17]),\n",
+       "  array([ 1.26494340e-06, -5.33119934e-17,  1.00249675e+00,  1.04890399e-17,\n",
+       "          2.28491829e-07,  9.18558609e-20,  1.00000000e+00,  9.08109598e-16,\n",
+       "          3.34657401e-15,  8.15363797e-04,  4.02173161e-04,  1.12261374e-04,\n",
+       "         -3.92452592e-16, -5.90534642e-06, -2.23801755e-17, -1.35243154e-01,\n",
+       "         -1.44286570e-15, -3.87571371e-05, -3.16512026e-18,  4.35821109e-17,\n",
+       "          1.19013925e-15,  2.66557980e-04,  1.49687654e-04,  6.10191960e-05,\n",
+       "         -1.47016472e-17]),\n",
+       "  array([ 1.25897706e-06, -5.33315710e-17,  1.00235441e+00,  9.73526383e-18,\n",
+       "          2.08171275e-07,  9.02074649e-20,  1.00000000e+00,  9.08155837e-16,\n",
+       "          3.34776388e-15,  8.15633187e-04,  4.02324262e-04,  1.12322798e-04,\n",
+       "         -3.92471286e-16, -5.90418843e-06, -2.24562741e-17, -1.42339383e-01,\n",
+       "         -1.50755207e-15, -4.06411079e-05, -3.29671022e-18,  4.62392447e-17,\n",
+       "          1.18986700e-15,  2.69389596e-04,  1.51101129e-04,  6.14241037e-05,\n",
+       "         -1.86936796e-17]),\n",
+       "  array([ 1.25301396e-06, -5.33512728e-17,  1.00220481e+00,  8.94968110e-18,\n",
+       "          1.86916798e-07,  8.84689375e-20,  1.00000000e+00,  9.08204581e-16,\n",
+       "          3.34895283e-15,  8.15905309e-04,  4.02476728e-04,  1.12384613e-04,\n",
+       "         -3.92493968e-16, -5.90398883e-06, -2.24970859e-17, -1.49597949e-01,\n",
+       "         -1.57116547e-15, -4.25089533e-05, -3.47696803e-18,  4.87442345e-17,\n",
+       "          1.18894890e-15,  2.72122094e-04,  1.52466103e-04,  6.18146942e-05,\n",
+       "         -2.26819865e-17]),\n",
+       "  array([ 1.24705393e-06, -5.33710911e-17,  1.00204779e+00,  8.13298941e-18,\n",
+       "          1.64744524e-07,  8.65857270e-20,  1.00000000e+00,  9.08255664e-16,\n",
+       "          3.35014024e-15,  8.16180066e-04,  4.02630517e-04,  1.12446811e-04,\n",
+       "         -3.92520606e-16, -5.90481353e-06, -2.25006457e-17, -1.57020246e-01,\n",
+       "         -1.63338338e-15, -4.43445478e-05, -3.76632935e-18,  5.10822877e-17,\n",
+       "          1.18741213e-15,  2.74757314e-04,  1.53788762e-04,  6.21978410e-05,\n",
+       "         -2.66379691e-17]),\n",
+       "  array([ 1.24109676e-06, -5.33910180e-17,  1.00188318e+00,  7.28607629e-18,\n",
+       "          1.41681662e-07,  8.44588329e-20,  1.00000000e+00,  9.08308905e-16,\n",
+       "          3.35132551e-15,  8.16457367e-04,  4.02785596e-04,  1.12509395e-04,\n",
+       "         -3.92551139e-16, -5.90673235e-06, -2.24649839e-17, -1.64607609e-01,\n",
+       "         -1.69382625e-15, -4.61257246e-05, -4.25369219e-18,  5.32410213e-17,\n",
+       "          1.18527009e-15,  2.77300156e-04,  1.55079238e-04,  6.25839007e-05,\n",
+       "         -3.05328688e-17]),\n",
+       "  array([ 1.23514222e-06, -5.34110455e-17,  1.00171082e+00,  6.41005333e-18,\n",
+       "          1.17770754e-07,  8.19257910e-20,  1.00000000e+00,  9.08364119e-16,\n",
+       "          3.35250802e-15,  8.16737127e-04,  4.02941949e-04,  1.12572383e-04,\n",
+       "         -3.92585483e-16, -5.90981976e-06, -2.23881383e-17, -1.72361311e-01,\n",
+       "         -1.75204592e-15, -4.78218166e-05, -5.06598358e-18,  5.52142498e-17,\n",
+       "          1.18250518e-15,  2.79759941e-04,  1.56353293e-04,  6.29881672e-05,\n",
+       "         -3.43437982e-17]),\n",
+       "  array([ 1.22919005e-06, -5.34311653e-17,  1.00153054e+00,  5.50629670e-18,\n",
+       "          9.30756727e-08,  7.87358903e-20,  1.00000000e+00,  9.08421129e-16,\n",
+       "          3.35368706e-15,  8.17019279e-04,  4.03099584e-04,  1.12635816e-04,\n",
+       "         -3.92623550e-16, -5.91415600e-06, -2.22681701e-17, -1.80282558e-01,\n",
+       "         -1.80751326e-15, -4.93901620e-05, -6.37969762e-18,  5.70095609e-17,\n",
+       "          1.17904020e-15,  2.82152407e-04,  1.57634711e-04,  6.34328678e-05,\n",
+       "         -3.80669496e-17]),\n",
+       "  array([ 1.22323994e-06, -5.34513692e-17,  1.00134216e+00,  4.57649396e-18,\n",
+       "          6.76901172e-08,  7.45190872e-20,  1.00000000e+00,  9.08479792e-16,\n",
+       "          3.35486175e-15,  8.17303782e-04,  4.03258543e-04,  1.12699765e-04,\n",
+       "         -3.92665296e-16, -5.91982850e-06, -2.21031865e-17, -1.88372491e-01,\n",
+       "         -1.85960548e-15, -5.07711110e-05, -8.43349987e-18,  5.86635094e-17,\n",
+       "          1.17469297e-15,  2.84502780e-04,  1.58958664e-04,  6.39497409e-05,\n",
+       "         -4.17461711e-17]),\n",
+       "  array([ 1.21729149e-06, -5.34716484e-17,  1.00114553e+00,  3.62269801e-18,\n",
+       "          4.17497251e-08,  6.87496742e-20,  1.00000000e+00,  9.08540065e-16,\n",
+       "          3.35603086e-15,  8.17590633e-04,  4.03418919e-04,  1.12764348e-04,\n",
+       "         -3.92710832e-16, -5.92693400e-06, -2.18913688e-17, -1.96632176e-01,\n",
+       "         -1.90759190e-15, -5.18807842e-05, -1.15387176e-17,  6.02728663e-17,\n",
+       "          1.16911038e-15,  2.86850990e-04,  1.60376380e-04,  6.45827656e-05,\n",
+       "         -4.55363210e-17]),\n",
+       "  array([ 1.21134418e-06, -5.34919936e-17,  1.00094047e+00,  2.64739278e-18,\n",
+       "          1.54496223e-08,  6.07103033e-20,  1.00000000e+00,  9.08602127e-16,\n",
+       "          3.35719254e-15,  8.17879895e-04,  4.03580881e-04,  1.12829737e-04,\n",
+       "         -3.92760681e-16, -5.93558187e-06, -2.16309997e-17, -2.05062606e-01,\n",
+       "         -1.95061047e-15, -5.26002055e-05, -1.60786327e-17,  6.20620210e-17,\n",
+       "          1.16168463e-15,  2.89262257e-04,  1.61961433e-04,  6.53886270e-05,\n",
+       "         -4.98492135e-17]),\n",
+       "  array([ 1.20539731e-06, -5.35123951e-17,  1.00072680e+00,  1.65359008e-18,\n",
+       "         -1.09292096e-08,  4.94741193e-20,  1.00000000e+00,  9.08666665e-16,\n",
+       "          3.35834402e-15,  8.18171749e-04,  4.03744698e-04,  1.12896162e-04,\n",
+       "         -3.92816381e-16, -5.94590062e-06, -2.13204628e-17, -2.13664693e-01,\n",
+       "         -1.98760541e-15, -5.27576639e-05, -2.24722591e-17,  6.45382820e-17,\n",
+       "          1.15147647e-15,  2.91853765e-04,  1.63817338e-04,  6.64249276e-05,\n",
+       "         -5.56991924e-17]),\n",
+       "  array([ 1.19944991e-06, -5.35328419e-17,  1.00050437e+00,  6.45023590e-19,\n",
+       "         -3.69769416e-08,  3.39554748e-20,  1.00000000e+00,  9.08735545e-16,\n",
+       "          3.35948123e-15,  8.18466624e-04,  4.03910781e-04,  1.12963850e-04,\n",
+       "         -3.92881895e-16, -5.95805431e-06, -2.09581277e-17, -2.22439267e-01,\n",
+       "         -2.01713297e-15, -5.20954640e-05, -3.10371808e-17,  6.88796586e-17,\n",
+       "          1.13721265e-15,  2.94875390e-04,  1.66083309e-04,  6.76880775e-05,\n",
+       "         -6.55141943e-17]),\n",
+       "  array([ 1.19350054e-06, -5.35533209e-17,  1.00027298e+00, -3.73360341e-19,\n",
+       "         -6.20730972e-08,  1.31703782e-20,  1.00000000e+00,  9.08813535e-16,\n",
+       "          3.36059867e-15,  8.18765607e-04,  4.04079702e-04,  1.13032711e-04,\n",
+       "         -3.92966787e-16, -5.97229330e-06, -2.05418708e-17, -2.31387072e-01,\n",
+       "         -2.03676786e-15, -5.01923112e-05, -4.15700855e-17,  7.79896067e-17,\n",
+       "          1.11743416e-15,  2.98983143e-04,  1.68920627e-04,  6.88611997e-05,\n",
+       "         -8.48923985e-17]),\n",
+       "  array([ 1.18754683e-06, -5.35738135e-17,  1.00003247e+00, -1.39405213e-18,\n",
+       "         -8.51928817e-08, -1.28888215e-20,  1.00000000e+00,  9.08913147e-16,\n",
+       "          3.36168907e-15,  8.19071838e-04,  4.04252074e-04,  1.13101093e-04,\n",
+       "         -3.93092297e-16, -5.98912968e-06, -2.00675475e-17, -2.40508762e-01,\n",
+       "         -2.04138359e-15, -4.62395689e-05, -5.21182900e-17,  9.96124230e-17,\n",
+       "          1.09040706e-15,  3.06231135e-04,  1.72372068e-04,  6.83818172e-05,\n",
+       "         -1.25509413e-16]),\n",
+       "  array([ 1.18158418e-06, -5.35942867e-17,  9.99782664e-01, -2.40323812e-18,\n",
+       "         -1.04335924e-07, -4.05638630e-20,  1.00000000e+00,  9.09069412e-16,\n",
+       "          3.36273910e-15,  8.19395795e-04,  4.04427288e-04,  1.13161416e-04,\n",
+       "         -3.93297366e-16, -6.00998727e-06, -1.95245360e-17, -2.49804895e-01,\n",
+       "         -2.01837198e-15, -3.82860851e-05, -5.53499645e-17,  1.56265260e-16,\n",
+       "          1.05003056e-15,  3.23956328e-04,  1.75214218e-04,  6.03233118e-05,\n",
+       "         -2.05069121e-16]),\n",
+       "  array([ 1.17560109e-06, -5.36146659e-17,  9.99523388e-01, -3.37023408e-18,\n",
+       "         -1.14492583e-07, -5.44064827e-20,  1.00000000e+00,  9.09389101e-16,\n",
+       "          3.36369470e-15,  8.19778368e-04,  4.04591048e-04,  1.13188515e-04,\n",
+       "         -3.93612911e-16, -6.03983645e-06, -1.88823350e-17, -2.59275932e-01,\n",
+       "         -1.93399192e-15, -2.03133170e-05, -2.76850864e-17,  3.19688586e-16,\n",
+       "          9.55591395e-16,  3.82572937e-04,  1.63760137e-04,  2.70990847e-05,\n",
+       "         -3.15544982e-16]),\n",
+       "  array([ 1.16955825e-06, -5.36347411e-17,  9.99254466e-01, -4.21126028e-18,\n",
+       "         -9.86401016e-08, -3.36328112e-21,  1.00000000e+00,  9.10237906e-16,\n",
+       "          3.36425313e-15,  8.20423021e-04,  4.04578495e-04,  1.13151468e-04,\n",
+       "         -3.93850355e-16, -6.10015306e-06, -1.80363471e-17, -2.68922227e-01,\n",
+       "         -1.68205239e-15,  3.17049623e-05,  1.02086703e-16,  8.48805593e-16,\n",
+       "          5.58432307e-16,  6.44653760e-04, -1.25528819e-05, -3.70470075e-05,\n",
+       "         -2.37443893e-16])],\n",
+       " [array([ 9.96419015e+02, -1.36386536e-12, -1.44461547e-01,  2.02633152e-13,\n",
+       "         -1.41189716e-14,  1.23333506e-12,  1.98070712e-01,  1.39369896e-01,\n",
+       "          7.23122699e-02,  6.95354390e-14]),\n",
+       "  array([ 9.60113764e+02, -1.40658848e-12, -1.43468869e-01,  1.92910859e-13,\n",
+       "         -2.15364380e-13,  1.05683484e-12,  1.29153047e-01,  1.23522992e-01,\n",
+       "          9.24007480e-02,  2.66888412e-13]),\n",
+       "  array([ 9.24512487e+02, -1.36859109e-12, -1.33985850e-01,  2.14417035e-13,\n",
+       "         -2.95039392e-13,  9.02532609e-13,  9.63682034e-02,  1.04054774e-01,\n",
+       "          8.73545087e-02,  3.32137874e-13]),\n",
+       "  array([ 8.89612771e+02, -1.28719512e-12, -1.21485738e-01,  2.41499961e-13,\n",
+       "         -3.26220739e-13,  7.78820767e-13,  7.51353812e-02,  8.66779383e-02,\n",
+       "          7.65665405e-02,  3.31295342e-13]),\n",
+       "  array([ 8.55411835e+02, -1.18142352e-12, -1.07927493e-01,  2.65086689e-13,\n",
+       "         -3.35800210e-13,  6.76257069e-13,  5.86994985e-02,  7.16829279e-02,\n",
+       "          6.55426476e-02,  3.06408287e-13]),\n",
+       "  array([ 8.21906546e+02, -1.06200554e-12, -9.41778813e-02,  2.82408271e-13,\n",
+       "         -3.34800352e-13,  5.87649404e-13,  4.49381752e-02,  5.87402766e-02,\n",
+       "          5.55666342e-02,  2.75779413e-13]),\n",
+       "  array([ 7.89093431e+02, -9.35658493e-13, -8.06968032e-02,  2.93161074e-13,\n",
+       "         -3.28159285e-13,  5.08831552e-13,  3.30473190e-02,  4.74979353e-02,\n",
+       "          4.67826003e-02,  2.45928487e-13]),\n",
+       "  array([ 7.56968693e+02, -8.06940646e-13, -6.77552938e-02,  2.97964175e-13,\n",
+       "         -3.18254208e-13,  4.37397300e-13,  2.26350635e-02,  3.76642956e-02,\n",
+       "          3.90678072e-02,  2.18646723e-13]),\n",
+       "  array([ 7.25528225e+02, -6.79099284e-13, -5.55175733e-02,  2.97715410e-13,\n",
+       "         -3.06304120e-13,  3.71858519e-13,  1.34600488e-02,  2.90098366e-02,\n",
+       "          3.22640193e-02,  1.94080272e-13]),\n",
+       "  array([ 6.94767625e+02, -5.54499019e-13, -4.40794243e-02,  2.93324974e-13,\n",
+       "         -2.92977709e-13,  3.11228936e-13,  5.34964299e-03,  2.13553693e-02,\n",
+       "          2.62317252e-02,  1.71905400e-13]),\n",
+       "  array([ 6.64682208e+02, -4.34864294e-13, -3.34900585e-02,  2.85614184e-13,\n",
+       "         -2.78673497e-13,  2.54826355e-13, -1.82953894e-03,  1.45601831e-02,\n",
+       "          2.08577440e-02,  1.51731168e-13]),\n",
+       "  array([ 6.35267018e+02, -3.21431793e-13, -2.37662534e-02,  2.75286813e-13,\n",
+       "         -2.63653898e-13,  2.02171099e-13, -8.18477807e-03,  8.51252751e-03,\n",
+       "          1.60519021e-02,  1.33218086e-13]),\n",
+       "  array([ 6.06516845e+02, -2.15054697e-13, -1.49020978e-02,  2.62930999e-13,\n",
+       "         -2.48110570e-13,  1.52925966e-13, -1.38045352e-02,  3.12242130e-03,\n",
+       "          1.17421446e-02,  1.16100460e-13]),\n",
+       "  array([ 5.78426235e+02, -1.16278985e-13, -6.87591517e-03,  2.49032529e-13,\n",
+       "         -2.32196445e-13,  1.06855522e-13, -1.87631497e-02, -1.68367775e-03,\n",
+       "          7.87027485e-03,  1.00179613e-13]),\n",
+       "  array([ 5.50989503e+02, -2.54023942e-14,  3.44738780e-04,  2.33990900e-13,\n",
+       "         -2.16041390e-13,  6.37959520e-14, -2.31241249e-02, -5.96680898e-03,\n",
+       "          4.38863791e-03,  8.53105245e-14]),\n",
+       "  array([ 5.24200746e+02,  5.74780205e-14,  6.79943422e-03,  2.18134561e-13,\n",
+       "         -1.99759795e-13,  2.36318742e-14, -2.69425148e-02, -9.77842017e-03,\n",
+       "          1.25762341e-03,  7.13888233e-14]),\n",
+       "  array([ 4.98053851e+02,  1.32426276e-13,  1.25321924e-02,  2.01734082e-13,\n",
+       "         -1.83454251e-13, -1.37215616e-14, -3.02666888e-02, -1.31625291e-02,\n",
+       "         -1.55619741e-03,  5.83398763e-14]),\n",
+       "  array([ 4.72542513e+02,  1.99633765e-13,  1.75895095e-02,  1.85013006e-13,\n",
+       "         -1.67217344e-13, -4.83322766e-14, -3.31396518e-02, -1.61573362e-02,\n",
+       "         -4.08146178e-03,  4.61101295e-14]),\n",
+       "  array([ 4.47660239e+02,  2.59390250e-13,  2.20188914e-02,  1.68156590e-13,\n",
+       "         -1.51132580e-13, -8.02612843e-14, -3.56000378e-02, -1.87964338e-02,\n",
+       "         -6.34305586e-03,  3.46604213e-14]),\n",
+       "  array([ 4.23400365e+02,  3.12058790e-13,  2.58677651e-02,  1.51318753e-13,\n",
+       "         -1.35274935e-13, -1.09569744e-13, -3.76828625e-02, -2.11097171e-02,\n",
+       "         -8.36289661e-03,  2.39609226e-14]),\n",
+       "  array([ 3.99756064e+02,  3.58054117e-13,  2.91826732e-02,  1.34627583e-13,\n",
+       "         -1.19711247e-13, -1.36323592e-13, -3.94200978e-02, -2.31240738e-02,\n",
+       "         -1.01605220e-02,  1.39873853e-14]),\n",
+       "  array([ 3.76720356e+02,  3.97824107e-13,  3.20086836e-02,  1.18189686e-13,\n",
+       "         -1.04500555e-13, -1.60596252e-13, -4.08411115e-02, -2.48639087e-02,\n",
+       "         -1.17535379e-02,  4.71843414e-15]),\n",
+       "  array([ 3.54286117e+02,  4.31834086e-13,  3.43889647e-02,  1.02093650e-13,\n",
+       "         -8.96944428e-14, -1.82469845e-13, -4.19730072e-02, -2.63515439e-02,\n",
+       "         -1.31579585e-02, -3.86632160e-15]),\n",
+       "  array([ 3.32446092e+02,  4.60553744e-13,  3.63644898e-02,  8.64128038e-14,\n",
+       "         -7.53373825e-14, -2.02035294e-13, -4.28408891e-02, -2.76075265e-02,\n",
+       "         -1.43884650e-02, -1.17875377e-14]),\n",
+       "  array([ 3.11192905e+02,  4.84446440e-13,  3.79738442e-02,  7.12074407e-14,\n",
+       "         -6.14670985e-14, -2.19391630e-13, -4.34680695e-02, -2.86508646e-02,\n",
+       "         -1.54586048e-02, -1.90668936e-14]),\n",
+       "  array([ 2.90519061e+02,  5.03960713e-13,  3.92531136e-02,  5.65266262e-14,\n",
+       "         -4.81149429e-14, -2.34644766e-13, -4.38762349e-02, -2.94992116e-02,\n",
+       "         -1.63809430e-02, -2.57274804e-14]),\n",
+       "  array([ 2.70416966e+02,  5.19523770e-13,  4.02358379e-02,  4.24096799e-14,\n",
+       "         -3.53062830e-14, -2.47905959e-13, -4.40855789e-02, -3.01690082e-02,\n",
+       "         -1.71671799e-02, -3.17939171e-14]),\n",
+       "  array([ 2.50878925e+02,  5.31536784e-13,  4.09530176e-02,  2.88874080e-14,\n",
+       "         -2.30608969e-14, -2.59290114e-13, -4.41149124e-02, -3.06755957e-02,\n",
+       "         -1.78282418e-02, -3.72922714e-14]),\n",
+       "  array([ 2.31897158e+02,  5.40371765e-13,  4.14331611e-02,  1.59831409e-14,\n",
+       "         -1.13933749e-14, -2.68914077e-13, -4.39817558e-02, -3.10333049e-02,\n",
+       "         -1.83743510e-02, -4.22498499e-14]),\n",
+       "  array([ 2.13463806e+02,  5.46369816e-13,  4.17023658e-02,  3.71361827e-15,\n",
+       "         -3.13522727e-16, -2.76894994e-13, -4.37024177e-02, -3.12555288e-02,\n",
+       "         -1.88150821e-02, -4.66949048e-14]),\n",
+       "  array([ 1.95570938e+02,  5.49840574e-13,  4.17844237e-02, -7.91024567e-15,\n",
+       "          1.01732350e-14, -2.83348816e-13, -4.32920644e-02, -3.13547820e-02,\n",
+       "         -1.91594055e-02, -5.06562987e-14]),\n",
+       "  array([ 1.78210559e+02,  5.51062614e-13,  4.17009459e-02, -1.88826915e-14,\n",
+       "          2.00654546e-14, -2.88388996e-13, -4.27647831e-02, -3.13427510e-02,\n",
+       "         -1.94157238e-02, -5.41631549e-14]),\n",
+       "  array([ 1.61374618e+02,  5.50284651e-13,  4.14714999e-02, -2.92025191e-14,\n",
+       "          2.93652796e-14, -2.92125397e-13, -4.21336388e-02, -3.12303377e-02,\n",
+       "         -1.95919016e-02, -5.72445173e-14]),\n",
+       "  array([ 1.45055017e+02,  5.47727342e-13,  4.11137553e-02, -3.88725537e-14,\n",
+       "          3.80780549e-14, -2.94663416e-13, -4.14107288e-02, -3.10276982e-02,\n",
+       "         -1.96952916e-02, -5.99290351e-14]),\n",
+       "  array([ 1.29243613e+02,  5.43585519e-13,  4.06436324e-02, -4.78991610e-14,\n",
+       "          4.62119536e-14, -2.96103348e-13, -4.06072344e-02, -3.07442786e-02,\n",
+       "         -1.97327578e-02, -6.22446834e-14]),\n",
+       "  array([ 1.13932232e+02,  5.38030716e-13,  4.00754518e-02, -5.62918049e-14,\n",
+       "          5.37776163e-14, -2.96539940e-13, -3.97334706e-02, -3.03888487e-02,\n",
+       "         -1.97106963e-02, -6.42185270e-14]),\n",
+       "  array([ 9.91126680e+01,  5.31213841e-13,  3.94220809e-02, -6.40626407e-14,\n",
+       "          6.07878081e-14, -2.96062153e-13, -3.87989343e-02, -2.99695340e-02,\n",
+       "         -1.96350563e-02, -6.58765296e-14]),\n",
+       "  array([ 8.47766959e+01,  5.23267890e-13,  3.86950750e-02, -7.12261393e-14,\n",
+       "          6.72570922e-14, -2.94753086e-13, -3.78123520e-02, -2.94938477e-02,\n",
+       "         -1.95113590e-02, -6.72434096e-14]),\n",
+       "  array([ 7.09160732e+01,  5.14310595e-13,  3.79048111e-02, -7.77987402e-14,\n",
+       "          7.32015250e-14, -2.92690044e-13, -3.67817253e-02, -2.89687212e-02,\n",
+       "         -1.93447180e-02, -6.83425401e-14]),\n",
+       "  array([ 5.75225480e+01,  5.04446941e-13,  3.70606129e-02, -8.37985297e-14,\n",
+       "          7.86383712e-14, -2.89944724e-13, -3.57143765e-02, -2.84005357e-02,\n",
+       "         -1.91398581e-02, -6.91958899e-14]),\n",
+       "  array([ 4.45878642e+01,  4.93771491e-13,  3.61708669e-02, -8.92449441e-14,\n",
+       "          8.35858416e-14, -2.86583492e-13, -3.46169925e-02, -2.77951520e-02,\n",
+       "         -1.89011356e-02, -6.98240018e-14]),\n",
+       "  array([ 3.21037673e+01,  4.82370465e-13,  3.52431274e-02, -9.41584960e-14,\n",
+       "          8.80628538e-14, -2.82667719e-13, -3.34956672e-02, -2.71579417e-02,\n",
+       "         -1.86325576e-02, -7.02460023e-14]),\n",
+       "  array([ 2.00620091e+01,  4.70323562e-13,  3.42842114e-02, -9.85605240e-14,\n",
+       "          9.20888149e-14, -2.78254168e-13, -3.23559429e-02, -2.64938169e-02,\n",
+       "         -1.83378023e-02, -7.04796367e-14]),\n",
+       "  array([ 8.45435358e+00,  4.57705497e-13,  3.33002827e-02, -1.02472963e-13,\n",
+       "          9.56834273e-14, -2.73395391e-13, -3.12028502e-02, -2.58072597e-02,\n",
+       "         -1.80202383e-02, -7.05413265e-14]),\n",
+       "  array([-2.72741862e+00,  4.44587264e-13,  3.22969262e-02, -1.05918140e-13,\n",
+       "          9.88665140e-14, -2.68140136e-13, -3.00409457e-02, -2.51023513e-02,\n",
+       "         -1.76829451e-02, -7.04462407e-14]),\n",
+       "  array([-1.34915054e+01,  4.31037114e-13,  3.12792125e-02, -1.08918591e-13,\n",
+       "          1.01657863e-13, -2.62533734e-13, -2.88743482e-02, -2.43828005e-02,\n",
+       "         -1.73287317e-02, -7.02083789e-14]),\n",
+       "  array([-2.38460785e+01,  4.17121285e-13,  3.02517530e-02, -1.11496906e-13,\n",
+       "          1.04077082e-13, -2.56618472e-13, -2.77067731e-02, -2.36519705e-02,\n",
+       "         -1.69601561e-02, -6.98406604e-14]),\n",
+       "  array([-3.37992795e+01,  4.02904487e-13,  2.92187467e-02, -1.13675608e-13,\n",
+       "          1.06143456e-13, -2.50433920e-13, -2.65415646e-02, -2.29129056e-02,\n",
+       "         -1.65795437e-02, -6.93550149e-14]),\n",
+       "  array([-4.33592150e+01,  3.88450174e-13,  2.81840206e-02, -1.15475179e-13,\n",
+       "          1.07877682e-13, -2.44017233e-13, -2.53817259e-02, -2.21683558e-02,\n",
+       "         -1.61890051e-02, -6.87624726e-14]),\n",
+       "  array([-5.25339531e+01,  3.73820626e-13,  2.71510615e-02, -1.16920411e-13,\n",
+       "          1.09295746e-13, -2.37403398e-13, -2.42299474e-02, -2.14208010e-02,\n",
+       "         -1.57904531e-02, -6.80732596e-14]),\n",
+       "  array([-6.13315197e+01,  3.59076890e-13,  2.61230441e-02, -1.18032633e-13,\n",
+       "          1.10415823e-13, -2.30625451e-13, -2.30886326e-02, -2.06724731e-02,\n",
+       "         -1.53856192e-02, -6.72968640e-14]),\n",
+       "  array([-6.97598940e+01,  3.44278589e-13,  2.51028527e-02, -1.18829552e-13,\n",
+       "          1.11258324e-13, -2.23714630e-13, -2.19599226e-02, -1.99253769e-02,\n",
+       "         -1.49760688e-02, -6.64421183e-14]),\n",
+       "  array([-7.78270060e+01,  3.29483625e-13,  2.40930996e-02, -1.19333880e-13,\n",
+       "          1.11837942e-13, -2.16700518e-13, -2.08457180e-02, -1.91813100e-02,\n",
+       "         -1.45632153e-02, -6.55172781e-14]),\n",
+       "  array([-8.55407325e+01,  3.14747834e-13,  2.30961401e-02, -1.19562959e-13,\n",
+       "          1.12173355e-13, -2.09611118e-13, -1.97476995e-02, -1.84418806e-02,\n",
+       "         -1.41483339e-02, -6.45300615e-14]),\n",
+       "  array([-9.29088940e+01,  3.00124581e-13,  2.21140848e-02, -1.19539978e-13,\n",
+       "          1.12276506e-13, -2.02472924e-13, -1.86673464e-02, -1.77085245e-02,\n",
+       "         -1.37325738e-02, -6.34877191e-14]),\n",
+       "  array([-9.99392517e+01,  2.85664367e-13,  2.11488100e-02, -1.19278949e-13,\n",
+       "          1.12166561e-13, -1.95310933e-13, -1.76059535e-02, -1.69825201e-02,\n",
+       "         -1.33169698e-02, -6.23970495e-14]),\n",
+       "  array([-1.06639505e+02,  2.71414413e-13,  2.02019669e-02, -1.18798944e-13,\n",
+       "          1.11856670e-13, -1.88148665e-13, -1.65646467e-02, -1.62650026e-02,\n",
+       "         -1.29024525e-02, -6.12644641e-14]),\n",
+       "  array([-1.13017288e+02,  2.57418283e-13,  1.92749902e-02, -1.18116018e-13,\n",
+       "          1.11361660e-13, -1.81008151e-13, -1.55443968e-02, -1.55569767e-02,\n",
+       "         -1.24898579e-02, -6.00959945e-14]),\n",
+       "  array([-1.19080167e+02,  2.43715541e-13,  1.83691053e-02, -1.17248795e-13,\n",
+       "          1.10692618e-13, -1.73909915e-13, -1.45460328e-02, -1.48593283e-02,\n",
+       "         -1.20799363e-02, -5.88973235e-14]),\n",
+       "  array([-1.24835638e+02,  2.30341477e-13,  1.74853369e-02, -1.16209176e-13,\n",
+       "          1.09865561e-13, -1.66872934e-13, -1.35702531e-02, -1.41728349e-02,\n",
+       "         -1.16733597e-02, -5.76737854e-14]),\n",
+       "  array([-1.30291127e+02,  2.17326861e-13,  1.66245166e-02, -1.15014056e-13,\n",
+       "          1.08890556e-13, -1.59914628e-13, -1.26176360e-02, -1.34981748e-02,\n",
+       "         -1.12707292e-02, -5.64304007e-14]),\n",
+       "  array([-1.35453983e+02,  2.04697800e-13,  1.57872915e-02, -1.13674740e-13,\n",
+       "          1.07781754e-13, -1.53050815e-13, -1.16886499e-02, -1.28359362e-02,\n",
+       "         -1.08725809e-02, -5.51718610e-14]),\n",
+       "  array([-1.40331479e+02,  1.92475635e-13,  1.49741332e-02, -1.12206574e-13,\n",
+       "          1.06548401e-13, -1.46295713e-13, -1.07836618e-02, -1.21866243e-02,\n",
+       "         -1.04793921e-02, -5.39025551e-14]),\n",
+       "  array([-1.44930810e+02,  1.80676930e-13,  1.41853473e-02, -1.10622449e-13,\n",
+       "          1.05200813e-13, -1.39661912e-13, -9.90294577e-03, -1.15506687e-02,\n",
+       "         -1.00915856e-02, -5.26265541e-14]),\n",
+       "  array([-1.49259090e+02,  1.69313541e-13,  1.34210836e-02, -1.08931298e-13,\n",
+       "          1.03751806e-13, -1.33160372e-13, -9.04669017e-03, -1.09284297e-02,\n",
+       "         -9.70953497e-03, -5.13476175e-14]),\n",
+       "  array([-1.53323350e+02,  1.58392718e-13,  1.26813473e-02, -1.07145999e-13,\n",
+       "          1.02209505e-13, -1.26800455e-13, -8.21500497e-03, -1.03202036e-02,\n",
+       "         -9.33356815e-03, -5.00692108e-14]),\n",
+       "  array([-1.57130540e+02,  1.47917304e-13,  1.19660102e-02, -1.05276902e-13,\n",
+       "          1.00583429e-13, -1.20589937e-13, -7.40792824e-03, -9.72622831e-03,\n",
+       "         -8.96397120e-03, -4.87944905e-14]),\n",
+       "  array([-1.60687523e+02,  1.37885982e-13,  1.12748227e-02, -1.03333838e-13,\n",
+       "          9.88825511e-14, -1.14535056e-13, -6.62543225e-03, -9.14668802e-03,\n",
+       "         -8.60099154e-03, -4.75263151e-14]),\n",
+       "  array([-1.64001075e+02,  1.28293570e-13,  1.06074266e-02, -1.01326097e-13,\n",
+       "          9.71153656e-14, -1.08640565e-13, -5.86742937e-03, -8.58171744e-03,\n",
+       "         -8.24484093e-03, -4.62672494e-14]),\n",
+       "  array([-1.67077885e+02,  1.19131364e-13,  9.96336720e-03, -9.92624319e-14,\n",
+       "          9.52899274e-14, -1.02909804e-13, -5.13377748e-03, -8.03140590e-03,\n",
+       "         -7.89569814e-03, -4.50195710e-14]),\n",
+       "  array([-1.69924553e+02,  1.10387515e-13,  9.34210639e-03, -9.71510805e-14,\n",
+       "          9.34138704e-14, -9.73447849e-14, -4.42428525e-03, -7.49580109e-03,\n",
+       "         -7.55371143e-03, -4.37852779e-14]),\n",
+       "  array([-1.72547589e+02,  1.02047432e-13,  8.74303561e-03, -9.49997719e-14,\n",
+       "          9.14944308e-14, -9.19462808e-14, -3.73871703e-03, -6.97491257e-03,\n",
+       "         -7.21900074e-03, -4.25660992e-14]),\n",
+       "  array([-1.74953412e+02,  9.40942052e-14,  8.16548838e-03, -9.28157590e-14,\n",
+       "          8.95384499e-14, -8.67139343e-14, -3.07679762e-03, -6.46871500e-03,\n",
+       "         -6.89165986e-03, -4.13635063e-14]),\n",
+       "  array([-1.77148349e+02,  8.65090416e-14,  7.60875280e-03, -9.06058333e-14,\n",
+       "          8.75523888e-14, -8.16463671e-14, -2.43821674e-03, -5.97715126e-03,\n",
+       "         -6.57175835e-03, -4.01787260e-14]),\n",
+       "  array([-1.79138634e+02,  7.92716976e-14,  7.07208361e-03, -8.83763424e-14,\n",
+       "          8.55423394e-14, -7.67412989e-14, -1.82263334e-03, -5.50013531e-03,\n",
+       "         -6.25934336e-03, -3.90127560e-14]),\n",
+       "  array([-1.80930408e+02,  7.23609102e-14,  6.55471364e-03, -8.61332138e-14,\n",
+       "          8.35140292e-14, -7.19956681e-14, -1.22967963e-03, -5.03755500e-03,\n",
+       "         -5.95444141e-03, -3.78663804e-14]),\n",
+       "  array([-1.82529718e+02,  6.57548152e-14,  6.05586474e-03, -8.38819698e-14,\n",
+       "          8.14728326e-14, -6.74057561e-14, -6.58964972e-04, -4.58927467e-03,\n",
+       "         -5.65706000e-03, -3.67401873e-14]),\n",
+       "  array([-1.83942518e+02,  5.94313451e-14,  5.57475786e-03, -8.16277471e-14,\n",
+       "          7.94237775e-14, -6.29673096e-14, -1.10079503e-04, -4.15513761e-03,\n",
+       "         -5.36718918e-03, -3.56345869e-14]),\n",
+       "  array([-1.85174663e+02,  5.33686041e-14,  5.11062239e-03, -7.93753126e-14,\n",
+       "          7.73715544e-14, -5.86756621e-14,  4.17402422e-04, -3.73496847e-03,\n",
+       "         -5.08480309e-03, -3.45498296e-14]),\n",
+       "  array([-1.86231918e+02,  4.75452118e-14,  4.66270452e-03, -7.71290793e-14,\n",
+       "          7.53205245e-14, -5.45258498e-14,  9.23919031e-04, -3.32857547e-03,\n",
+       "         -4.80986135e-03, -3.34860251e-14]),\n",
+       "  array([-1.87119948e+02,  4.19406152e-14,  4.23027474e-03, -7.48931227e-14,\n",
+       "          7.32747287e-14, -5.05127229e-14,  1.40991815e-03, -2.93575249e-03,\n",
+       "         -4.54231047e-03, -3.24431608e-14]),\n",
+       "  array([-1.87844326e+02,  3.65353619e-14,  3.81263425e-03, -7.26711946e-14,\n",
+       "          7.12378956e-14, -4.66310486e-14,  1.87585448e-03, -2.55628112e-03,\n",
+       "         -4.28208513e-03, -3.14211200e-14]),\n",
+       "  array([-1.88410525e+02,  3.13113359e-14,  3.40912043e-03, -7.04667380e-14,\n",
+       "          6.92134518e-14, -4.28756058e-14,  2.32218703e-03, -2.18993248e-03,\n",
+       "         -4.02910945e-03, -3.04196999e-14]),\n",
+       "  array([-1.88823925e+02,  2.62519505e-14,  3.01911125e-03, -6.82829004e-14,\n",
+       "          6.72045301e-14, -3.92412695e-14,  2.74937690e-03, -1.83646901e-03,\n",
+       "         -3.78329821e-03, -2.94386276e-14]),\n",
+       "  array([-1.89089810e+02,  2.13423010e-14,  2.64202867e-03, -6.61225470e-14,\n",
+       "          6.52139804e-14, -3.57230854e-14,  3.15788523e-03, -1.49564604e-03,\n",
+       "         -3.54455792e-03, -2.84775765e-14]),\n",
+       "  array([-1.89213366e+02,  1.65692744e-14,  2.27734103e-03, -6.39882732e-14,\n",
+       "          6.32443793e-14, -3.23163321e-14,  3.54817138e-03, -1.16721333e-03,\n",
+       "         -3.31278793e-03, -2.75361798e-14]),\n",
+       "  array([-1.89199685e+02,  1.19216086e-14,  1.92456425e-03, -6.18824167e-14,\n",
+       "          6.12980407e-14, -2.90165745e-14,  3.92069137e-03, -8.50916437e-04,\n",
+       "         -3.08788144e-03, -2.66140450e-14]),\n",
+       "  array([-1.89053763e+02,  7.38996411e-15,  1.58326337e-03, -5.98070855e-14,\n",
+       "          5.93770102e-14, -2.58196921e-14,  4.27589673e-03, -5.46497754e-04,\n",
+       "         -2.86972629e-03, -2.57107607e-14]),\n",
+       "  array([-1.88780499e+02,  2.96684381e-15,  1.25305054e-03, -5.77641025e-14,\n",
+       "          5.74831403e-14, -2.27219275e-14,  4.61423301e-03, -2.53697976e-04,\n",
+       "         -2.65820607e-03, -2.48259131e-14]),\n",
+       "  array([-1.88384700e+02, -1.35339930e-15,  9.33585061e-04, -5.57551429e-14,\n",
+       "          5.56179793e-14, -1.97198829e-14,  4.93613930e-03,  2.77432081e-05,\n",
+       "         -2.45320070e-03, -2.39590891e-14]),\n",
+       "  array([-1.87871074e+02, -5.57465549e-15,  6.24571171e-04, -5.37815944e-14,\n",
+       "          5.37829275e-14, -1.68105325e-14,  5.24204735e-03,  2.98086189e-04,\n",
+       "         -2.25458725e-03, -2.31098838e-14]),\n",
+       "  array([-1.87244237e+02, -9.69916635e-15,  3.25755486e-04, -5.18446820e-14,\n",
+       "          5.19791365e-14, -1.39912160e-14,  5.53238119e-03,  5.57590706e-04,\n",
+       "         -2.06224053e-03, -2.22779055e-14]),\n",
+       "  array([-1.86508712e+02, -1.37276586e-14,  3.69238815e-05, -4.99454199e-14,\n",
+       "          5.02075778e-14, -1.12596241e-14,  5.80755676e-03,  8.06515243e-04,\n",
+       "         -1.87603371e-03, -2.14627785e-14]),\n",
+       "  array([-1.85668926e+02, -1.76595005e-14, -2.42102116e-04, -4.80846897e-14,\n",
+       "          4.84689845e-14, -8.61377428e-15,  6.06798186e-03,  1.04511653e-03,\n",
+       "         -1.69583879e-03, -2.06641449e-14]),\n",
+       "  array([-1.84729215e+02, -2.14928770e-14, -5.11469346e-04, -4.62631270e-14,\n",
+       "          4.67639802e-14, -6.05197944e-15,  6.31405616e-03,  1.27364914e-03,\n",
+       "         -1.52152710e-03, -1.98816645e-14]),\n",
+       "  array([-1.83693821e+02, -2.52249790e-14, -7.71297357e-04, -4.44811770e-14,\n",
+       "          4.50930441e-14, -3.57281035e-15,  6.54617136e-03,  1.49236522e-03,\n",
+       "         -1.35296962e-03, -1.91150142e-14]),\n",
+       "  array([-1.82566895e+02, -2.88522031e-14, -1.02168296e-03, -4.27392074e-14,\n",
+       "          4.34564231e-14, -1.17505246e-15,  6.76471148e-03,  1.70151425e-03,\n",
+       "         -1.19003732e-03, -1.83638857e-14]),\n",
+       "  array([-1.81352495e+02, -3.23703579e-14, -1.26270495e-03, -4.10374176e-14,\n",
+       "          4.18542368e-14,  1.14234090e-15,  6.97005326e-03,  1.90134294e-03,\n",
+       "         -1.03260144e-03, -1.76279823e-14]),\n",
+       "  array([-1.80054592e+02, -3.57748720e-14, -1.49442888e-03, -3.93758001e-14,\n",
+       "          4.02865313e-14,  3.38029832e-15,  7.16256659e-03,  2.09209515e-03,\n",
+       "         -8.80533717e-04, -1.69070150e-14]),\n",
+       "  array([-1.78677064e+02, -3.90610013e-14, -1.71691182e-03, -3.77542945e-14,\n",
+       "          3.87531491e-14,  5.53968148e-15,  7.34261507e-03,  2.27401190e-03,\n",
+       "         -7.33706515e-04, -1.62006987e-14]),\n",
+       "  array([-1.77223701e+02, -4.22240310e-14, -1.93020705e-03, -3.61726402e-14,\n",
+       "          3.72538892e-14,  7.62133645e-15,  7.51055654e-03,  2.44733139e-03,\n",
+       "         -5.91993006e-04, -1.55087468e-14]),\n",
+       "  array([-1.75698204e+02, -4.52594692e-14, -2.13436858e-03, -3.46305616e-14,\n",
+       "          3.57883445e-14,  9.62614445e-15,  7.66674366e-03,  2.61228910e-03,\n",
+       "         -4.55267263e-04, -1.48308666e-14]),\n",
+       "  array([-1.74104187e+02, -4.81632289e-14, -2.32945544e-03, -3.31274674e-14,\n",
+       "          3.43562114e-14,  1.15550701e-14,  7.81152450e-03,  2.76911784e-03,\n",
+       "         -3.23404354e-04, -1.41667547e-14]),\n",
+       "  array([-1.72445178e+02, -5.09317970e-14, -2.51553574e-03, -3.16628135e-14,\n",
+       "          3.29569617e-14,  1.34092067e-14,  7.94524307e-03,  2.91804786e-03,\n",
+       "         -1.96280422e-04, -1.35160916e-14]),\n",
+       "  array([-1.70724618e+02, -5.35623855e-14, -2.69269035e-03, -3.02359400e-14,\n",
+       "          3.15900231e-14,  1.51898176e-14,  8.06823985e-03,  3.05930694e-03,\n",
+       "         -7.37727562e-05, -1.28785382e-14]),\n",
+       "  array([-1.68945863e+02, -5.60530656e-14, -2.86101630e-03, -2.88462336e-14,\n",
+       "          3.02546369e-14,  1.68983725e-14,  8.18085224e-03,  3.19312046e-03,\n",
+       "          4.42401175e-05, -1.22537317e-14]),\n",
+       "  array([-1.67112186e+02, -5.84028814e-14, -3.02062963e-03, -2.74928344e-14,\n",
+       "          2.89501588e-14,  1.85365775e-14,  8.28341488e-03,  3.31971136e-03,\n",
+       "          1.57878342e-04, -1.16412828e-14]),\n",
+       "  array([-1.65226775e+02, -6.06119415e-14, -3.17166793e-03, -2.61748145e-14,\n",
+       "          2.76759073e-14,  2.01063992e-14,  8.37625998e-03,  3.43930020e-03,\n",
+       "          2.67260597e-04, -1.10407736e-14]),\n",
+       "  array([-1.63292738e+02, -6.26814902e-14, -3.31429234e-03, -2.48911310e-14,\n",
+       "          2.64312390e-14,  2.16100815e-14,  8.45971742e-03,  3.55210497e-03,\n",
+       "          3.72503940e-04, -1.04517570e-14]),\n",
+       "  array([-1.61313100e+02, -6.46139539e-14, -3.44868905e-03, -2.36409365e-14,\n",
+       "          2.52152757e-14,  2.30501535e-14,  8.53411478e-03,  3.65834097e-03,\n",
+       "          4.73723588e-04, -9.87375659e-15]),\n",
+       "  array([-1.59290806e+02, -6.64129648e-14, -3.57507024e-03, -2.24232429e-14,\n",
+       "          2.40272504e-14,  2.44294302e-14,  8.59977717e-03,  3.75822052e-03,\n",
+       "          5.71032661e-04, -9.30626924e-15]),\n",
+       "  array([-1.57228722e+02, -6.80833606e-14, -3.69367450e-03, -2.12369360e-14,\n",
+       "          2.28665170e-14,  2.57510031e-14,  8.65702698e-03,  3.85195253e-03,\n",
+       "          6.64541847e-04, -8.74876800e-15]),\n",
+       "  array([-1.55129637e+02, -6.96311593e-14, -3.80476656e-03, -2.00811250e-14,\n",
+       "          2.17322381e-14,  2.70182215e-14,  8.70618330e-03,  3.93974209e-03,\n",
+       "          7.54359015e-04, -8.20070761e-15]),\n",
+       "  array([-1.52996260e+02, -7.10635090e-14, -3.90863648e-03, -1.89547520e-14,\n",
+       "          2.06237861e-14,  2.82346631e-14,  8.74756130e-03,  4.02178979e-03,\n",
+       "          8.40588749e-04, -7.66153157e-15]),\n",
+       "  array([-1.50831226e+02, -7.23886119e-14, -4.00559801e-03, -1.78569209e-14,\n",
+       "          1.95404448e-14,  2.94040934e-14,  8.78147130e-03,  4.09829102e-03,\n",
+       "          9.23331822e-04, -7.13068151e-15]),\n",
+       "  array([-1.48637094e+02, -7.36156210e-14, -4.09598632e-03, -1.67866890e-14,\n",
+       "          1.84816302e-14,  3.05304140e-14,  8.80821771e-03,  4.16943511e-03,\n",
+       "          1.00268462e-03, -6.60760847e-15]),\n",
+       "  array([-1.46416350e+02, -7.47545078e-14, -4.18015484e-03, -1.57431140e-14,\n",
+       "          1.74468631e-14,  3.16175977e-14,  8.82809772e-03,  4.23540441e-03,\n",
+       "          1.07873848e-03, -6.09178661e-15]),\n",
+       "  array([-1.44171406e+02, -7.58158999e-14, -4.25847123e-03, -1.47253442e-14,\n",
+       "          1.64357000e-14,  3.26696111e-14,  8.84139986e-03,  4.29637323e-03,\n",
+       "          1.15157911e-03, -5.58272909e-15]),\n",
+       "  array([-1.41904600e+02, -7.68108859e-14, -4.33131244e-03, -1.37327083e-14,\n",
+       "          1.54476570e-14,  3.36903240e-14,  8.84840239e-03,  4.35250686e-03,\n",
+       "          1.22128587e-03, -5.08000604e-15]),\n",
+       "  array([-1.39618205e+02, -7.77507846e-14, -4.39905878e-03, -1.27644873e-14,\n",
+       "          1.44824327e-14,  3.46834050e-14,  8.84937152e-03,  4.40396045e-03,\n",
+       "          1.28793120e-03, -4.58326440e-15]),\n",
+       "  array([-1.37314417e+02, -7.86468774e-14, -4.46208703e-03, -1.18200297e-14,\n",
+       "          1.35397968e-14,  3.56522053e-14,  8.84455971e-03,  4.45087802e-03,\n",
+       "          1.35158013e-03, -4.09224927e-15]),\n",
+       "  array([-1.34995370e+02, -7.95101030e-14, -4.52076247e-03, -1.08988845e-14,\n",
+       "          1.26194546e-14,  3.65996310e-14,  8.83420382e-03,  4.49339164e-03,\n",
+       "          1.41228990e-03, -3.60682618e-15]),\n",
+       "  array([-1.32663126e+02, -8.03507133e-14, -4.57543023e-03, -1.00004912e-14,\n",
+       "          1.17213351e-14,  3.75280056e-14,  8.81852346e-03,  4.53162076e-03,\n",
+       "          1.47010976e-03, -3.12700327e-15]),\n",
+       "  array([-1.30319682e+02, -8.11778955e-14, -4.62640578e-03, -9.12442629e-15,\n",
+       "          1.08453375e-14,  3.84389293e-14,  8.79771957e-03,  4.56567176e-03,\n",
+       "          1.52508106e-03, -2.65295261e-15]),\n",
+       "  array([-1.27966970e+02, -8.19993651e-14, -4.67396518e-03, -8.27039438e-15,\n",
+       "          9.99131947e-15,  3.93331375e-14,  8.77197319e-03,  4.59563802e-03,\n",
+       "          1.57723758e-03, -2.18502908e-15]),\n",
+       "  array([-1.25606859e+02, -8.28209429e-14, -4.71833533e-03, -7.43804982e-15,\n",
+       "          9.15924503e-15,  4.02103672e-14,  8.74144482e-03,  4.62160019e-03,\n",
+       "          1.62660623e-03, -1.72378533e-15]),\n",
+       "  array([-1.23241151e+02, -8.36461320e-14, -4.75968488e-03, -6.62713801e-15,\n",
+       "          8.34902120e-15,  4.10692405e-14,  8.70627422e-03,  4.64362714e-03,\n",
+       "          1.67320800e-03, -1.26998135e-15]),\n",
+       "  array([-1.20871591e+02, -8.44757202e-14, -4.79811642e-03, -5.83741815e-15,\n",
+       "          7.56054849e-15,  4.19071744e-14,  8.66658092e-03,  4.66177717e-03,\n",
+       "          1.71705926e-03, -8.24586667e-16]),\n",
+       "  array([-1.18499860e+02, -8.53074355e-14, -4.83366079e-03, -5.06871132e-15,\n",
+       "          6.79365037e-15,  4.27203305e-14,  8.62246545e-03,  4.67609985e-03,\n",
+       "          1.75817332e-03, -3.88773904e-16]),\n",
+       "  array([-1.16127580e+02, -8.61356936e-14, -4.86627438e-03, -4.32082762e-15,\n",
+       "          6.04812388e-15,  4.35036141e-14,  8.57401134e-03,  4.68663815e-03,\n",
+       "          1.79656213e-03,  3.60978575e-17]),\n",
+       "  array([-1.13756314e+02, -8.69514734e-14, -4.89583999e-03, -3.59353798e-15,\n",
+       "          5.32375561e-15,  4.42507369e-14,  8.52128790e-03,  4.69343089e-03,\n",
+       "          1.83223809e-03,  4.48510525e-16]),\n",
+       "  array([-1.11387570e+02, -8.77423604e-14, -4.92217197e-03, -2.88669614e-15,\n",
+       "          4.62020184e-15,  4.49543485e-14,  8.46435370e-03,  4.69651542e-03,\n",
+       "          1.86521578e-03,  8.46825503e-16]),\n",
+       "  array([-1.09022796e+02, -8.84927921e-14, -4.94502599e-03, -2.20021308e-15,\n",
+       "          3.93701743e-15,  4.56062457e-14,  8.40326057e-03,  4.69593027e-03,\n",
+       "          1.89551350e-03,  1.22933264e-15]),\n",
+       "  array([-1.06663388e+02, -8.91845257e-14, -4.96411318e-03, -1.53395258e-15,\n",
+       "          3.27376752e-15,  4.61976564e-14,  8.33805809e-03,  4.69171764e-03,\n",
+       "          1.92315461e-03,  1.59430810e-15]),\n",
+       "  array([-1.04310685e+02, -8.97973365e-14, -4.97911839e-03, -8.87677110e-16,\n",
+       "          2.63010448e-15,  4.67195921e-14,  8.26879817e-03,  4.68392569e-03,\n",
+       "          1.94816837e-03,  1.94007872e-15]),\n",
+       "  array([-1.01965975e+02, -9.03099302e-14, -4.98972129e-03, -2.61286906e-16,\n",
+       "          2.00557188e-15,  4.71632552e-14,  8.19553952e-03,  4.67261031e-03,\n",
+       "          1.97059044e-03,  2.26508944e-15]),\n",
+       "  array([-9.96304946e+01, -9.07010292e-14, -4.99561915e-03,  3.45337959e-16,\n",
+       "          1.39979566e-15,  4.75204788e-14,  8.11835176e-03,  4.65783646e-03,\n",
+       "          1.99046290e-03,  2.56797015e-15]),\n",
+       "  array([-9.73054270e+01, -9.09505762e-14, -4.99654968e-03,  9.32141229e-16,\n",
+       "          8.12327005e-16,  4.77841617e-14,  8.03731870e-03,  4.63967871e-03,\n",
+       "          2.00783381e-03,  2.84759517e-15]),\n",
+       "  array([-9.49919077e+01, -9.10409436e-14, -4.99231142e-03,  1.49935727e-15,\n",
+       "          2.43126568e-16,  4.79486874e-14,  7.95254100e-03,  4.61822152e-03,\n",
+       "          2.02275652e-03,  3.10313625e-15]),\n",
+       "  array([-9.26910226e+01, -9.09580860e-14, -4.98278100e-03,  2.04680006e-15,\n",
+       "         -3.08099374e-16,  4.80102556e-14,  7.86413723e-03,  4.59355850e-03,\n",
+       "          2.03528858e-03,  3.33409596e-15]),\n",
+       "  array([-9.04038104e+01, -9.06924934e-14, -4.96792472e-03,  2.57443486e-15,\n",
+       "         -8.41337719e-16,  4.79671196e-14,  7.77224405e-03,  4.56579138e-03,\n",
+       "          2.04549056e-03,  3.54032427e-15]),\n",
+       "  array([-8.81312630e+01, -9.02398561e-14, -4.94780379e-03,  3.08218963e-15,\n",
+       "         -1.35646149e-15,  4.78196857e-14,  7.67701484e-03,  4.53502838e-03,\n",
+       "          2.05342474e-03,  3.72201236e-15]),\n",
+       "  array([-8.58743266e+01, -8.96013527e-14, -4.92257249e-03,  3.56996903e-15,\n",
+       "         -1.85323856e-15,  4.75704568e-14,  7.57861726e-03,  4.50138232e-03,\n",
+       "          2.05915389e-03,  3.87966319e-15]),\n",
+       "  array([-8.36339034e+01, -8.87835038e-14, -4.89246922e-03,  4.03767104e-15,\n",
+       "         -2.33135506e-15,  4.72238126e-14,  7.47722972e-03,  4.46496853e-03,\n",
+       "          2.06274023e-03,  4.01403935e-15]),\n",
+       "  array([-8.14108515e+01, -8.77975716e-14, -4.85780112e-03,  4.48520598e-15,\n",
+       "         -2.79045074e-15,  4.67856334e-14,  7.37303717e-03,  4.42590278e-03,\n",
+       "          2.06424464e-03,  4.12609178e-15]),\n",
+       "  array([-7.92059869e+01, -8.66585323e-14, -4.81892330e-03,  4.91251652e-15,\n",
+       "         -3.23016293e-15,  4.62627938e-14,  7.26622660e-03,  4.38429956e-03,\n",
+       "          2.06372631e-03,  4.21687490e-15]),\n",
+       "  array([-7.70200841e+01, -8.53836964e-14, -4.77621434e-03,  5.31959688e-15,\n",
+       "         -3.65017480e-15,  4.56625686e-14,  7.15698261e-03,  4.34027079e-03,\n",
+       "          2.06124291e-03,  4.28745621e-15]),\n",
+       "  array([-7.48538771e+01, -8.39910944e-14, -4.73005023e-03,  5.70650893e-15,\n",
+       "         -4.05026315e-15,  4.49920059e-14,  7.04548370e-03,  4.29392536e-03,\n",
+       "          2.05685135e-03,  4.33883004e-15]),\n",
+       "  array([-7.27080604e+01, -8.24977868e-14, -4.68077883e-03,  6.07339278e-15,\n",
+       "         -4.43034108e-15,  4.42573353e-14,  6.93189967e-03,  4.24536956e-03,\n",
+       "          2.05060927e-03,  4.37184613e-15]),\n",
+       "  array([-7.05832902e+01, -8.09182777e-14, -4.62869743e-03,  6.42047008e-15,\n",
+       "         -4.79049080e-15,  4.34634807e-14,  6.81639058e-03,  4.19470875e-03,\n",
+       "          2.04257718e-03,  4.38716359e-15]),\n",
+       "  array([-6.84801851e+01, -7.92632232e-14, -4.57403571e-03,  6.74803838e-15,\n",
+       "         -5.13098307e-15,  4.26137492e-14,  6.69910762e-03,  4.14205004e-03,\n",
+       "          2.03282128e-03,  4.38523986e-15]),\n",
+       "  array([-6.63993271e+01, -7.75386110e-14, -4.51694605e-03,  7.05645590e-15,\n",
+       "         -5.45228030e-15,  4.17097533e-14,  6.58019609e-03,  4.08750629e-03,\n",
+       "          2.02141685e-03,  4.36636199e-15]),\n",
+       "  array([-6.43412629e+01, -7.57455575e-14, -4.45750326e-03,  7.34611674e-15,\n",
+       "         -5.75502183e-15,  4.07516109e-14,  6.45980057e-03,  4.03120101e-03,\n",
+       "          2.00845195e-03,  4.33072429e-15]),\n",
+       "  array([-6.23065043e+01, -7.38808179e-14, -4.39571437e-03,  7.61741737e-15,\n",
+       "         -6.03999090e-15,  3.97384438e-14,  6.33807207e-03,  3.97327397e-03,\n",
+       "          1.99403129e-03,  4.27855238e-15]),\n",
+       "  array([-6.02955297e+01, -7.19380379e-14, -4.33153917e-03,  7.87071600e-15,\n",
+       "         -6.30806416e-15,  3.86691670e-14,  6.21517690e-03,  3.91388728e-03,\n",
+       "          1.97827985e-03,  4.21026922e-15]),\n",
+       "  array([-5.83087846e+01, -6.99097020e-14, -4.26492070e-03,  8.10628723e-15,\n",
+       "         -6.56014575e-15,  3.75435316e-14,  6.09130661e-03,  3.85323121e-03,\n",
+       "          1.96134602e-03,  4.12669372e-15]),\n",
+       "  array([-5.63466827e+01, -6.77896499e-14, -4.19582412e-03,  8.32427460e-15,\n",
+       "         -6.79708900e-15,  3.63633539e-14,  5.96668837e-03,  3.79152949e-03,\n",
+       "          1.94340382e-03,  4.02925810e-15]),\n",
+       "  array([-5.44096069e+01, -6.55759651e-14, -4.12428136e-03,  8.52464465e-15,\n",
+       "         -7.01961032e-15,  3.51338350e-14,  5.84159487e-03,  3.72904329e-03,\n",
+       "          1.92465390e-03,  3.92022642e-15]),\n",
+       "  array([-5.24979100e+01, -6.32739711e-14, -4.05043803e-03,  8.70714610e-15,\n",
+       "         -7.22820067e-15,  3.38648532e-14,  5.71635268e-03,  3.66607347e-03,\n",
+       "          1.90532304e-03,  3.80289377e-15]),\n",
+       "  array([-5.06119154e+01, -6.08990374e-14, -3.97459823e-03,  8.87127822e-15,\n",
+       "         -7.42304142e-15,  3.25720984e-14,  5.59134817e-03,  3.60296062e-03,\n",
+       "          1.88566199e-03,  3.68174434e-15]),\n",
+       "  array([-4.87519184e+01, -5.84788771e-14, -3.89726265e-03,  9.01627244e-15,\n",
+       "         -7.60393232e-15,  3.12779139e-14,  5.46702989e-03,  3.54008242e-03,\n",
+       "          1.86594151e-03,  3.56254689e-15]),\n",
+       "  array([-4.69181868e+01, -5.60550370e-14, -3.81915507e-03,  9.14109111e-15,\n",
+       "         -7.77023966e-15,  3.00117180e-14,  5.34390666e-03,  3.47784799e-03,\n",
+       "          1.84644659e-03,  3.45236851e-15]),\n",
+       "  array([-4.51109614e+01, -5.36833255e-14, -3.74123312e-03,  9.24444676e-15,\n",
+       "         -7.92087247e-15,  2.88099022e-14,  5.22254048e-03,  3.41668940e-03,\n",
+       "          1.82746910e-03,  3.35949116e-15]),\n",
+       "  array([-4.33304572e+01, -5.14330003e-14, -3.66467951e-03,  9.32484420e-15,\n",
+       "         -8.05429357e-15,  2.77151297e-14,  5.10353411e-03,  3.35705004e-03,\n",
+       "          1.80929896e-03,  3.29322164e-15]),\n",
+       "  array([-4.15768638e+01, -4.93846319e-14, -3.59087194e-03,  9.38064664e-15,\n",
+       "         -8.16856986e-15,  2.67750042e-14,  4.98751311e-03,  3.29937046e-03,\n",
+       "          1.79221423e-03,  3.26359201e-15]),\n",
+       "  array([-3.98503464e+01, -4.76266774e-14, -3.52133093e-03,  9.41016572e-15,\n",
+       "         -8.26146343e-15,  2.60401240e-14,  4.87510268e-03,  3.24407176e-03,\n",
+       "          1.77647052e-03,  3.28095578e-15]),\n",
+       "  array([-3.81510464e+01, -4.62509086e-14, -3.45764729e-03,  9.41177360e-15,\n",
+       "         -8.33056129e-15,  2.55615897e-14,  4.76690009e-03,  3.19153743e-03,\n",
+       "          1.76229000e-03,  3.35549314e-15]),\n",
+       "  array([-3.64790819e+01, -4.53469552e-14, -3.40139243e-03,  9.38403439e-15,\n",
+       "         -8.37343843e-15,  2.53880831e-14,  4.66344384e-03,  3.14209414e-03,\n",
+       "          1.74985060e-03,  3.49664640e-15]),\n",
+       "  array([-3.48345487e+01, -4.49963087e-14, -3.35401695e-03,  9.32585123e-15,\n",
+       "         -8.38784589e-15,  2.55626783e-14,  4.56518092e-03,  3.09599240e-03,\n",
+       "          1.73927567e-03,  3.71251417e-15]),\n",
+       "  array([-3.32175207e+01, -4.52662036e-14, -3.31674398e-03,  9.23662477e-15,\n",
+       "         -8.37191450e-15,  2.61195833e-14,  4.47243415e-03,  3.05338800e-03,\n",
+       "          1.73062470e-03,  4.00923826e-15]),\n",
+       "  array([-3.16280508e+01, -4.62038135e-14, -3.29046515e-03,  9.11641838e-15,\n",
+       "         -8.32436470e-15,  2.70810275e-14,  4.38537140e-03,  3.01432526e-03,\n",
+       "          1.72388523e-03,  4.39042124e-15]),\n",
+       "  array([-3.00661713e+01, -4.78312004e-14, -3.27564675e-03,  8.96612460e-15,\n",
+       "         -8.24471489e-15,  2.84545207e-14,  4.30397897e-03,  2.97872294e-03,\n",
+       "          1.71896659e-03,  4.85661398e-15]),\n",
+       "  array([-2.85318948e+01, -5.01414035e-14, -3.27225394e-03,  8.78762544e-15,\n",
+       "         -8.13348303e-15,  3.02306934e-14,  4.22804086e-03,  2.94636398e-03,\n",
+       "          1.71569570e-03,  5.40491160e-15]),\n",
+       "  array([-2.70252150e+01, -5.30959715e-14, -3.27969916e-03,  8.58433591e-15,\n",
+       "         -7.99197897e-15,  3.23819143e-14,  4.15712601e-03,  2.91688985e-03,\n",
+       "          1.71381534e-03,  6.02869239e-15]),\n",
+       "  array([-2.55461071e+01, -5.66242149e-14, -3.29681983e-03,  8.35976238e-15,\n",
+       "         -7.82394542e-15,  3.48617663e-14,  4.09058487e-03,  2.88980023e-03,\n",
+       "          1.71298519e-03,  6.71751907e-15]),\n",
+       "  array([-2.40945287e+01, -6.06241102e-14, -3.32188806e-03,  8.12031514e-15,\n",
+       "         -7.63316401e-15,  3.76056175e-14,  4.02755633e-03,  2.86445883e-03,\n",
+       "          1.71278600e-03,  7.45724913e-15]),\n",
+       "  array([-2.26704204e+01, -6.49650913e-14, -3.35265314e-03,  7.87295871e-15,\n",
+       "         -7.42575130e-15,  4.05320884e-14,  3.96698543e-03,  2.84010543e-03,\n",
+       "          1.71272697e-03,  8.23031640e-15]),\n",
+       "  array([-2.12737069e+01, -6.94923763e-14, -3.38641516e-03,  7.62614087e-15,\n",
+       "         -7.20924001e-15,  4.35455715e-14,  3.90765183e-03,  2.81587433e-03,\n",
+       "          1.71225659e-03,  9.01622161e-15]),\n",
+       "  array([-1.99042972e+01, -7.40327221e-14, -3.42012641e-03,  7.38958336e-15,\n",
+       "         -6.99258128e-15,  4.65395927e-14,  3.84820804e-03,  2.79081882e-03,\n",
+       "          1.71077672e-03,  9.79219552e-15]),\n",
+       "  array([-1.85620857e+01, -7.84012823e-14, -3.45051512e-03,  7.17392087e-15,\n",
+       "         -6.78604929e-15,  4.94008778e-14,  3.78722610e-03,  2.76394097e-03,\n",
+       "          1.70765965e-03,  1.05340105e-14]),\n",
+       "  array([-1.72469531e+01, -8.24092122e-14, -3.47422511e-03,  6.99038902e-15,\n",
+       "         -6.60083382e-15,  5.20139174e-14,  3.72325066e-03,  2.73422569e-03,\n",
+       "          1.70226787e-03,  1.12169038e-14]),\n",
+       "  array([-1.59587665e+01, -8.58716406e-14, -3.48796396e-03,  6.85018515e-15,\n",
+       "         -6.44866149e-15,  5.42657875e-14,  3.65485599e-03,  2.70067768e-03,\n",
+       "          1.69397553e-03,  1.18165664e-14]),\n",
+       "  array([-1.46973807e+01, -8.86156092e-14, -3.48865193e-03,  6.76380460e-15,\n",
+       "         -6.34118623e-15,  5.60509759e-14,  3.58070424e-03,  2.66235967e-03,\n",
+       "          1.68219108e-03,  1.23101482e-14]),\n",
+       "  array([-1.34626385e+01, -9.04875964e-14, -3.47356376e-03,  6.74038740e-15,\n",
+       "         -6.28917563e-15,  5.72759571e-14,  3.49960200e-03,  2.61843009e-03,\n",
+       "          1.66637994e-03,  1.26772274e-14]),\n",
+       "  array([-1.22543715e+01, -9.13602721e-14, -3.44045664e-03,  6.78689531e-15,\n",
+       "         -6.30175488e-15,  5.78632819e-14,  3.41055238e-03,  2.56817844e-03,\n",
+       "          1.64608612e-03,  1.29006938e-14]),\n",
+       "  array([-1.10724007e+01, -9.11380930e-14, -3.38767536e-03,  6.90759301e-15,\n",
+       "         -6.38538573e-15,  5.77549878e-14,  3.31280013e-03,  2.51105682e-03,\n",
+       "          1.62095210e-03,  1.29675047e-14]),\n",
+       "  array([-9.91653673e+00, -8.97616238e-14, -3.31423446e-03,  7.10291655e-15,\n",
+       "         -6.54364005e-15,  5.69151321e-14,  3.20586696e-03,  2.44670534e-03,\n",
+       "          1.59073536e-03,  1.28692676e-14]),\n",
+       "  array([-8.78658100e+00, -8.72101865e-14, -3.21986672e-03,  7.36971329e-15,\n",
+       "         -6.77599999e-15,  5.53313812e-14,  3.08957631e-03,  2.37497121e-03,\n",
+       "          1.55532142e-03,  1.26026315e-14]),\n",
+       "  array([-7.68232560e+00, -8.35028390e-14, -3.10503996e-03,  7.70123270e-15,\n",
+       "         -7.07738638e-15,  5.30155589e-14,  2.96406551e-03,  2.29591980e-03,\n",
+       "          1.51473242e-03,  1.21694646e-14]),\n",
+       "  array([-6.60355397e+00, -7.86975999e-14, -2.97093980e-03,  8.08608195e-15,\n",
+       "         -7.43921938e-15,  5.00031547e-14,  2.82978524e-03,  2.20983744e-03,\n",
+       "          1.46913074e-03,  1.15768049e-14]),\n",
+       "  array([-5.55004131e+00, -7.28889542e-14, -2.81941940e-03,  8.51006623e-15,\n",
+       "         -7.84845638e-15,  4.63518431e-14,  2.68748625e-03,  2.11722576e-03,\n",
+       "          1.41881763e-03,  1.08366122e-14]),\n",
+       "  array([-4.52155489e+00, -6.62037975e-14, -2.65291939e-03,  8.95629930e-15,\n",
+       "         -8.28884385e-15,  4.21391030e-14,  2.53819422e-03,  2.01878793e-03,\n",
+       "          1.36422673e-03,  9.96530616e-15]),\n",
+       "  array([-3.51785449e+00, -5.87960298e-14, -2.47436228e-03,  9.40627906e-15,\n",
+       "         -8.74174934e-15,  3.74590726e-14,  2.38317389e-03,  1.91540730e-03,\n",
+       "          1.30591279e-03,  8.98313860e-15]),\n",
+       "  array([-2.53869265e+00, -5.08400994e-14, -2.28702759e-03,  9.84096547e-15,\n",
+       "         -9.18734970e-15,  3.24188069e-14,  2.22388437e-03,  1.80811952e-03,\n",
+       "          1.24453597e-03,  7.91342242e-15]),\n",
+       "  array([-1.58381507e+00, -4.25238520e-14, -2.09441467e-03,  1.02419861e-14,\n",
+       "         -9.60585591e-15,  2.71341289e-14,  2.06192777e-03,  1.69807920e-03,\n",
+       "          1.18084234e-03,  6.78165877e-15]),\n",
+       "  array([-6.52960896e-01, -3.40410660e-14, -1.90010087e-03,  1.05926594e-14,\n",
+       "         -9.97884964e-15,  2.17252820e-14,  1.89899355e-03,  1.58652273e-03,\n",
+       "          1.11564135e-03,  5.61460288e-15]),\n",
+       "  array([ 2.54136949e-01, -2.55840674e-14, -1.70760279e-03,  1.08789845e-14,\n",
+       "         -1.02903896e-14,  1.63125846e-14,  1.73680117e-03,  1.47472869e-03,\n",
+       "          1.04978112e-03,  4.43931426e-15]),\n",
+       "  array([ 1.13775144e+00, -1.73367928e-14, -1.52024760e-03,  1.10903460e-14,\n",
+       "         -1.05279509e-14,  1.10122882e-14,  1.57704355e-03,  1.36397754e-03,\n",
+       "          9.84122562e-04,  3.28223223e-15]),\n",
+       "  array([ 1.99816113e+00, -9.46862141e-15, -1.34106073e-03,  1.12199548e-14,\n",
+       "         -1.06830551e-14,  5.93281259e-15,  1.42133371e-03,  1.25551224e-03,\n",
+       "          9.19513383e-04,  2.16831763e-15]),\n",
+       "  array([ 2.83564978e+00, -2.12923599e-15, -1.17267453e-03,  1.12649963e-14,\n",
+       "         -1.07515613e-14,  1.17150732e-15,  1.27115685e-03,  1.15050139e-03,\n",
+       "          8.56762922e-04,  1.12029509e-15]),\n",
+       "  array([ 3.65050607e+00,  4.55531214e-15, -1.01726106e-03,  1.12264903e-14,\n",
+       "         -1.07336224e-14, -3.18794860e-15,  1.12782943e-03,  1.05000624e-03,\n",
+       "          7.96618925e-04,  1.58023744e-16]),\n",
+       "  array([ 4.44302319e+00,  1.04852413e-14, -8.76490310e-04,  1.11089041e-14,\n",
+       "         -1.06333335e-14, -7.07743618e-15,  9.92466795e-04,  9.54952915e-04,\n",
+       "          7.39747105e-04, -7.01983408e-16]),\n",
+       "  array([ 5.21349855e+00,  1.55883714e-14, -7.51513570e-04,  1.09195740e-14,\n",
+       "         -1.04581340e-14, -1.04455460e-14,  8.65959997e-04,  8.66110534e-04,\n",
+       "          6.86714279e-04, -1.44688085e-15]),\n",
+       "  array([ 5.96223335e+00,  1.98202170e-14, -6.42970128e-04,  1.06680050e-14,\n",
+       "         -1.02180379e-14, -1.32579970e-14,  7.48962291e-04,  7.84076114e-04,\n",
+       "          6.37975643e-04, -2.06764990e-15]),\n",
+       "  array([ 6.68953232e+00,  2.31629751e-14, -5.51014350e-04,  1.03651105e-14,\n",
+       "         -9.92478434e-15, -1.54973691e-14,  6.41885068e-04,  7.09266285e-04,\n",
+       "          5.93866566e-04, -2.55910153e-15]),\n",
+       "  array([ 7.39570329e+00,  2.56235732e-14, -4.75359345e-04,  1.00224753e-14,\n",
+       "         -9.59097401e-15, -1.71622342e-14,  5.44902652e-04,  6.41915859e-04,\n",
+       "          5.54599026e-04, -2.91973851e-15]),\n",
+       "  array([ 8.08105688e+00,  2.72309928e-14, -4.15332981e-04,  9.65167763e-15,\n",
+       "         -9.22927741e-15, -1.82657757e-14,  4.57965003e-04,  5.82082807e-04,\n",
+       "          5.20262578e-04, -3.15149290e-15]),\n",
+       "  array([ 8.74590618e+00,  2.80330763e-14, -3.69941942e-04,  9.26372072e-15,\n",
+       "         -8.85175781e-15, -1.88340188e-14,  3.80817051e-04,  5.29658961e-04,\n",
+       "          4.90829533e-04, -3.25936505e-15]),\n",
+       "  array([ 9.39056640e+00,  2.80930292e-14, -3.37939692e-04,  8.86859780e-15,\n",
+       "         -8.46934297e-15, -1.89037895e-14,  3.13023241e-04,  4.84385560e-04,\n",
+       "          4.66163836e-04, -3.25098919e-15]),\n",
+       "  array([ 1.00153546e+01,  2.74858130e-14, -3.17894695e-04,  8.47499558e-15,\n",
+       "         -8.09146162e-15, -1.85205212e-14,  2.53995754e-04,  4.45872560e-04,\n",
+       "          4.46032989e-04, -3.13615222e-15]),\n",
+       "  array([ 1.06205893e+01,  2.62945968e-14, -3.08255801e-04,  8.09013228e-15,\n",
+       "         -7.72584028e-15, -1.77360205e-14,  2.03024877e-04,  4.13620593e-04,\n",
+       "          4.30122260e-04, -2.92629157e-15]),\n",
+       "  array([ 1.12065903e+01,  2.46074061e-14, -3.07412428e-04,  7.71971464e-15,\n",
+       "         -7.37844414e-15, -1.66062884e-14,  1.59310096e-04,  3.87044431e-04,\n",
+       "          4.18050406e-04, -2.63399500e-15]),\n",
+       "  array([ 1.17736785e+01,  2.25140747e-14, -3.13747839e-04,  7.36799253e-15,\n",
+       "         -7.05353559e-15, -1.51894780e-14,  1.21990612e-04,  3.65496864e-04,\n",
+       "          4.09386101e-04, -2.27252268e-15]),\n",
+       "  array([ 1.23221752e+01,  2.01035701e-14, -3.25684480e-04,  7.03788362e-15,\n",
+       "         -6.75382296e-15, -1.35440495e-14,  9.01742114e-05,  3.48292031e-04,\n",
+       "          4.03664361e-04, -1.85536712e-15]),\n",
+       "  array([ 1.28524025e+01,  1.74617374e-14, -3.41720957e-04,  6.73114607e-15,\n",
+       "         -6.48066551e-15, -1.17271653e-14,  6.29636096e-05,  3.34727367e-04,\n",
+       "          4.00402305e-04, -1.39586308e-15]),\n",
+       "  array([ 1.33646825e+01,  1.46694745e-14, -3.60460676e-04,  6.44857199e-15,\n",
+       "         -6.23431079e-15, -9.79335061e-15,  3.94796502e-05,  3.24103505e-04,\n",
+       "          3.99113737e-04, -9.06854834e-16]),\n",
+       "  array([ 1.38593374e+01,  1.18013351e-14, -3.80632575e-04,  6.19018775e-15,\n",
+       "         -6.01413554e-15, -7.79342696e-15,  1.88809597e-05,  3.15741674e-04,\n",
+       "          3.99322120e-04, -4.00424789e-16]),\n",
+       "  array([ 1.43366892e+01,  8.92453363e-15, -4.01104641e-04,  5.95543925e-15,\n",
+       "         -5.81887855e-15, -5.77371457e-15,  3.79868869e-07,  3.08998283e-04,\n",
+       "          4.00571678e-04,  1.12316140e-16]),\n",
+       "  array([ 1.47970596e+01,  6.09831924e-15, -4.20891085e-04,  5.74336016e-15,\n",
+       "         -5.64684572e-15, -3.77548778e-15, -1.67454013e-05,  3.03276565e-04,\n",
+       "          4.02436472e-04,  6.21378706e-16]),\n",
+       "  array([ 1.52407696e+01,  3.37367345e-15, -4.39154113e-04,  5.55271073e-15,\n",
+       "         -5.49608606e-15, -1.83466026e-15, -3.31421378e-05,  2.98035291e-04,\n",
+       "          4.04527396e-04,  1.11799038e-15]),\n",
+       "  array([ 1.56681394e+01,  7.93284959e-16, -4.55201281e-04,  5.38209187e-15,\n",
+       "         -5.36452987e-15,  1.83285585e-17, -4.93778512e-05,  2.92794692e-04,\n",
+       "          4.06497153e-04,  1.59464118e-15]),\n",
+       "  array([ 1.60794884e+01, -1.60824762e-15, -4.68479373e-04,  5.23002428e-15,\n",
+       "         -5.25010011e-15,  1.75845676e-15, -6.59379563e-05,  2.87139814e-04,\n",
+       "          4.08043340e-04,  2.04508706e-15]),\n",
+       "  array([ 1.64751348e+01, -3.80403241e-15, -4.78565665e-04,  5.09501903e-15,\n",
+       "         -5.15077760e-15,  3.36592492e-15, -8.32260117e-05,  2.80721586e-04,\n",
+       "          4.08909821e-04,  2.46431812e-15]),\n",
+       "  array([ 1.68553956e+01, -5.77436478e-15, -4.85157365e-04,  4.97560156e-15,\n",
+       "         -5.06466410e-15,  4.82585351e-15, -1.01566091e-04,  2.73255941e-04,\n",
+       "          4.08886623e-04,  2.84849847e-15]),\n",
+       "  array([ 1.72205861e+01, -7.50611209e-15, -4.88059894e-04,  4.87036712e-15,\n",
+       "         -4.98997833e-15,  6.12790168e-15, -1.21206856e-04,  2.64521335e-04,\n",
+       "          4.07808580e-04,  3.19488531e-15]),\n",
+       "  array([ 1.75710205e+01, -8.99203806e-15, -4.87174586e-04,  4.77793512e-15,\n",
+       "         -4.92511911e-15,  7.26583307e-15, -1.42326917e-04,  2.54355003e-04,\n",
+       "          4.05552990e-04,  3.50173217e-15]),\n",
+       "  array([ 1.79070109e+01, -1.02300969e-14, -4.82486262e-04,  4.69698469e-15,\n",
+       "         -4.86863585e-15,  8.23705148e-15, -1.65041098e-04,  2.42648283e-04,\n",
+       "          4.02036516e-04,  3.76818405e-15]),\n",
+       "  array([ 1.82288678e+01, -1.12227223e-14, -4.74051039e-04,  4.62626376e-15,\n",
+       "         -4.81921347e-15,  9.04212525e-15, -1.89407276e-04,  2.29341305e-04,\n",
+       "          3.97211550e-04,  3.99416722e-15]),\n",
+       "  array([ 1.85368994e+01, -1.19761320e-14, -4.61984658e-04,  4.56455478e-15,\n",
+       "         -4.77569235e-15,  9.68431573e-15, -2.15433486e-04,  2.14417327e-04,\n",
+       "          3.91062259e-04,  4.18027850e-15]),\n",
+       "  array([ 1.88314122e+01, -1.24996611e-14, -4.46451529e-04,  4.51085852e-15,\n",
+       "         -4.73687258e-15,  1.01691229e-14, -2.43085051e-04,  1.97896918e-04,\n",
+       "          3.83600471e-04,  4.32767788e-15]),\n",
+       "  array([ 1.91127102e+01, -1.28051318e-14, -4.27654443e-04,  4.46394017e-15,\n",
+       "         -4.70191344e-15,  1.05038566e-14, -2.72291517e-04,  1.79832232e-04,\n",
+       "          3.74861570e-04,  4.43798213e-15]),\n",
+       "  array([ 1.93810950e+01, -1.29063233e-14, -4.05826332e-04,  4.42276218e-15,\n",
+       "         -4.66991737e-15,  1.06972327e-14, -3.02953410e-04,  1.60301307e-04,\n",
+       "          3.64900383e-04,  4.51317144e-15]),\n",
+       "  array([ 1.96368661e+01, -1.28183648e-14, -3.81220233e-04,  4.38632228e-15,\n",
+       "         -4.64008200e-15,  1.07590298e-14, -3.34948113e-04,  1.39403135e-04,\n",
+       "          3.53787580e-04,  4.55550458e-15]),\n",
+       "  array([ 1.98803200e+01, -1.25573567e-14, -3.54103740e-04,  4.35365567e-15,\n",
+       "         -4.61168951e-15,  1.06997455e-14, -3.68135871e-04,  1.17252522e-04,\n",
+       "          3.41605946e-04,  4.56743411e-15]),\n",
+       "  array([ 2.01117509e+01, -1.21399347e-14, -3.24752085e-04,  4.32385753e-15,\n",
+       "         -4.58408053e-15,  1.05303238e-14, -4.02364704e-04,  9.39758176e-05,\n",
+       "          3.28447212e-04,  4.55153850e-15]),\n",
+       "  array([ 2.03314501e+01, -1.15829218e-14, -2.93442772e-04,  4.29606640e-15,\n",
+       "         -4.55666754e-15,  1.02619093e-14, -4.37474932e-04,  6.97070095e-05,\n",
+       "          3.14409178e-04,  4.51046119e-15]),\n",
+       "  array([ 2.05397060e+01, -1.09030343e-14, -2.60451042e-04,  4.26947775e-15,\n",
+       "         -4.52892223e-15,  9.90563835e-15, -4.73303094e-04,  4.45842997e-05,\n",
+       "          2.99593175e-04,  4.44685870e-15]),\n",
+       "  array([ 2.07368042e+01, -1.01166207e-14, -2.26045772e-04,  4.24334691e-15,\n",
+       "         -4.50037436e-15,  9.47246828e-15, -5.09685247e-04,  1.87472166e-05,\n",
+       "          2.84101912e-04,  4.36335782e-15]),\n",
+       "  array([ 2.09230272e+01, -9.23952106e-15, -1.90487695e-04,  4.21704646e-15,\n",
+       "         -4.47055703e-15,  8.97302487e-15, -5.46459955e-04, -7.66606865e-06,\n",
+       "          2.68037478e-04,  4.26251612e-15]),\n",
+       "  array([ 2.10986545e+01, -8.28683528e-15, -1.54025380e-04,  4.18991696e-15,\n",
+       "         -4.43915087e-15,  8.41750812e-15, -5.83470288e-04, -3.45205069e-05,\n",
+       "          2.51499992e-04,  4.14679811e-15]),\n",
+       "  array([ 2.12639624e+01, -7.27284989e-15, -1.16894378e-04,  4.16141082e-15,\n",
+       "         -4.40584759e-15,  7.81559261e-15, -6.20565871e-04, -6.16859954e-05,\n",
+       "          2.34586251e-04,  4.01855002e-15]),\n",
+       "  array([ 2.14192239e+01, -6.21094122e-15, -7.93156726e-05,  4.13107411e-15,\n",
+       "         -4.37036838e-15,  7.17636843e-15, -6.57604241e-04, -8.90386282e-05,\n",
+       "          2.17388770e-04,  3.87998379e-15]),\n",
+       "  array([ 2.15647089e+01, -5.11351832e-15, -4.14947849e-05,  4.09850445e-15,\n",
+       "         -4.33250266e-15,  6.50829793e-15, -6.94451898e-04, -1.16461663e-04,\n",
+       "          1.99995044e-04,  3.73316544e-15]),\n",
+       "  array([ 2.17006839e+01, -3.99199039e-15, -3.62125502e-06,  4.06337078e-15,\n",
+       "         -4.29208588e-15,  5.81918963e-15, -7.30985037e-04, -1.43846211e-04,\n",
+       "          1.82487012e-04,  3.58000777e-15]),\n",
+       "  array([ 2.18274120e+01, -2.85675510e-15,  3.41315682e-05,  4.02540960e-15,\n",
+       "         -4.24899926e-15,  5.11618671e-15, -7.67090001e-04, -1.71091680e-04,\n",
+       "          1.64940703e-04,  3.42226663e-15]),\n",
+       "  array([ 2.19451528e+01, -1.71720416e-15,  7.16064741e-05,  3.98442358e-15,\n",
+       "         -4.20316604e-15,  4.40576740e-15, -8.02663510e-04, -1.98106019e-04,\n",
+       "          1.47426040e-04,  3.26154025e-15]),\n",
+       "  array([ 2.20541624e+01, -5.81742898e-16,  1.08662124e-04,  3.94027563e-15,\n",
+       "         -4.15455099e-15,  3.69375540e-15, -8.37612680e-04, -2.24805785e-04,\n",
+       "          1.30006766e-04,  3.09927104e-15]),\n",
+       "  array([ 2.21546936e+01,  5.42178898e-16,  1.45172614e-04,  3.89288632e-15,\n",
+       "         -4.10315592e-15,  2.98533798e-15, -8.71854896e-04, -2.51116068e-04,\n",
+       "          1.12740481e-04,  2.93674940e-15]),\n",
+       "  array([ 2.22469954e+01,  1.64802745e-15,  1.81026900e-04,  3.84222925e-15,\n",
+       "         -4.04901646e-15,  2.28509031e-15, -9.05317554e-04, -2.76970308e-04,\n",
+       "          9.56787590e-05,  2.77511911e-15]),\n",
+       "  array([ 2.23313134e+01,  2.73013898e-15,  2.16128126e-04,  3.78832551e-15,\n",
+       "         -3.99219929e-15,  1.59700431e-15, -9.37937697e-04, -3.02310019e-04,\n",
+       "          7.88673391e-05,  2.61538384e-15]),\n",
+       "  array([ 2.24078894e+01,  3.78366920e-15,  2.50392874e-04,  3.73123873e-15,\n",
+       "         -3.93279852e-15,  9.24520853e-16, -9.69661586e-04, -3.27084445e-04,\n",
+       "          6.23463607e-05,  2.45841457e-15]),\n",
+       "  array([ 2.24769615e+01,  4.80453965e-15,  2.83750363e-04,  3.67107019e-15,\n",
+       "         -3.87093199e-15,  2.70564087e-16, -1.00044421e-03, -3.51250169e-04,\n",
+       "          4.61506409e-05,  2.30495762e-15]),\n",
+       "  array([ 2.25387644e+01,  5.78938268e-15,  3.16141623e-04,  3.60795362e-15,\n",
+       "         -3.80673787e-15, -3.62422928e-16, -1.03024876e-03, -3.74770684e-04,\n",
+       "          3.03099757e-05,  2.15564297e-15]),\n",
+       "  array([ 2.25935290e+01,  6.73548571e-15,  3.47518650e-04,  3.54205037e-15,\n",
+       "         -3.74037125e-15, -9.72442142e-16, -1.05904608e-03, -3.97615950e-04,\n",
+       "          1.48494580e-05,  2.01099278e-15]),\n",
+       "  array([ 2.26414823e+01,  7.64073607e-15,  3.77843561e-04,  3.47354451e-15,\n",
+       "         -3.67200097e-15, -1.55790454e-15, -1.08681413e-03, -4.19761936e-04,\n",
+       "         -2.10196101e-07,  1.87142985e-15]),\n",
+       "  array([ 2.26828477e+01,  8.50356691e-15,  4.07087771e-04,  3.40263814e-15,\n",
+       "         -3.60180669e-15, -2.11759479e-15, -1.11353740e-03, -4.41190161e-04,\n",
+       "         -1.48523196e-05,  1.73728608e-15]),\n",
+       "  array([ 2.27178450e+01,  9.32290487e-15,  4.35231176e-04,  3.32954745e-15,\n",
+       "         -3.52997586e-15, -2.65063692e-15, -1.13920639e-03, -4.61887242e-04,\n",
+       "         -2.90639703e-05,  1.60881057e-15]),\n",
+       "  array([ 2.27466900e+01,  1.00981198e-14,  4.62261371e-04,  3.25449863e-15,\n",
+       "         -3.45670115e-15, -3.15646128e-15, -1.16381705e-03, -4.81844451e-04,\n",
+       "         -4.28356138e-05,  1.48617755e-15]),\n",
+       "  array([ 2.27695949e+01,  1.08289772e-14,  4.88172902e-04,  3.17772443e-15,\n",
+       "         -3.38217802e-15, -3.63477297e-15, -1.18737032e-03, -5.01057292e-04,\n",
+       "         -5.61608169e-05,  1.36949385e-15]),\n",
+       "  array([ 2.27867682e+01,  1.15155927e-14,  5.12966552e-04,  3.09946089e-15,\n",
+       "         -3.30660250e-15, -4.08552197e-15, -1.20987154e-03, -5.19525088e-04,\n",
+       "         -6.90359541e-05,  1.25880614e-15]),\n",
+       "  array([ 2.27984145e+01,  1.21583901e-14,  5.36648659e-04,  3.01994440e-15,\n",
+       "         -3.23016938e-15, -4.50887492e-15, -1.23133009e-03, -5.37250592e-04,\n",
+       "         -8.14599273e-05,  1.15410757e-15]),\n",
+       "  array([ 2.28047347e+01,  1.27580613e-14,  5.59230483e-04,  2.93940931e-15,\n",
+       "         -3.15307039e-15, -4.90518874e-15, -1.25175888e-03, -5.54239622e-04,\n",
+       "         -9.34339010e-05,  1.05534423e-15]),\n",
+       "  array([ 2.28059260e+01,  1.33155302e-14,  5.80727611e-04,  2.85808562e-15,\n",
+       "         -3.07549275e-15, -5.27498590e-15, -1.27117394e-03, -5.70500712e-04,\n",
+       "         -1.04961053e-04,  9.62420989e-16]),\n",
+       "  array([ 2.28021817e+01,  1.38319181e-14,  6.01159393e-04,  2.77619731e-15,\n",
+       "         -2.99761784e-15, -5.61893156e-15, -1.28959406e-03, -5.86044785e-04,\n",
+       "         -1.16046339e-04,  8.75207049e-16]),\n",
+       "  array([ 2.27936915e+01,  1.43085127e-14,  6.20548430e-04,  2.69396061e-15,\n",
+       "         -2.91962019e-15, -5.93781225e-15, -1.30704038e-03, -6.00884850e-04,\n",
+       "         -1.26696277e-04,  7.93541079e-16]),\n",
+       "  array([ 2.27806414e+01,  1.47467394e-14,  6.38920091e-04,  2.61158288e-15,\n",
+       "         -2.84166647e-15, -6.23251627e-15, -1.32353611e-03, -6.15035720e-04,\n",
+       "         -1.36918739e-04,  7.17235944e-16]),\n",
+       "  array([ 2.27632135e+01,  1.51481346e-14,  6.56302068e-04,  2.52926154e-15,\n",
+       "         -2.76391483e-15, -6.50401563e-15, -1.33910614e-03, -6.28513746e-04,\n",
+       "         -1.46722763e-04,  6.46083091e-16]),\n",
+       "  array([ 2.27415865e+01,  1.55143224e-14,  6.72723971e-04,  2.44718282e-15,\n",
+       "         -2.68651471e-15, -6.75334936e-15, -1.35377680e-03, -6.41336572e-04,\n",
+       "         -1.56118378e-04,  5.79856577e-16]),\n",
+       "  array([ 2.27159351e+01,  1.58469923e-14,  6.88216948e-04,  2.36552194e-15,\n",
+       "         -2.60960579e-15, -6.98160834e-15, -1.36757559e-03, -6.53522911e-04,\n",
+       "         -1.65116440e-04,  5.18316787e-16]),\n",
+       "  array([ 2.26864305e+01,  1.61478796e-14,  7.02813341e-04,  2.28444206e-15,\n",
+       "         -2.53331825e-15, -7.18992130e-15, -1.38053088e-03, -6.65092331e-04,\n",
+       "         -1.73728478e-04,  4.61213829e-16]),\n",
+       "  array([ 2.26532402e+01,  1.64187477e-14,  7.16546378e-04,  2.20409463e-15,\n",
+       "         -2.45777216e-15, -7.37944215e-15, -1.39267174e-03, -6.76065067e-04,\n",
+       "         -1.81966560e-04,  4.08290652e-16]),\n",
+       "  array([ 2.26165282e+01,  1.66613723e-14,  7.29449874e-04,  2.12461864e-15,\n",
+       "         -2.38307791e-15, -7.55133835e-15, -1.40402768e-03, -6.86461835e-04,\n",
+       "         -1.89843158e-04,  3.59285887e-16]),\n",
+       "  array([ 2.25764546e+01,  1.68775263e-14,  7.41557982e-04,  2.04614123e-15,\n",
+       "         -2.30933577e-15, -7.70678040e-15, -1.41462848e-03, -6.96303674e-04,\n",
+       "         -1.97371034e-04,  3.13936448e-16]),\n",
+       "  array([ 2.25331761e+01,  1.70689677e-14,  7.52904947e-04,  1.96877719e-15,\n",
+       "         -2.23663657e-15, -7.84693232e-15, -1.42450401e-03, -7.05611790e-04,\n",
+       "         -2.04563129e-04,  2.71979881e-16]),\n",
+       "  array([ 2.24868460e+01,  1.72374278e-14,  7.63524900e-04,  1.89262994e-15,\n",
+       "         -2.16506118e-15, -7.97294306e-15, -1.43368402e-03, -7.14407420e-04,\n",
+       "         -2.11432461e-04,  2.33156508e-16]),\n",
+       "  array([ 2.24376138e+01,  1.73846011e-14,  7.73451659e-04,  1.81779028e-15,\n",
+       "         -2.09468226e-15, -8.08593875e-15, -1.44219808e-03, -7.22711703e-04,\n",
+       "         -2.17992034e-04,  1.97211344e-16]),\n",
+       "  array([ 2.23856256e+01,  1.75121366e-14,  7.82718560e-04,  1.74434078e-15,\n",
+       "         -2.02556075e-15, -8.18701583e-15, -1.45007536e-03, -7.30545566e-04,\n",
+       "         -2.24254758e-04,  1.63895854e-16]),\n",
+       "  array([ 2.23310240e+01,  1.76216298e-14,  7.91358301e-04,  1.67234879e-15,\n",
+       "         -1.95775320e-15, -8.27723496e-15, -1.45734454e-03, -7.37929617e-04,\n",
+       "         -2.30233365e-04,  1.32969434e-16]),\n",
+       "  array([ 2.22739482e+01,  1.77146161e-14,  7.99402808e-04,  1.60187556e-15,\n",
+       "         -1.89130408e-15, -8.35761555e-15, -1.46403370e-03, -7.44884050e-04,\n",
+       "         -2.35940346e-04,  1.04200864e-16]),\n",
+       "  array([ 2.22145339e+01,  1.77925649e-14,  8.06883113e-04,  1.53296690e-15,\n",
+       "         -1.82625573e-15, -8.42913120e-15, -1.47017021e-03, -7.51428563e-04,\n",
+       "         -2.41387886e-04,  7.73694204e-17]),\n",
+       "  array([ 2.21529135e+01,  1.78568749e-14,  8.13829252e-04,  1.46566450e-15,\n",
+       "         -1.76263901e-15, -8.49270555e-15, -1.47578064e-03, -7.57582278e-04,\n",
+       "         -2.46587811e-04,  5.22660267e-17]),\n",
+       "  array([ 2.20892161e+01,  1.79088703e-14,  8.20270169e-04,  1.40001780e-15,\n",
+       "         -1.70046217e-15, -8.54920898e-15, -1.48089072e-03, -7.63363674e-04,\n",
+       "         -2.51551535e-04,  2.86940799e-17]),\n",
+       "  array([ 2.20235672e+01,  1.79497971e-14,  8.26233648e-04,  1.33603286e-15,\n",
+       "         -1.63975889e-15, -8.59945582e-15, -1.48552521e-03, -7.68790532e-04,\n",
+       "         -2.56290021e-04,  6.46984177e-18]),\n",
+       "  array([ 2.19560893e+01,  1.79808210e-14,  8.31746244e-04,  1.27372845e-15,\n",
+       "         -1.58053755e-15, -8.64420215e-15, -1.48970789e-03, -7.73879885e-04,\n",
+       "         -2.60813744e-04, -1.45763529e-17]),\n",
+       "  array([ 2.18869016e+01,  1.80030256e-14,  8.36833231e-04,  1.21311514e-15,\n",
+       "         -1.52280269e-15, -8.68414418e-15, -1.49346150e-03, -7.78647973e-04,\n",
+       "         -2.65132658e-04, -3.46000378e-17]),\n",
+       "  array([ 2.18161199e+01,  1.80174112e-14,  8.41518570e-04,  1.15419661e-15,\n",
+       "         -1.46655456e-15, -8.71991714e-15, -1.49680769e-03, -7.83110215e-04,\n",
+       "         -2.69256173e-04, -5.37422581e-17]),\n",
+       "  array([ 2.17438571e+01,  1.80248946e-14,  8.45824872e-04,  1.09697061e-15,\n",
+       "         -1.41178903e-15, -8.75209475e-15, -1.49976703e-03, -7.87281179e-04,\n",
+       "         -2.73193136e-04, -7.21293785e-17]),\n",
+       "  array([ 2.16702227e+01,  1.80263088e-14,  8.49773385e-04,  1.04142975e-15,\n",
+       "         -1.35849782e-15, -8.78118907e-15, -1.50235893e-03, -7.91174567e-04,\n",
+       "         -2.76951815e-04, -8.98730270e-17]),\n",
+       "  array([ 2.15953232e+01,  1.80224040e-14,  8.53383985e-04,  9.87562350e-16,\n",
+       "         -1.30666857e-15, -8.80765093e-15, -1.50460169e-03, -7.94803204e-04,\n",
+       "         -2.80539894e-04, -1.07070165e-16]),\n",
+       "  array([ 2.15192620e+01,  1.80138485e-14,  8.56675179e-04,  9.35353538e-16,\n",
+       "         -1.25628461e-15, -8.83187078e-15, -1.50651246e-03, -7.98179034e-04,\n",
+       "         -2.83964467e-04, -1.23803282e-16]),\n",
+       "  array([ 2.14421395e+01,  1.80012307e-14,  8.59664112e-04,  8.84764638e-16,\n",
+       "         -1.20734614e-15, -8.85417997e-15, -1.50810727e-03, -8.01313123e-04,\n",
+       "         -2.87232042e-04, -1.40140742e-16]),\n",
+       "  array([ 2.13640531e+01,  1.79850611e-14,  8.62366588e-04,  8.35799656e-16,\n",
+       "         -1.15980931e-15, -8.87485231e-15, -1.50940102e-03, -8.04215673e-04,\n",
+       "         -2.90348545e-04, -1.56136736e-16]),\n",
+       "  array([ 2.12850972e+01,  1.79657748e-14,  8.64797099e-04,  7.88420351e-16,\n",
+       "         -1.11366541e-15, -8.89410626e-15, -1.51040752e-03, -8.06896031e-04,\n",
+       "         -2.93319333e-04, -1.71832636e-16]),\n",
+       "  array([ 2.12053633e+01,  1.79437343e-14,  8.66968854e-04,  7.42605447e-16,\n",
+       "         -1.06888566e-15, -8.91210718e-15, -1.51113950e-03, -8.09362720e-04,\n",
+       "         -2.96149206e-04, -1.87256811e-16]),\n",
+       "  array([ 2.11249400e+01,  1.79192333e-14,  8.68893827e-04,  6.98318441e-16,\n",
+       "         -1.02545267e-15, -8.92897013e-15, -1.51160867e-03, -8.11623458e-04,\n",
+       "         -2.98842431e-04, -2.02425696e-16]),\n",
+       "  array([ 2.10439131e+01,  1.78924998e-14,  8.70582796e-04,  6.55530906e-16,\n",
+       "         -9.83339651e-16, -8.94476284e-15, -1.51182574e-03, -8.13685197e-04,\n",
+       "         -3.01402761e-04, -2.17344273e-16]),\n",
+       "  array([ 2.09623657e+01,  1.78637005e-14,  8.72045406e-04,  6.14211164e-16,\n",
+       "         -9.42522014e-16, -8.95950894e-15, -1.51180047e-03, -8.15554157e-04,\n",
+       "         -3.03833461e-04, -2.32007043e-16]),\n",
+       "  array([ 2.08803778e+01,  1.78329447e-14,  8.73290221e-04,  5.74328914e-16,\n",
+       "         -9.02973447e-16, -8.97319143e-15, -1.51154171e-03, -8.17235868e-04,\n",
+       "         -3.06137342e-04, -2.46398831e-16]),\n",
+       "  array([ 2.07980269e+01,  1.78002891e-14,  8.74324790e-04,  5.35850948e-16,\n",
+       "         -8.64670459e-16, -8.98575641e-15, -1.51105749e-03, -8.18735216e-04,\n",
+       "         -3.08316786e-04, -2.60495734e-16]),\n",
+       "  array([ 2.07153880e+01,  1.77657419e-14,  8.75155717e-04,  4.98746329e-16,\n",
+       "         -8.27588057e-16, -8.99711681e-15, -1.51035503e-03, -8.20056492e-04,\n",
+       "         -3.10373786e-04, -2.74266022e-16]),\n",
+       "  array([ 2.06325331e+01,  1.77292684e-14,  8.75788728e-04,  4.62984643e-16,\n",
+       "         -7.91701780e-16, -9.00715642e-15, -1.50944084e-03, -8.21203439e-04,\n",
+       "         -3.12309979e-04, -2.87671157e-16]),\n",
+       "  array([ 2.05495317e+01,  1.76907950e-14,  8.76228752e-04,  4.28532758e-16,\n",
+       "         -7.56991143e-16, -9.01573390e-15, -1.50832076e-03, -8.22179310e-04,\n",
+       "         -3.14126685e-04, -3.00666809e-16]),\n",
+       "  array([ 2.04664509e+01,  1.76502153e-14,  8.76479992e-04,  3.95362157e-16,\n",
+       "         -7.23433276e-16, -9.02268686e-15, -1.50700003e-03, -8.22986921e-04,\n",
+       "         -3.15824946e-04, -3.13203810e-16]),\n",
+       "  array([ 2.03833550e+01,  1.76073943e-14,  8.76546010e-04,  3.63445252e-16,\n",
+       "         -6.91006598e-16, -9.02783600e-15, -1.50548339e-03, -8.23628705e-04,\n",
+       "         -3.17405565e-04, -3.25229246e-16]),\n",
+       "  array([ 2.03003061e+01,  1.75621739e-14,  8.76429804e-04,  3.32753560e-16,\n",
+       "         -6.59692601e-16, -9.03098916e-15, -1.50377510e-03, -8.24106772e-04,\n",
+       "         -3.18869146e-04, -3.36687475e-16]),\n",
+       "  array([ 2.02173636e+01,  1.75143780e-14,  8.76133889e-04,  3.03261319e-16,\n",
+       "         -6.29472629e-16, -9.03194543e-15, -1.50187901e-03, -8.24422961e-04,\n",
+       "         -3.20216137e-04, -3.47521098e-16]),\n",
+       "  array([ 2.01345846e+01,  1.74638175e-14,  8.75660380e-04,  2.74942325e-16,\n",
+       "         -6.00331029e-16, -9.03049907e-15, -1.49979869e-03, -8.24578903e-04,\n",
+       "         -3.21446865e-04, -3.57671975e-16]),\n",
+       "  array([ 2.00520239e+01,  1.74102952e-14,  8.75011071e-04,  2.47775049e-16,\n",
+       "         -5.72250395e-16, -9.02644341e-15, -1.49753741e-03, -8.24576067e-04,\n",
+       "         -3.22561582e-04, -3.67082145e-16]),\n",
+       "  array([ 1.99697338e+01,  1.73536107e-14,  8.74187515e-04,  2.21735646e-16,\n",
+       "         -5.45218070e-16, -9.01957453e-15, -1.49509827e-03, -8.24415821e-04,\n",
+       "         -3.23560495e-04, -3.75694817e-16]),\n",
+       "  array([ 1.98877644e+01,  1.72935648e-14,  8.73191103e-04,  1.96805401e-16,\n",
+       "         -5.19219054e-16, -9.00969483e-15, -1.49248424e-03, -8.24099481e-04,\n",
+       "         -3.24443810e-04, -3.83455166e-16]),\n",
+       "  array([ 1.98061636e+01,  1.72299644e-14,  8.72023135e-04,  1.72963148e-16,\n",
+       "         -4.94242983e-16, -8.99661640e-15, -1.48969820e-03, -8.23628361e-04,\n",
+       "         -3.25211763e-04, -3.90311245e-16]),\n",
+       "  array([ 1.97249770e+01,  1.71626262e-14,  8.70684896e-04,  1.50187017e-16,\n",
+       "         -4.70282671e-16, -8.98016415e-15, -1.48674304e-03, -8.23003818e-04,\n",
+       "         -3.25864654e-04, -3.96214684e-16]),\n",
+       "  array([ 1.96442479e+01,  1.70913810e-14,  8.69177723e-04,  1.28468385e-16,\n",
+       "         -4.47320858e-16, -8.96017868e-15, -1.48362166e-03, -8.22227300e-04,\n",
+       "         -3.26402881e-04, -4.01121349e-16]),\n",
+       "  array([ 1.95640177e+01,  1.70160775e-14,  8.67503068e-04,  1.07790933e-16,\n",
+       "         -4.25348901e-16, -8.93651895e-15, -1.48033708e-03, -8.21300381e-04,\n",
+       "         -3.26826964e-04, -4.04992205e-16]),\n",
+       "  array([ 1.94843256e+01,  1.69365852e-14,  8.65662562e-04,  8.81342288e-17,\n",
+       "         -4.04363037e-16, -8.90906466e-15, -1.47689244e-03, -8.20224803e-04,\n",
+       "         -3.27137573e-04, -4.07793744e-16]),\n",
+       "  array([ 1.94052086e+01,  1.68527978e-14,  8.63658065e-04,  6.94851480e-17,\n",
+       "         -3.84354035e-16, -8.87771831e-15, -1.47329104e-03, -8.19002504e-04,\n",
+       "         -3.27335553e-04, -4.09498404e-16]),\n",
+       "  array([ 1.93267019e+01,  1.67646357e-14,  8.61491719e-04,  5.18307647e-17,\n",
+       "         -3.65313792e-16, -8.84240698e-15, -1.46953641e-03, -8.17635653e-04,\n",
+       "         -3.27421942e-04, -4.10085112e-16]),\n",
+       "  array([ 1.92488385e+01,  1.66720486e-14,  8.59165992e-04,  3.51586519e-17,\n",
+       "         -3.47234630e-16, -8.80308382e-15, -1.46563231e-03, -8.16126667e-04,\n",
+       "         -3.27397988e-04, -4.09539611e-16]),\n",
+       "  array([ 1.91716495e+01,  1.65750170e-14,  8.56683715e-04,  1.94571690e-17,\n",
+       "         -3.30108630e-16, -8.75972917e-15, -1.46158276e-03, -8.14478237e-04,\n",
+       "         -3.27265164e-04, -4.07854724e-16]),\n",
+       "  array([ 1.90951642e+01,  1.64735541e-14,  8.54048111e-04,  4.71589878e-18,\n",
+       "         -3.13926746e-16, -8.71235142e-15, -1.45739207e-03, -8.12693343e-04,\n",
+       "         -3.27025179e-04, -4.05030555e-16]),\n",
+       "  array([ 1.90194098e+01,  1.63677068e-14,  8.51262827e-04, -9.09011548e-18,\n",
+       "         -2.98693960e-16, -8.66098761e-15, -1.45306487e-03, -8.10775264e-04,\n",
+       "         -3.26679986e-04, -4.01074646e-16]),\n",
+       "  array([ 1.89444118e+01,  1.62575565e-14,  8.48331948e-04, -2.19567123e-17,\n",
+       "         -2.84388585e-16, -8.60570350e-15, -1.44860608e-03, -8.08727584e-04,\n",
+       "         -3.26231783e-04, -3.96001688e-16]),\n",
+       "  array([ 1.88701937e+01,  1.61432192e-14,  8.45260010e-04, -3.39007824e-17,\n",
+       "         -2.71008404e-16, -8.54659360e-15, -1.44402092e-03, -8.06554196e-04,\n",
+       "         -3.25683020e-04, -3.89834034e-16]),\n",
+       "  array([ 1.87967776e+01,  1.60248459e-14,  8.42052006e-04, -4.49337252e-17,\n",
+       "         -2.58545214e-16, -8.48378072e-15, -1.43931497e-03, -8.04259302e-04,\n",
+       "         -3.25036392e-04, -3.82601168e-16]),\n",
+       "  array([ 1.87241834e+01,  1.59026216e-14,  8.38713386e-04, -5.50670583e-17,\n",
+       "         -2.46990219e-16, -8.41741530e-15, -1.43449408e-03, -8.01847402e-04,\n",
+       "         -3.24294837e-04, -3.74339638e-16]),\n",
+       "  array([ 1.86524294e+01,  1.57767649e-14,  8.35250050e-04, -6.43127710e-17,\n",
+       "         -2.36334184e-16, -8.34767445e-15, -1.42956440e-03, -7.99323291e-04,\n",
+       "         -3.23461527e-04, -3.65092802e-16]),\n",
+       "  array([ 1.85815325e+01,  1.56475267e-14,  8.31668333e-04, -7.26834734e-17,\n",
+       "         -2.26567457e-16, -8.27476073e-15, -1.42453239e-03, -7.96692037e-04,\n",
+       "         -3.22539858e-04, -3.54910500e-16]),\n",
+       "  array([ 1.85115075e+01,  1.55151886e-14,  8.27974986e-04, -8.01917604e-17,\n",
+       "         -2.17679317e-16, -8.19890068e-15, -1.41940476e-03, -7.93958970e-04,\n",
+       "         -3.21533436e-04, -3.43848669e-16]),\n",
+       "  array([ 1.84423680e+01,  1.53800609e-14,  8.24177152e-04, -8.68505748e-17,\n",
+       "         -2.09658249e-16, -8.12034310e-15, -1.41418845e-03, -7.91129657e-04,\n",
+       "         -3.20446062e-04, -3.31968910e-16]),\n",
+       "  array([ 1.83741257e+01,  1.52424807e-14,  8.20282333e-04, -9.26733404e-17,\n",
+       "         -2.02491999e-16, -8.03935720e-15, -1.40889062e-03, -7.88209883e-04,\n",
+       "         -3.19281717e-04, -3.19338008e-16]),\n",
+       "  array([ 1.83067908e+01,  1.51028092e-14,  8.16298356e-04, -9.76739794e-17,\n",
+       "         -1.96167537e-16, -7.95623045e-15, -1.40351862e-03, -7.85205619e-04,\n",
+       "         -3.18044537e-04, -3.06027397e-16]),\n",
+       "  array([ 1.82403722e+01,  1.49614293e-14,  8.12233334e-04, -1.01866877e-16,\n",
+       "         -1.90671008e-16, -7.87126635e-15, -1.39807994e-03, -7.82122993e-04,\n",
+       "         -3.16738795e-04, -2.92112589e-16]),\n",
+       "  array([ 1.81748770e+01,  1.48187423e-14,  8.08095617e-04, -1.05266841e-16,\n",
+       "         -1.85987673e-16, -7.78478204e-15, -1.39258218e-03, -7.78968264e-04,\n",
+       "         -3.15368877e-04, -2.77672576e-16]),\n",
+       "  array([ 1.81103109e+01,  1.46751647e-14,  8.03893748e-04, -1.07889238e-16,\n",
+       "         -1.82102043e-16, -7.69710577e-15, -1.38703303e-03, -7.75747782e-04,\n",
+       "         -3.13939258e-04, -2.62789195e-16]),\n",
+       "  array([ 1.80466783e+01,  1.45311253e-14,  7.99636410e-04, -1.09749912e-16,\n",
+       "         -1.78997808e-16, -7.60857430e-15, -1.38144020e-03, -7.72467960e-04,\n",
+       "         -3.12454475e-04, -2.47546480e-16]),\n",
+       "  array([ 1.79839821e+01,  1.43870616e-14,  7.95332371e-04, -1.10865258e-16,\n",
+       "         -1.76657931e-16, -7.51953021e-15, -1.37581138e-03, -7.69135230e-04,\n",
+       "         -3.10919105e-04, -2.32029998e-16]),\n",
+       "  array([ 1.79222237e+01,  1.42434161e-14,  7.90990430e-04, -1.11252159e-16,\n",
+       "         -1.75064610e-16, -7.43031921e-15, -1.37015423e-03, -7.65756013e-04,\n",
+       "         -3.09337733e-04, -2.16326168e-16]),\n",
+       "  array([ 1.78614035e+01,  1.41006327e-14,  7.86619355e-04, -1.10927934e-16,\n",
+       "         -1.74199271e-16, -7.34128738e-15, -1.36447631e-03, -7.62336682e-04,\n",
+       "         -3.07714929e-04, -2.00521591e-16]),\n",
+       "  array([ 1.78015201e+01,  1.39591532e-14,  7.82227830e-04, -1.09910522e-16,\n",
+       "         -1.74042778e-16, -7.25277843e-15, -1.35878503e-03, -7.58883520e-04,\n",
+       "         -3.06055216e-04, -1.84702367e-16]),\n",
+       "  array([ 1.77425711e+01,  1.38194139e-14,  7.77824393e-04, -1.08218244e-16,\n",
+       "         -1.74575251e-16, -7.16513101e-15, -1.35308762e-03, -7.55402684e-04,\n",
+       "         -3.04363052e-04, -1.68953433e-16]),\n",
+       "  array([ 1.76845527e+01,  1.36818415e-14,  7.73417374e-04, -1.05869947e-16,\n",
+       "         -1.75776251e-16, -7.07867606e-15, -1.34739110e-03, -7.51900176e-04,\n",
+       "         -3.02642793e-04, -1.53357909e-16]),\n",
+       "  array([ 1.76274600e+01,  1.35468497e-14,  7.69014845e-04, -1.02884931e-16,\n",
+       "         -1.77624758e-16, -6.99373421e-15, -1.34170221e-03, -7.48381796e-04,\n",
+       "         -3.00898674e-04, -1.37996463e-16]),\n",
+       "  array([ 1.75712867e+01,  1.34148362e-14,  7.64624555e-04, -9.92829917e-17,\n",
+       "         -1.80099263e-16, -6.91061328e-15, -1.33602737e-03, -7.44853118e-04,\n",
+       "         -2.99134785e-04, -1.22946717e-16]),\n",
+       "  array([ 1.75160254e+01,  1.32861788e-14,  7.60253880e-04, -9.50842877e-17,\n",
+       "         -1.83177696e-16, -6.82960619e-15, -1.33037269e-03, -7.41319453e-04,\n",
+       "         -2.97355042e-04, -1.08282729e-16]),\n",
+       "  array([ 1.74616675e+01,  1.31612322e-14,  7.55909770e-04, -9.03094824e-17,\n",
+       "         -1.86837605e-16, -6.75098875e-15, -1.32474386e-03, -7.37785815e-04,\n",
+       "         -2.95563168e-04, -9.40744119e-17]),\n",
+       "  array([ 1.74082032e+01,  1.30403264e-14,  7.51598698e-04, -8.49797216e-17,\n",
+       "         -1.91056196e-16, -6.67501666e-15, -1.31914617e-03, -7.34256900e-04,\n",
+       "         -2.93762672e-04, -8.03868244e-17]),\n",
+       "  array([ 1.73556217e+01,  1.29237633e-14,  7.47326617e-04, -7.91165324e-17,\n",
+       "         -1.95810328e-16, -6.60192434e-15, -1.31358446e-03, -7.30737054e-04,\n",
+       "         -2.91956829e-04, -6.72798576e-17]),\n",
+       "  array([ 1.73039109e+01,  1.28118137e-14,  7.43098914e-04, -7.27413965e-17,\n",
+       "         -2.01076152e-16, -6.53192286e-15, -1.30806310e-03, -7.27230248e-04,\n",
+       "         -2.90148663e-04, -5.48079110e-17]),\n",
+       "  array([ 1.72530577e+01,  1.27047122e-14,  7.38920375e-04, -6.58772871e-17,\n",
+       "         -2.06830646e-16, -6.46520179e-15, -1.30258595e-03, -7.23740062e-04,\n",
+       "         -2.88340931e-04, -4.30200115e-17]),\n",
+       "  array([ 1.72030481e+01,  1.26026643e-14,  7.34795150e-04, -5.85456182e-17,\n",
+       "         -2.13048830e-16, -6.40191952e-15, -1.29715635e-03, -7.20269660e-04,\n",
+       "         -2.86536110e-04, -3.19579264e-17]),\n",
+       "  array([ 1.71538669e+01,  1.25058332e-14,  7.30726727e-04, -5.07702197e-17,\n",
+       "         -2.19707560e-16, -6.34221258e-15, -1.29177710e-03, -7.16821782e-04,\n",
+       "         -2.84736385e-04, -2.16578571e-17]),\n",
+       "  array([ 1.71054977e+01,  1.24143478e-14,  7.26717905e-04, -4.25737635e-17,\n",
+       "         -2.26782324e-16, -6.28618647e-15, -1.28645042e-03, -7.13398724e-04,\n",
+       "         -2.82943638e-04, -1.21486948e-17]),\n",
+       "  array([ 1.70579236e+01,  1.23282973e-14,  7.22770777e-04, -3.39789043e-17,\n",
+       "         -2.34248371e-16, -6.23391882e-15, -1.28117801e-03, -7.10002333e-04,\n",
+       "         -2.81159447e-04, -3.45256358e-18]),\n",
+       "  array([ 1.70111261e+01,  1.22477295e-14,  7.18886722e-04, -2.50101106e-17,\n",
+       "         -2.42082540e-16, -6.18545999e-15, -1.27596095e-03, -7.06634000e-04,\n",
+       "         -2.79385073e-04,  4.41506150e-18]),\n",
+       "  array([ 1.69650863e+01,  1.21726551e-14,  7.15066389e-04, -1.56891726e-17,\n",
+       "         -2.50259165e-16, -6.14082845e-15, -1.27079977e-03, -7.03294656e-04,\n",
+       "         -2.77621466e-04,  1.14462366e-17]),\n",
+       "  array([ 1.69197841e+01,  1.21030414e-14,  7.11309707e-04, -6.04136994e-18,\n",
+       "         -2.58755977e-16, -6.10001676e-15, -1.26569442e-03, -6.99984774e-04,\n",
+       "         -2.75869257e-04,  1.76393957e-17]),\n",
+       "  array([ 1.68751984e+01,  1.20388182e-14,  7.07615878e-04,  3.91028507e-18,\n",
+       "         -2.67548929e-16, -6.06298687e-15, -1.26064425e-03, -6.96704373e-04,\n",
+       "         -2.74128766e-04,  2.30002682e-17]),\n",
+       "  array([ 1.68313074e+01,  1.19798758e-14,  7.03983395e-04,  1.41429458e-17,\n",
+       "         -2.76614375e-16, -6.02967278e-15, -1.25564810e-03, -6.93453020e-04,\n",
+       "         -2.72400003e-04,  2.75413916e-17]),\n",
+       "  array([ 1.67880883e+01,  1.19260664e-14,  7.00410055e-04,  2.46337109e-17,\n",
+       "         -2.85929386e-16, -5.99998118e-15, -1.25070421e-03, -6.90229844e-04,\n",
+       "         -2.70682679e-04,  3.12818816e-17]),\n",
+       "  array([ 1.67455173e+01,  1.18772050e-14,  6.96892979e-04,  3.53598255e-17,\n",
+       "         -2.95471706e-16, -5.97379225e-15, -1.24581031e-03, -6.87033550e-04,\n",
+       "         -2.68976207e-04,  3.42472414e-17]),\n",
+       "  array([ 1.67035702e+01,  1.18330716e-14,  6.93428636e-04,  4.62992676e-17,\n",
+       "         -3.05219355e-16, -5.95096058e-15, -1.24096360e-03, -6.83862428e-04,\n",
+       "         -2.67279720e-04,  3.64691353e-17]),\n",
+       "  array([ 1.66622215e+01,  1.17934127e-14,  6.90012880e-04,  5.74310976e-17,\n",
+       "         -3.15150409e-16, -5.93131655e-15, -1.23616080e-03, -6.80714377e-04,\n",
+       "         -2.65592081e-04,  3.79850244e-17]),\n",
+       "  array([ 1.66214450e+01,  1.17579421e-14,  6.86640978e-04,  6.87325709e-17,\n",
+       "         -3.25245922e-16, -5.91466888e-15, -1.23139815e-03, -6.77586923e-04,\n",
+       "         -2.63911895e-04,  3.88376149e-17]),\n",
+       "  array([ 1.65812140e+01,  1.17263462e-14,  6.83307652e-04,  8.01849846e-17,\n",
+       "         -3.35484661e-16, -5.90080389e-15, -1.22667147e-03, -6.74477241e-04,\n",
+       "         -2.62237528e-04,  3.90749243e-17]),\n",
+       "  array([ 1.65415006e+01,  1.16982821e-14,  6.80007125e-04,  9.17648146e-17,\n",
+       "         -3.45851784e-16, -5.88949129e-15, -1.22197614e-03, -6.71382183e-04,\n",
+       "         -2.60567124e-04,  3.87491728e-17]),\n",
+       "  array([ 1.65022764e+01,  1.16733882e-14,  6.76733163e-04,  1.03460041e-16,\n",
+       "         -3.56323663e-16, -5.88047911e-15, -1.21730718e-03, -6.68298301e-04,\n",
+       "         -2.58898623e-04,  3.79176412e-17]),\n",
+       "  array([ 1.64635122e+01,  1.16512762e-14,  6.73479128e-04,  1.15248596e-16,\n",
+       "         -3.66888040e-16, -5.87350492e-15, -1.21265927e-03, -6.65221878e-04,\n",
+       "         -2.57229781e-04,  3.66402526e-17]),\n",
+       "  array([ 1.64251780e+01,  1.16315435e-14,  6.70238026e-04,  1.27116357e-16,\n",
+       "         -3.77527309e-16, -5.86829034e-15, -1.20802680e-03, -6.62148957e-04,\n",
+       "         -2.55558189e-04,  3.49806048e-17]),\n",
+       "  array([ 1.63872433e+01,  1.16137695e-14,  6.67002565e-04,  1.39044383e-16,\n",
+       "         -3.88230897e-16, -5.86454859e-15, -1.20340385e-03, -6.59075370e-04,\n",
+       "         -2.53881300e-04,  3.30045169e-17]),\n",
+       "  array([ 1.63496765e+01,  1.15975265e-14,  6.63765210e-04,  1.51024624e-16,\n",
+       "         -3.98980616e-16, -5.86198066e-15, -1.19878432e-03, -6.55996775e-04,\n",
+       "         -2.52196446e-04,  3.07806324e-17]),\n",
+       "  array([ 1.63124458e+01,  1.15823740e-14,  6.60518237e-04,  1.63041069e-16,\n",
+       "         -4.09768220e-16, -5.86028472e-15, -1.19416189e-03, -6.52908681e-04,\n",
+       "         -2.50500863e-04,  2.83782887e-17]),\n",
+       "  array([ 1.62755183e+01,  1.15678668e-14,  6.57253790e-04,  1.75079596e-16,\n",
+       "         -4.20586523e-16, -5.85915487e-15, -1.18953011e-03, -6.49806488e-04,\n",
+       "         -2.48791714e-04,  2.58679074e-17]),\n",
+       "  array([ 1.62388608e+01,  1.15535622e-14,  6.53963941e-04,  1.87138516e-16,\n",
+       "         -4.31419721e-16, -5.85827957e-15, -1.18488241e-03, -6.46685513e-04,\n",
+       "         -2.47066112e-04,  2.33211933e-17]),\n",
+       "  array([ 1.62024391e+01,  1.15390135e-14,  6.50640743e-04,  1.99204805e-16,\n",
+       "         -4.42265289e-16, -5.85735245e-15, -1.18021217e-03, -6.43541027e-04,\n",
+       "         -2.45321143e-04,  2.08086993e-17]),\n",
+       "  array([ 1.61662188e+01,  1.15237818e-14,  6.47276286e-04,  2.11274722e-16,\n",
+       "         -4.53114653e-16, -5.85606699e-15, -1.17551273e-03, -6.40368287e-04,\n",
+       "         -2.43553888e-04,  1.84008405e-17]),\n",
+       "  array([ 1.61301646e+01,  1.15074324e-14,  6.43862752e-04,  2.23338086e-16,\n",
+       "         -4.63968248e-16, -5.85412418e-15, -1.17077743e-03, -6.37162564e-04,\n",
+       "         -2.41761445e-04,  1.61663691e-17]),\n",
+       "  array([ 1.60942405e+01,  1.14895445e-14,  6.40392467e-04,  2.35395892e-16,\n",
+       "         -4.74819144e-16, -5.85122921e-15, -1.16599968e-03, -6.33919177e-04,\n",
+       "         -2.39940951e-04,  1.41730114e-17]),\n",
+       "  array([ 1.60584103e+01,  1.14697090e-14,  6.36857945e-04,  2.47446075e-16,\n",
+       "         -4.85666249e-16, -5.84709762e-15, -1.16117295e-03, -6.30633520e-04,\n",
+       "         -2.38089604e-04,  1.24860492e-17]),\n",
+       "  array([ 1.60226370e+01,  1.14475325e-14,  6.33251944e-04,  2.59487599e-16,\n",
+       "         -4.96510227e-16, -5.84145560e-15, -1.15629085e-03, -6.27301090e-04,\n",
+       "         -2.36204679e-04,  1.11681526e-17]),\n",
+       "  array([ 1.59868829e+01,  1.14226400e-14,  6.29567500e-04,  2.71522426e-16,\n",
+       "         -5.07351540e-16, -5.83404182e-15, -1.15134713e-03, -6.23917515e-04,\n",
+       "         -2.34283550e-04,  1.02789913e-17]),\n",
+       "  array([ 1.59511101e+01,  1.13946765e-14,  6.25797972e-04,  2.83552095e-16,\n",
+       "         -5.18193665e-16, -5.82460900e-15, -1.14633570e-03, -6.20478576e-04,\n",
+       "         -2.32323707e-04,  9.87485260e-18]),\n",
+       "  array([ 1.59152800e+01,  1.13633099e-14,  6.21937077e-04,  2.95580961e-16,\n",
+       "         -5.29039833e-16, -5.81292534e-15, -1.14125070e-03, -6.16980231e-04,\n",
+       "         -2.30322769e-04,  1.00082929e-17]),\n",
+       "  array([ 1.58793534e+01,  1.13282316e-14,  6.17978922e-04,  3.07614499e-16,\n",
+       "         -5.39894515e-16, -5.79877578e-15, -1.13608650e-03, -6.13418635e-04,\n",
+       "         -2.28278502e-04,  1.07278295e-17]),\n",
+       "  array([ 1.58432907e+01,  1.12891590e-14,  6.13918033e-04,  3.19658352e-16,\n",
+       "         -5.50764144e-16, -5.78196308e-15, -1.13083771e-03, -6.09790159e-04,\n",
+       "         -2.26188828e-04,  1.20776744e-17]),\n",
+       "  array([ 1.58070519e+01,  1.12458361e-14,  6.09749375e-04,  3.31719762e-16,\n",
+       "         -5.61655557e-16, -5.76230875e-15, -1.12549922e-03, -6.06091404e-04,\n",
+       "         -2.24051843e-04,  1.40975103e-17]),\n",
+       "  array([ 1.57705965e+01,  1.11980345e-14,  6.05468376e-04,  3.43808949e-16,\n",
+       "         -5.72574412e-16, -5.73965373e-15, -1.12006622e-03, -6.02319218e-04,\n",
+       "         -2.21865819e-04,  1.68223106e-17]),\n",
+       "  array([ 1.57338834e+01,  1.11455544e-14,  6.01070937e-04,  3.55933771e-16,\n",
+       "         -5.83530070e-16, -5.71385901e-15, -1.11453417e-03, -5.98470704e-04,\n",
+       "         -2.19629216e-04,  2.02822029e-17]),\n",
+       "  array([ 1.56968711e+01,  1.10882249e-14,  5.96553445e-04,  3.68103352e-16,\n",
+       "         -5.94531855e-16, -5.68480588e-15, -1.10889889e-03, -5.94543230e-04,\n",
+       "         -2.17340689e-04,  2.45023755e-17]),\n",
+       "  array([ 1.56595179e+01,  1.10259039e-14,  5.91912780e-04,  3.80329861e-16,\n",
+       "         -6.05587100e-16, -5.65239624e-15, -1.10315647e-03, -5.90534436e-04,\n",
+       "         -2.14999091e-04,  2.95030289e-17]),\n",
+       "  array([ 1.56217814e+01,  1.09584784e-14,  5.87146311e-04,  3.92624109e-16,\n",
+       "         -6.16705063e-16, -5.61655248e-15, -1.09730337e-03, -5.86442239e-04,\n",
+       "         -2.12603476e-04,  3.52993685e-17]),\n",
+       "  array([ 1.55836190e+01,  1.08858639e-14,  5.82251897e-04,  4.04996391e-16,\n",
+       "         -6.27895801e-16, -5.57721737e-15, -1.09133634e-03, -5.82264831e-04,\n",
+       "         -2.10153101e-04,  4.19016395e-17]),\n",
+       "  array([ 1.55449877e+01,  1.08080039e-14,  5.77227882e-04,  4.17456816e-16,\n",
+       "         -6.39169639e-16, -5.53435373e-15, -1.08525249e-03, -5.78000684e-04,\n",
+       "         -2.07647425e-04,  4.93152008e-17]),\n",
+       "  array([ 1.55058439e+01,  1.07248693e-14,  5.72073079e-04,  4.30018421e-16,\n",
+       "         -6.50533886e-16, -5.48794390e-15, -1.07904923e-03, -5.73648541e-04,\n",
+       "         -2.05086108e-04,  5.75406385e-17]),\n",
+       "  array([ 1.54661440e+01,  1.06364571e-14,  5.66786759e-04,  4.42690634e-16,\n",
+       "         -6.61998853e-16, -5.43798911e-15, -1.07272429e-03, -5.69207417e-04,\n",
+       "         -2.02469006e-04,  6.65739130e-17]),\n",
+       "  array([ 1.54258439e+01,  1.05427892e-14,  5.61368633e-04,  4.55485788e-16,\n",
+       "         -6.73571239e-16, -5.38450872e-15, -1.06627571e-03, -5.64676589e-04,\n",
+       "         -1.99796169e-04,  7.64065406e-17]),\n",
+       "  array([ 1.53848990e+01,  1.04439113e-14,  5.55818831e-04,  4.68409504e-16,\n",
+       "         -6.85263247e-16, -5.32753926e-15, -1.05970184e-03, -5.60055589e-04,\n",
+       "         -1.97067832e-04,  8.70258045e-17]),\n",
+       "  array([ 1.53432648e+01,  1.03398913e-14,  5.50137879e-04,  4.81476982e-16,\n",
+       "         -6.97076557e-16, -5.26713350e-15, -1.05300130e-03, -5.55344194e-04,\n",
+       "         -1.94284410e-04,  9.84149931e-17]),\n",
+       "  array([ 1.53008962e+01,  1.02308174e-14,  5.44326672e-04,  4.94693734e-16,\n",
+       "         -7.09020656e-16, -5.20335925e-15, -1.04617299e-03, -5.50542412e-04,\n",
+       "         -1.91446488e-04,  1.10553663e-16]),\n",
+       "  array([ 1.52577479e+01,  1.01167968e-14,  5.38386449e-04,  5.08066317e-16,\n",
+       "         -7.21102238e-16, -5.13629824e-15, -1.03921605e-03, -5.45650472e-04,\n",
+       "         -1.88554815e-04,  1.23417919e-16]),\n",
+       "  array([ 1.52137744e+01,  9.99795331e-15,  5.32318764e-04,  5.21601798e-16,\n",
+       "         -7.33325644e-16, -5.06604481e-15, -1.03212988e-03, -5.40668811e-04,\n",
+       "         -1.85610290e-04,  1.36980718e-16]),\n",
+       "  array([ 1.51689299e+01,  9.87442594e-15,  5.26125451e-04,  5.35309264e-16,\n",
+       "         -7.45691121e-16, -4.99270462e-15, -1.02491409e-03, -5.35598055e-04,\n",
+       "         -1.82613954e-04,  1.51212176e-16]),\n",
+       "  array([ 1.51231684e+01,  9.74636659e-15,  5.19808600e-04,  5.49186352e-16,\n",
+       "         -7.58207704e-16, -4.91639328e-15, -1.01756849e-03, -5.30439007e-04,\n",
+       "         -1.79566979e-04,  1.66079894e-16]),\n",
+       "  array([ 1.50764437e+01,  9.61393828e-15,  5.13370521e-04,  5.63240182e-16,\n",
+       "         -7.70872912e-16, -4.83723500e-15, -1.01009308e-03, -5.25192631e-04,\n",
+       "         -1.76470654e-04,  1.81549286e-16]),\n",
+       "  array([ 1.50287094e+01,  9.47731308e-15,  5.06813712e-04,  5.77476635e-16,\n",
+       "         -7.83682889e-16, -4.75536122e-15, -1.00248801e-03, -5.19860033e-04,\n",
+       "         -1.73326377e-04,  1.97583908e-16]),\n",
+       "  array([ 1.49799190e+01,  9.33667021e-15,  5.00140831e-04,  5.91885741e-16,\n",
+       "         -7.96646411e-16, -4.67090919e-15, -9.94753593e-04, -5.14442447e-04,\n",
+       "         -1.70135640e-04,  2.14145787e-16]),\n",
+       "  array([ 1.49300258e+01,  9.19219410e-15,  4.93354663e-04,  6.06481770e-16,\n",
+       "         -8.09745942e-16, -4.58402069e-15, -9.86890244e-04, -5.08941219e-04,\n",
+       "         -1.66900019e-04,  2.31195750e-16]),\n",
+       "  array([ 1.48789830e+01,  9.04407257e-15,  4.86458091e-04,  6.21252779e-16,\n",
+       "         -8.22986199e-16, -4.49484064e-15, -9.78898496e-04, -5.03357789e-04,\n",
+       "         -1.63621159e-04,  2.48693740e-16]),\n",
+       "  array([ 1.48267436e+01,  8.89249501e-15,  4.79454068e-04,  6.36195696e-16,\n",
+       "         -8.36360115e-16, -4.40351589e-15, -9.70778962e-04, -4.97693675e-04,\n",
+       "         -1.60300769e-04,  2.66599123e-16]),\n",
+       "  array([ 1.47732606e+01,  8.73765078e-15,  4.72345588e-04,  6.51305211e-16,\n",
+       "         -8.49859746e-16, -4.31019401e-15, -9.62532327e-04, -4.91950460e-04,\n",
+       "         -1.56940605e-04,  2.84870985e-16]),\n",
+       "  array([ 1.47184870e+01,  8.57972753e-15,  4.65135663e-04,  6.66579451e-16,\n",
+       "         -8.63470506e-16, -4.21502208e-15, -9.54159321e-04, -4.86129776e-04,\n",
+       "         -1.53542460e-04,  3.03468409e-16]),\n",
+       "  array([ 1.46623755e+01,  8.41890982e-15,  4.57827297e-04,  6.82011799e-16,\n",
+       "         -8.77178659e-16, -4.11814571e-15, -9.45660715e-04, -4.80233291e-04,\n",
+       "         -1.50108157e-04,  3.22350743e-16]),\n",
+       "  array([ 1.46048791e+01,  8.25537777e-15,  4.50423467e-04,  6.97566156e-16,\n",
+       "         -8.90995701e-16, -4.01970799e-15, -9.37037294e-04, -4.74262695e-04,\n",
+       "         -1.46639538e-04,  3.41477834e-16]),\n",
+       "  array([ 1.45459506e+01,  8.08930582e-15,  4.42927104e-04,  7.13249129e-16,\n",
+       "         -9.04889083e-16, -3.91984862e-15, -9.28289856e-04, -4.68219690e-04,\n",
+       "         -1.43138452e-04,  3.60810259e-16]),\n",
+       "  array([ 1.44855428e+01,  7.92085126e-15,  4.35340838e-04,  7.29026627e-16,\n",
+       "         -9.18863372e-16, -3.81870452e-15, -9.19419214e-04, -4.62106013e-04,\n",
+       "         -1.39606779e-04,  3.80308946e-16]),\n",
+       "  array([ 1.44236087e+01,  7.75020038e-15,  4.27668032e-04,  7.44903516e-16,\n",
+       "         -9.32882814e-16, -3.71640096e-15, -9.10426051e-04, -4.55923258e-04,\n",
+       "         -1.36046299e-04,  3.99938178e-16]),\n",
+       "  array([ 1.43601013e+01,  7.57748762e-15,  4.19911013e-04,  7.60860614e-16,\n",
+       "         -9.46932664e-16, -3.61306845e-15, -9.01311201e-04, -4.49673174e-04,\n",
+       "         -1.32458888e-04,  4.19660658e-16]),\n",
+       "  array([ 1.42949735e+01,  7.40285654e-15,  4.12072388e-04,  7.76878127e-16,\n",
+       "         -9.60995346e-16, -3.50882520e-15, -8.92075368e-04, -4.43357410e-04,\n",
+       "         -1.28846369e-04,  4.39441586e-16]),\n",
+       "  array([ 1.42281787e+01,  7.22644091e-15,  4.04154652e-04,  7.92935272e-16,\n",
+       "         -9.75051427e-16, -3.40378345e-15, -8.82719224e-04, -4.36977585e-04,\n",
+       "         -1.25210538e-04,  4.59247780e-16]),\n",
+       "  array([ 1.41596701e+01,  7.04836456e-15,  3.96160184e-04,  8.09010121e-16,\n",
+       "         -9.89079951e-16, -3.29804893e-15, -8.73243402e-04, -4.30535285e-04,\n",
+       "         -1.21553167e-04,  4.79047646e-16]),\n",
+       "  array([ 1.40894013e+01,  6.86874127e-15,  3.88091250e-04,  8.25079543e-16,\n",
+       "         -1.00305866e-15, -3.19172056e-15, -8.63648492e-04, -4.24032058e-04,\n",
+       "         -1.17875995e-04,  4.98811214e-16]),\n",
+       "  array([ 1.40173260e+01,  6.68767475e-15,  3.79949996e-04,  8.41119212e-16,\n",
+       "         -1.01696412e-15, -3.08489030e-15, -8.53935036e-04, -4.17469413e-04,\n",
+       "         -1.14180736e-04,  5.18510180e-16]),\n",
+       "  array([ 1.39433982e+01,  6.50525876e-15,  3.71738458e-04,  8.57103646e-16,\n",
+       "         -1.03077187e-15, -2.97764306e-15, -8.44103535e-04, -4.10848821e-04,\n",
+       "         -1.10469069e-04,  5.38117920e-16]),\n",
+       "  array([ 1.38675721e+01,  6.32157732e-15,  3.63458560e-04,  8.73006262e-16,\n",
+       "         -1.04445647e-15, -2.87005679e-15, -8.34154442e-04, -4.04171711e-04,\n",
+       "         -1.06742645e-04,  5.57609495e-16]),\n",
+       "  array([ 1.37898021e+01,  6.13670506e-15,  3.55112120e-04,  8.88799450e-16,\n",
+       "         -1.05799162e-15, -2.76220262e-15, -8.24088173e-04, -3.97439477e-04,\n",
+       "         -1.03003082e-04,  5.76961627e-16]),\n",
+       "  array([ 1.37100431e+01,  5.95070756e-15,  3.46700862e-04,  9.04454641e-16,\n",
+       "         -1.07135021e-15, -2.65414504e-15, -8.13905106e-04, -3.90653476e-04,\n",
+       "         -9.92519693e-05,  5.96152657e-16]),\n",
+       "  array([ 1.36282504e+01,  5.76364198e-15,  3.38226420e-04,  9.19942389e-16,\n",
+       "         -1.08450443e-15, -2.54594224e-15, -8.03605590e-04, -3.83815034e-04,\n",
+       "         -9.54908678e-05,  6.15162490e-16]),\n",
+       "  array([ 1.35443794e+01,  5.57555755e-15,  3.29690352e-04,  9.35232457e-16,\n",
+       "         -1.09742583e-15, -2.43764643e-15, -7.93189952e-04, -3.76925451e-04,\n",
+       "         -9.17213142e-05,  6.33972518e-16]),\n",
+       "  array([ 1.34583861e+01,  5.38649633e-15,  3.21094150e-04,  9.50293891e-16,\n",
+       "         -1.11008538e-15, -2.32930423e-15, -7.82658500e-04, -3.69986004e-04,\n",
+       "         -8.79448230e-05,  6.52565536e-16]),\n",
+       "  array([ 1.33702271e+01,  5.19649390e-15,  3.12439253e-04,  9.65095108e-16,\n",
+       "         -1.12245361e-15, -2.22095718e-15, -7.72011539e-04, -3.62997956e-04,\n",
+       "         -8.41628907e-05,  6.70925641e-16]),\n",
+       "  array([ 1.32798592e+01,  5.00558016e-15,  3.03727058e-04,  9.79603984e-16,\n",
+       "         -1.13450058e-15, -2.11264217e-15, -7.61249376e-04, -3.55962560e-04,\n",
+       "         -8.03770002e-05,  6.89038122e-16]),\n",
+       "  array([ 1.31872400e+01,  4.81378021e-15,  2.94958942e-04,  9.93787929e-16,\n",
+       "         -1.14619608e-15, -2.00439201e-15, -7.50372330e-04, -3.48881070e-04,\n",
+       "         -7.65886249e-05,  7.06889344e-16]),\n",
+       "  array([ 1.30923274e+01,  4.62111515e-15,  2.86136267e-04,  1.00761398e-15,\n",
+       "         -1.15750958e-15, -1.89623598e-15, -7.39380745e-04, -3.41754746e-04,\n",
+       "         -7.27992341e-05,  7.24466621e-16]),\n",
+       "  array([ 1.29950802e+01,  4.42760305e-15,  2.77260405e-04,  1.02104888e-15,\n",
+       "         -1.16841041e-15, -1.78820040e-15, -7.28275002e-04, -3.34584861e-04,\n",
+       "         -6.90102982e-05,  7.41758087e-16]),\n",
+       "  array([ 1.28954577e+01,  4.23325988e-15,  2.68332746e-04,  1.03405917e-15,\n",
+       "         -1.17886777e-15, -1.68030924e-15, -7.17055526e-04, -3.27372714e-04,\n",
+       "         -6.52232943e-05,  7.58752560e-16]),\n",
+       "  array([ 1.27934197e+01,  4.03810040e-15,  2.59354721e-04,  1.04661126e-15,\n",
+       "         -1.18885081e-15, -1.57258472e-15, -7.05722806e-04, -3.20119638e-04,\n",
+       "         -6.14397118e-05,  7.75439406e-16]),\n",
+       "  array([ 1.26889271e+01,  3.84213912e-15,  2.50327812e-04,  1.05867152e-15,\n",
+       "         -1.19832873e-15, -1.46504793e-15, -6.94277399e-04, -3.12827006e-04,\n",
+       "         -5.76610583e-05,  7.91808400e-16]),\n",
+       "  array([ 1.25819413e+01,  3.64539127e-15,  2.41253575e-04,  1.07020639e-15,\n",
+       "         -1.20727084e-15, -1.35771942e-15, -6.82719949e-04, -3.05496241e-04,\n",
+       "         -5.38888654e-05,  8.07849586e-16]),\n",
+       "  array([ 1.24724246e+01,  3.44787371e-15,  2.32133649e-04,  1.08118243e-15,\n",
+       "         -1.21564660e-15, -1.25061983e-15, -6.71051195e-04, -2.98128830e-04,\n",
+       "         -5.01246950e-05,  8.23553142e-16]),\n",
+       "  array([ 1.23603403e+01,  3.24960586e-15,  2.22969780e-04,  1.09156644e-15,\n",
+       "         -1.22342572e-15, -1.14377049e-15, -6.59271989e-04, -2.90726327e-04,\n",
+       "         -4.63701448e-05,  8.38909250e-16]),\n",
+       "  array([ 1.22456523e+01,  3.05061092e-15,  2.13763830e-04,  1.10132529e-15,\n",
+       "         -1.23057850e-15, -1.03719371e-15, -6.47383302e-04, -2.83290366e-04,\n",
+       "         -4.26268544e-05,  8.53907995e-16]),\n",
+       "  array([ 1.21283258e+01,  2.85091575e-15,  2.04517798e-04,  1.11042689e-15,\n",
+       "         -1.23707505e-15, -9.30914281e-16, -6.35386241e-04, -2.75822668e-04,\n",
+       "         -3.88965113e-05,  8.68539080e-16]),\n",
+       "  array([ 1.20083267e+01,  2.65055297e-15,  1.95233832e-04,  1.11883932e-15,\n",
+       "         -1.24288630e-15, -8.24958918e-16, -6.23282060e-04, -2.68325055e-04,\n",
+       "         -3.51808562e-05,  8.82791915e-16]),\n",
+       "  array([ 1.18856222e+01,  2.44956174e-15,  1.85914248e-04,  1.12653046e-15,\n",
+       "         -1.24798447e-15, -7.19356905e-16, -6.11072174e-04, -2.60799450e-04,\n",
+       "         -3.14816888e-05,  8.96655483e-16]),\n",
+       "  array([ 1.17601805e+01,  2.24798731e-15,  1.76561542e-04,  1.13347022e-15,\n",
+       "         -1.25234131e-15, -6.14141666e-16, -5.98758167e-04, -2.53247895e-04,\n",
+       "         -2.78008733e-05,  9.10118003e-16]),\n",
+       "  array([ 1.16319710e+01,  2.04588285e-15,  1.67178406e-04,  1.13962925e-15,\n",
+       "         -1.25592941e-15, -5.09350362e-16, -5.86341807e-04, -2.45672552e-04,\n",
+       "         -2.41403431e-05,  9.23166999e-16]),\n",
+       "  array([ 1.15009642e+01,  1.84331069e-15,  1.57767742e-04,  1.14497771e-15,\n",
+       "         -1.25872358e-15, -4.05023975e-16, -5.73825057e-04, -2.38075715e-04,\n",
+       "         -2.05021065e-05,  9.35789282e-16]),\n",
+       "  array([ 1.13671321e+01,  1.64034171e-15,  1.48332678e-04,  1.14948850e-15,\n",
+       "         -1.26069812e-15, -3.01208906e-16, -5.61210084e-04, -2.30459820e-04,\n",
+       "         -1.68882509e-05,  9.47970639e-16]),\n",
+       "  array([ 1.12304477e+01,  1.43705689e-15,  1.38876581e-04,  1.15313576e-15,\n",
+       "         -1.26182842e-15, -1.97956684e-16, -5.48499274e-04, -2.22827445e-04,\n",
+       "         -1.33009477e-05,  9.59695855e-16]),\n",
+       "  array([ 1.10908858e+01,  1.23354814e-15,  1.29403068e-04,  1.15589427e-15,\n",
+       "         -1.26209167e-15, -9.53242211e-17, -5.35695240e-04, -2.15181326e-04,\n",
+       "         -9.74245679e-06,  9.70948703e-16]),\n",
+       "  array([ 1.09484222e+01,  1.02991924e-15,  1.19916027e-04,  1.15773861e-15,\n",
+       "         -1.26146811e-15,  6.62606795e-18, -5.22800831e-04, -2.07524359e-04,\n",
+       "         -6.21513033e-06,  9.81711882e-16]),\n",
+       "  array([ 1.08030345e+01,  8.26284612e-16,  1.10419621e-04,  1.15864990e-15,\n",
+       "         -1.25993503e-15,  1.07824329e-16, -5.09819147e-04, -1.99859609e-04,\n",
+       "         -2.72141707e-06,  9.91966689e-16]),\n",
+       "  array([ 1.06547019e+01,  6.22772751e-16,  1.00918311e-04,  1.15860593e-15,\n",
+       "         -1.25747630e-15,  2.08195473e-16, -4.96753544e-04, -1.92190314e-04,\n",
+       "          7.36133956e-07,  1.00169335e-15]),\n",
+       "  array([ 1.05034050e+01,  4.19524317e-16,  9.14168604e-05,  1.15759087e-15,\n",
+       "         -1.25407368e-15,  3.07656659e-16, -4.83607648e-04, -1.84519896e-04,\n",
+       "          4.15486977e-06,  1.01087065e-15]),\n",
+       "  array([ 1.03491262e+01,  2.16694225e-16,  8.19203563e-05,  1.15558955e-15,\n",
+       "         -1.24971244e-15,  4.06118427e-16, -4.70385362e-04, -1.76851964e-04,\n",
+       "          7.53202994e-06,  1.01947608e-15]),\n",
+       "  array([ 1.01918497e+01,  1.44518092e-17,  7.24342176e-05,  1.15258911e-15,\n",
+       "         -1.24438015e-15,  5.03484125e-16, -4.57090877e-04, -1.69190319e-04,\n",
+       "          1.08647432e-05,  1.02748581e-15]),\n",
+       "  array([ 1.00315616e+01, -1.87018728e-16,  6.29642105e-05,  1.14857956e-15,\n",
+       "         -1.23806663e-15,  5.99649696e-16, -4.43728681e-04, -1.61538965e-04,\n",
+       "          1.41500239e-05,  1.03487460e-15]),\n",
+       "  array([ 9.86824965e+00, -3.87517591e-16,  5.35164622e-05,  1.14355285e-15,\n",
+       "         -1.23076544e-15,  6.94503790e-16, -4.30303569e-04, -1.53902112e-04,\n",
+       "          1.73847690e-05,  1.04161588e-15]),\n",
+       "  array([ 9.70190383e+00, -5.86829817e-16,  4.40974743e-05,  1.13750801e-15,\n",
+       "         -1.22246951e-15,  7.87926868e-16, -4.16820654e-04, -1.46284181e-04,\n",
+       "          2.05657544e-05,  1.04768158e-15]),\n",
+       "  array([ 9.53251601e+00, -7.84723451e-16,  3.47141372e-05,  1.13044407e-15,\n",
+       "         -1.21317831e-15,  8.79792362e-16, -4.03285376e-04, -1.38689815e-04,\n",
+       "          2.36896318e-05,  1.05304230e-15]),\n",
+       "  array([ 9.36008023e+00, -9.80950174e-16,  2.53737445e-05,  1.12236621e-15,\n",
+       "         -1.20289256e-15,  9.69965684e-16, -3.89703510e-04, -1.31123879e-04,\n",
+       "          2.67529249e-05,  1.05766727e-15]),\n",
+       "  array([ 9.18459269e+00, -1.17524502e-15,  1.60840085e-05,  1.11328717e-15,\n",
+       "         -1.19161311e-15,  1.05830411e-15, -3.76081181e-04, -1.23591473e-04,\n",
+       "          2.97520257e-05,  1.06152426e-15]),\n",
+       "  array([ 9.00605187e+00, -1.36732403e-15,  6.85307589e-06,  1.10321498e-15,\n",
+       "         -1.17935296e-15,  1.14465852e-15, -3.62424872e-04, -1.16097936e-04,\n",
+       "          3.26831909e-05,  1.06457997e-15]),\n",
+       "  array([ 8.82445859e+00, -1.55688624e-15, -2.31045546e-06,  1.09216768e-15,\n",
+       "         -1.16612422e-15,  1.22887147e-15, -3.48741435e-04, -1.08648853e-04,\n",
+       "          3.55425376e-05,  1.06679975e-15]),\n",
+       "  array([ 8.63981608e+00, -1.74361327e-15, -1.13975179e-05,  1.08017465e-15,\n",
+       "         -1.15193744e-15,  1.31077738e-15, -3.35038107e-04, -1.01250063e-04,\n",
+       "          3.83260390e-05,  1.06814756e-15]),\n",
+       "  array([ 8.45213011e+00, -1.92716724e-15, -2.03985535e-05,  1.06726408e-15,\n",
+       "         -1.13681311e-15,  1.39020410e-15, -3.21322517e-04, -9.39076693e-05,\n",
+       "          4.10295207e-05,  1.06858630e-15]),\n",
+       "  array([ 8.26140899e+00, -2.10719076e-15, -2.93034917e-05,  1.05346474e-15,\n",
+       "         -1.12078031e-15,  1.46697281e-15, -3.07602701e-04, -8.66280429e-05,\n",
+       "          4.36486560e-05,  1.06807795e-15]),\n",
+       "  array([ 8.06766372e+00, -2.28330854e-15, -3.81017214e-05,  1.03882105e-15,\n",
+       "         -1.10386340e-15,  1.54089653e-15, -2.93887116e-04, -7.94178330e-05,\n",
+       "          4.61789633e-05,  1.06658330e-15]),\n",
+       "  array([ 7.87090807e+00, -2.45512509e-15, -4.67820595e-05,  1.02337856e-15,\n",
+       "         -1.08609544e-15,  1.61178204e-15, -2.80184651e-04, -7.22839716e-05,\n",
+       "          4.86158030e-05,  1.06406223e-15]),\n",
+       "  array([ 7.67115862e+00, -2.62222491e-15, -5.53327113e-05,  1.00718882e-15,\n",
+       "         -1.06751336e-15,  1.67942950e-15, -2.66504638e-04, -6.52336780e-05,\n",
+       "          5.09543784e-05,  1.06047383e-15]),\n",
+       "  array([ 7.46843490e+00, -2.78417194e-15, -6.37412200e-05,  9.90308698e-16,\n",
+       "         -1.04815814e-15,  1.74363266e-15, -2.52856862e-04, -5.82744591e-05,\n",
+       "          5.31897384e-05,  1.05577646e-15]),\n",
+       "  array([ 7.26275946e+00, -2.94050885e-15, -7.19944036e-05,  9.72799886e-16,\n",
+       "         -1.02807462e-15,  1.80417911e-15, -2.39251567e-04, -5.14141033e-05,\n",
+       "          5.53167866e-05,  1.04992792e-15]),\n",
+       "  array([ 7.05415796e+00, -3.09075607e-15, -8.00782702e-05,  9.54728101e-16,\n",
+       "         -1.00731109e-15,  1.86085052e-15, -2.25699453e-04, -4.46606660e-05,\n",
+       "          5.73302993e-05,  1.04288561e-15]),\n",
+       "  array([ 6.84265927e+00, -3.23441051e-15, -8.79779073e-05,  9.36161909e-16,\n",
+       "         -9.85918740e-16,  1.91342284e-15, -2.12211667e-04, -3.80224406e-05,\n",
+       "          5.92249555e-05,  1.03460674e-15]),\n",
+       "  array([ 6.62829555e+00, -3.37094379e-15, -9.56773326e-05,  9.17171112e-16,\n",
+       "         -9.63951001e-16,  1.96166651e-15, -1.98799778e-04, -3.15079083e-05,\n",
+       "          6.09953860e-05,  1.02504859e-15]),\n",
+       "  array([ 6.41110236e+00, -3.49979980e-15, -1.03159293e-04,  8.97824497e-16,\n",
+       "         -9.41462565e-16,  2.00534662e-15, -1.85475726e-04, -2.51256580e-05,\n",
+       "          6.26362503e-05,  1.01416894e-15]),\n",
+       "  array([ 6.19111875e+00, -3.62039128e-15, -1.10404991e-04,  8.78186839e-16,\n",
+       "         -9.18508233e-16,  2.04422307e-15, -1.72251742e-04, -1.88842606e-05,\n",
+       "          6.41423531e-05,  1.00192650e-15]),\n",
+       "  array([ 5.96838735e+00, -3.73209524e-15, -1.17393710e-04,  8.58314859e-16,\n",
+       "         -8.95141492e-16,  2.07805075e-15, -1.59140217e-04, -1.27920808e-05,\n",
+       "          6.55088173e-05,  9.88281645e-16]),\n",
+       "  array([ 5.74295448e+00, -3.83424655e-15, -1.24102302e-04,  8.38251890e-16,\n",
+       "         -8.71412768e-16,  2.10657958e-15, -1.46153501e-04, -6.85699587e-06,\n",
+       "          6.67313389e-05,  9.73197339e-16]),\n",
+       "  array([ 5.51487026e+00, -3.92612932e-15, -1.30504482e-04,  8.18020796e-16,\n",
+       "         -8.47367354e-16,  2.12955450e-15, -1.33303605e-04, -1.08598459e-06,\n",
+       "          6.78065566e-05,  9.56640356e-16]),\n",
+       "  array([ 5.28418868e+00, -4.00696520e-15, -1.36569848e-04,  7.97614645e-16,\n",
+       "         -8.23042906e-16,  2.14671523e-15, -1.20601755e-04,  4.51546984e-06,\n",
+       "          6.87325867e-05,  9.38582955e-16]),\n",
+       "  array([ 5.05096770e+00, -4.07589762e-15, -1.42262527e-04,  7.76984359e-16,\n",
+       "         -7.98466466e-16,  2.15779563e-15, -1.08057744e-04,  9.94424094e-06,\n",
+       "          6.95097900e-05,  9.19005032e-16]),\n",
+       "  array([ 4.81526938e+00, -4.13197060e-15, -1.47539286e-04,  7.56022424e-16,\n",
+       "         -7.73650837e-16,  2.16252210e-15, -9.56789892e-05,  1.52007947e-05,\n",
+       "          7.01418692e-05,  8.97896822e-16]),\n",
+       "  array([ 4.57715995e+00, -4.17410052e-15, -1.52346896e-04,  7.34541353e-16,\n",
+       "         -7.48590145e-16,  2.16061036e-15, -8.34691825e-05,  2.02909572e-05,\n",
+       "          7.06374348e-05,  8.75262162e-16]),\n",
+       "  array([ 4.33670994e+00, -4.20103868e-15, -1.56618434e-04,  7.12245265e-16,\n",
+       "         -7.23254249e-16,  2.15175906e-15, -7.14263451e-05,  2.52284361e-05,\n",
+       "          7.10122357e-05,  8.51122125e-16]),\n",
+       "  array([ 4.09399425e+00, -4.21132198e-15, -1.60268087e-04,  6.88692498e-16,\n",
+       "         -6.97581515e-16,  2.13563773e-15, -5.95400512e-05,  3.00384141e-05,\n",
+       "          7.12923320e-05,  8.25518550e-16]),\n",
+       "  array([ 3.84909224e+00, -4.20320850e-15, -1.63183830e-04,  6.63246701e-16,\n",
+       "         -6.71469164e-16,  2.11186482e-15, -4.77874630e-05,  3.47626611e-05,\n",
+       "          7.15186048e-05,  7.98516356e-16]),\n",
+       "  array([ 3.60208790e+00, -4.17459429e-15, -1.65217080e-04,  6.35013533e-16,\n",
+       "         -6.44759944e-16,  2.07996913e-15, -3.61276760e-05,  3.94668040e-05,\n",
+       "          7.17531570e-05,  7.70202405e-16]),\n",
+       "  array([ 3.35306987e+00, -4.12290705e-15, -1.66168066e-04,  6.02760076e-16,\n",
+       "         -6.17222923e-16,  2.03932373e-15, -2.44936466e-05,  4.42506548e-05,\n",
+       "          7.20883804e-05,  7.40676502e-16]),\n",
+       "  array([ 3.10213162e+00, -4.04497170e-15, -1.65765085e-04,  5.64815134e-16,\n",
+       "         -5.88524279e-16,  1.98903716e-15, -1.27806266e-05,  4.92628697e-05,\n",
+       "          7.26597299e-05,  7.10025759e-16]),\n",
+       "  array([ 2.84937149e+00, -3.93684043e-15, -1.63635057e-04,  5.18951907e-16,\n",
+       "         -5.58179420e-16,  1.92778165e-15, -8.29397093e-07,  5.47217181e-05,\n",
+       "          7.36634863e-05,  6.78263878e-16]),\n",
+       "  array([ 2.59489286e+00, -3.79357360e-15, -1.59261589e-04,  4.62263347e-16,\n",
+       "         -5.25466477e-16,  1.85353938e-15,  1.15987696e-05,  6.09443994e-05,\n",
+       "          7.53806018e-05,  6.45193255e-16]),\n",
+       "  array([ 2.33880424e+00, -3.60893628e-15, -1.51924727e-04,  3.91061030e-16,\n",
+       "         -4.89252601e-16,  1.76326803e-15,  2.48621829e-05,  6.83880682e-05,\n",
+       "          7.82055520e-05,  6.10085765e-16]),\n",
+       "  array([ 2.08121940e+00, -3.37491420e-15, -1.40612595e-04,  3.00878307e-16,\n",
+       "         -4.47607214e-16,  1.65256381e-15,  3.95122943e-05,  7.77060182e-05,\n",
+       "          8.26690981e-05,  5.70911012e-16]),\n",
+       "  array([ 1.82225748e+00, -3.08078125e-15, -1.23884834e-04,  1.86776559e-16,\n",
+       "         -3.96865931e-16,  1.51561453e-15,  5.64594636e-05,  8.98201873e-05,\n",
+       "          8.94043159e-05,  5.22399943e-16]),\n",
+       "  array([ 1.56204313e+00, -2.71098445e-15, -9.96366025e-05,  4.44576549e-17,\n",
+       "         -3.29199412e-16,  1.34622204e-15,  7.74339700e-05,  1.05997569e-04,\n",
+       "          9.88569572e-05,  4.51152517e-16]),\n",
+       "  array([ 1.30070665e+00, -2.23986866e-15, -6.46052190e-05, -1.26493664e-16,\n",
+       "         -2.25906931e-16,  1.14145832e-15,  1.06473637e-04,  1.27853631e-04,\n",
+       "          1.09998533e-04,  3.23791818e-16]),\n",
+       "  array([ 1.03838415e+00, -1.61795771e-15, -1.30755268e-05, -3.13540604e-16,\n",
+       "         -3.78536677e-17,  9.09259840e-16,  1.55153805e-04,  1.56855941e-04,\n",
+       "          1.15373566e-04,  6.18545254e-17]),\n",
+       "  array([ 7.75217670e-01, -7.35405379e-16,  6.72253889e-05, -4.65694376e-16,\n",
+       "          3.74459430e-16,  6.70714734e-16,  2.62210693e-04,  1.90324402e-04,\n",
+       "          8.35496516e-05, -4.92439235e-16]),\n",
+       "  array([ 5.11355434e-01,  6.82544073e-16,  2.10097197e-04, -4.24062451e-16,\n",
+       "          1.43135020e-15,  3.80075570e-16,  5.75450582e-04,  1.85903667e-04,\n",
+       "         -9.33411046e-05, -1.51716943e-15]),\n",
+       "  array([ 2.46952099e-01,  3.46120206e-15,  5.34592006e-04,  2.17445316e-16,\n",
+       "          4.45149018e-15, -6.48985623e-16,  1.77986973e-03, -3.13205057e-04,\n",
+       "         -6.45045565e-04, -2.45251105e-15])],\n",
+       " True)"
+      ]
+     },
+     "execution_count": 116,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "# DEFINING THE SHOOTING PROBLEM & SOLVING\n",
+    "\n",
+    "# Defining the time duration for running action models and the terminal one\n",
+    "dt = 1e-3\n",
+    "runningModel.timeStep = dt\n",
+    "\n",
+    "# For this optimal control problem, we define 250 knots (or running action\n",
+    "# models) plus a terminal knot\n",
+    "T = 500\n",
+    "q0 = robot.model.referenceConfigurations[\"initial_pose\"]\n",
+    "\n",
+    "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n",
+    "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)\n",
+    "\n",
+    "# Creating the DDP solver for this OC problem, defining a logger\n",
+    "ddp = SolverDDP(problem)\n",
+    "ddp.callback = [CallbackDDPVerbose()]\n",
+    "ddp.callback.append(CallbackDDPLogger())\n",
+    "\n",
+    "# Solving it with the DDP algorithm\n",
+    "ddp.solve()"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 118,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "displayTrajectory(robot, ddp.xs, runningModel.timeStep)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 119,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "thrust = []\n",
+    "Mr = [];\n",
+    "Mp = [];\n",
+    "My = [];\n",
+    "for u in ddp.us:\n",
+    "    thrust.append(u[0])\n",
+    "    Mr.append(u[1])\n",
+    "    Mp.append(u[2])\n",
+    "    My.append(u[3])"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 120,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/plain": [
+       "<matplotlib.legend.Legend at 0x7f2de8cf6050>"
+      ]
+     },
+     "execution_count": 120,
+     "metadata": {},
+     "output_type": "execute_result"
+    },
+    {
+     "data": {
+      "image/png": "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\n",
+      "text/plain": [
+       "<matplotlib.figure.Figure at 0x7f2deb729d90>"
+      ]
+     },
+     "metadata": {
+      "needs_background": "light"
+     },
+     "output_type": "display_data"
+    },
+    {
+     "data": {
+      "image/png": "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\n",
+      "text/plain": [
+       "<matplotlib.figure.Figure at 0x7f2df03da850>"
+      ]
+     },
+     "metadata": {
+      "needs_background": "light"
+     },
+     "output_type": "display_data"
+    }
+   ],
+   "source": [
+    "import matplotlib.pyplot as plt\n",
+    "t = np.arange(0., T*dt, dt)\n",
+    "\n",
+    "plt.figure()\n",
+    "plt.plot(t, thrust)\n",
+    "plt.ylabel('Thrust, [N]')\n",
+    "\n",
+    "plt.figure()\n",
+    "plt.plot(t,Mr, t,Mp, t,My)\n",
+    "plt.legend(['Mr','Mp','My'])"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 92,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "robot.display(q0)"
+   ]
+  }
+ ],
+ "metadata": {
+  "kernelspec": {
+   "display_name": "Python 2",
+   "language": "python",
+   "name": "python2"
+  },
+  "language_info": {
+   "codemirror_mode": {
+    "name": "ipython",
+    "version": 2
+   },
+   "file_extension": ".py",
+   "mimetype": "text/x-python",
+   "name": "python",
+   "nbconvert_exporter": "python",
+   "pygments_lexer": "ipython2",
+   "version": "2.7.12"
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}