diff --git a/crocoddyl/__init__.py b/crocoddyl/__init__.py index 7483b5aaa5c3760bc8a71e8892d68b8b334cb12b..068c48fb9b1ba2cef5abe456412e9fd75f453f2c 100644 --- a/crocoddyl/__init__.py +++ b/crocoddyl/__init__.py @@ -29,7 +29,7 @@ from .impact import (ActionDataImpact, ActionModelImpact, CostModelImpactCoM, Co from .integrated_action import (IntegratedActionDataEuler, IntegratedActionDataRK4, IntegratedActionModelEuler, IntegratedActionModelRK4) from .kkt import SolverKKT -from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs, loadKinton, loadKintonArm +from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs, loadKinton, loadKintonArm, loadBorinotArm from .shooting import ShootingProblem from .solver import SolverAbstract from .state import StateAbstract, StateNumDiff, StatePinocchio, StateVector diff --git a/crocoddyl/plots.py b/crocoddyl/plots.py index bf821b95d5918426790dd70b899d02418ab23621..0109d5f48147efc7334ea5df3bf455ce12b82de2 100644 --- a/crocoddyl/plots.py +++ b/crocoddyl/plots.py @@ -24,10 +24,9 @@ class PlotUAM: axs[1, 0].set_title('Motor 3') axs[1, 1].plot(t,self.PlotDataType.control[:,3]) axs[1, 1].set_title('Motor 4') - return fig,axs - def plotActuation(self): + def plotFlyingPlatformActuation(self): fig, axs = plt.subplots(1,2, figsize=(15,10)) fig.suptitle('Motor forces') t = self.PlotDataType.t @@ -35,11 +34,18 @@ class PlotUAM: axs[0].set_title('Moments') axs[0].legend(['Mx','My','Mz']) axs[1].plot(t,self.PlotDataType.thrust) - axs[1].set_title('Motor 2') - - + axs[1].set_title('Thrust') return fig,axs + # def plotArmActuation(self): + # fig, axs = plt.subplot(1,1figsize=(15,10)) + # fig.suptitle('Motor forces') + # t = self.PlotDataType.t + # axs[0].plot(t,self.PlotDataType.M[:,0], t,self.PlotDataType.M[:,1], t,self.PlotDataType.M[:,2]) + # axs[0].set_title('Moments') + # axs[0].legend(['M1','M2','M3','M4','M5','M6']) + # return fig,axs + class PlotDataUAM(): def __init__(self, model): self.t = np.arange(0, model.knots*model.dt, model.dt) @@ -50,7 +56,7 @@ class PlotDataUAM(): My = model.d*(-self.control[:,0]+self.control[:,1]-self.control[:,2]+self.control[:,3]) Mz = model.cm/model.cf*(-self.control[:,0]-self.control[:,1]+self.control[:,2]+self.control[:,3]) - self.M = np.zeros([np.size(self.control,1), 3]) + self.M = np.zeros([np.size(self.control,0), 3]) self.M[:, 0] = Mx self.M[:, 1] = My self.M[:, 2] = Mz diff --git a/crocoddyl/robots.py b/crocoddyl/robots.py index 802d504bb03d5263deba23015da79d310330df9f..8008ad622f7a1d1dae2710494fffdc951e4ce1ce 100644 --- a/crocoddyl/robots.py +++ b/crocoddyl/robots.py @@ -133,7 +133,7 @@ def loadKinton(modelPath='/opt/openrobots/share/example-robot-data'): robot.q0.flat[7:] = [0, 0, 0, 0, 0, 0] robot.model.referenceConfigurations["initial_pose"] = robot.q0 robot.q0.flat[7:] = [0, 0.2, 1.7, 2, 0, 0] - robot.model.referenceConfigurations["centered"] = robot.q0 + robot.model.referenceConfigurations["centered"] = robot.q0 return robot def loadKintonArm(modelPath='/opt/openrobots/share/example-robot-data'): @@ -141,3 +141,10 @@ def loadKintonArm(modelPath='/opt/openrobots/share/example-robot-data'): URDF_SUBPATH = "/kinton_description/urdf/" + URDF_FILENAME robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath]) return robot + +def loadBorinotArm(modelPath='/opt/openrobots/share/example-robot-data'): + URDF_FILENAME = "borinot_arm.urdf" + URDF_SUBPATH = "/borinot_arm/urdf/" + URDF_FILENAME + robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath]) + robot.q0.flat = [np.pi,0] + return robot diff --git a/examples/notebooks/borinot_arm.ipynb b/examples/notebooks/borinot_arm.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..492a1840bddaf2978f70214924c8eb9269e3d964 --- /dev/null +++ b/examples/notebooks/borinot_arm.ipynb @@ -0,0 +1,597 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 98, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl import *\n", + "import pinocchio as pin\n", + "import numpy as np\n", + "\n", + "robot = loadBorinotArm()\n", + "robot.initViewer(loadModel=True)\n", + "\n", + "q0 = [-3.14, 3.14]\n", + "robot.q0.flat = q0\n", + "robot.framesForwardKinematics(robot.q0)\n", + "robot.display(robot.q0)\n", + "\n", + "IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)\n", + "IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)\n", + "Mlink1 = robot.data.oMf[IDX_LINK1]\n", + "Mlink2 = robot.data.oMf[IDX_LINK2]\n", + "\n", + "target_pos = np.array([0,0,0.3])\n", + "target_quat = pin.Quaternion(1, 0, 0, 0)\n", + "target_quat.normalize()\n", + "\n", + "Mref = pin.SE3()\n", + "Mref.translation = target_pos.reshape(3,1)\n", + "Mref.rotation = target_quat.matrix()\n", + "\n", + "#robot.viewer.gui.addXYZaxis('world/framelink1', [1., 0., 0., 1.], .005, 0.05)\n", + "#robot.viewer.gui.addXYZaxis('world/framelink2', [1., 0., 0., 1.], .005, 0.05)\n", + "#robot.viewer.gui.addXYZaxis('world/frameref', [1., 0., 0., 1.], .005, 0.05)\n", + "\n", + "#robot.viewer.gui.applyConfiguration('world/framelink1', pin.se3ToXYZQUATtuple(Mlink1))\n", + "#robot.viewer.gui.applyConfiguration('world/framelink2', pin.se3ToXYZQUATtuple(Mlink2))\n", + "#robot.viewer.gui.applyConfiguration('world/frameref', pin.se3ToXYZQUATtuple(Mref))\n", + "\n", + "robot.viewer.gui.refresh()" + ] + }, + { + "cell_type": "code", + "execution_count": 111, + "metadata": {}, + "outputs": [], + "source": [ + "state = StatePinocchio(robot.model)\n", + "\n", + "goalOrientationCost1 = CostModelFrameRotation(robot.model, \n", + " frame=robot.model.getFrameId('link1'), \n", + " ref=Mref.rotation, \n", + " nu=robot.model.nv)\n", + "goalOrientationCost2 = CostModelFrameRotation(robot.model, \n", + " frame=robot.model.getFrameId('link2'), \n", + " ref=Mref.rotation, \n", + " nu=robot.model.nv)\n", + "\n", + "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=robot.model.nv)\n", + "uRegCost = CostModelControl(robot.model, nu=robot.model.nv)\n", + "uLimCost = CostModelControl(robot.model, \n", + " nu=robot.model.nv,\n", + " activation = ActivationModelInequality(np.array([-1e-3, -1e-3]), np.array([1e-3, 1e-3])))\n", + "\n", + "\n", + "\n", + "runningCostModel = CostModelSum(robot.model)\n", + "terminalCostModel = CostModelSum(robot.model)\n", + "\n", + "runningCostModel.addCost(name=\"ori1\", weight=1e-2, cost=goalOrientationCost1)\n", + "runningCostModel.addCost(name=\"ori2\", weight=1e-2, cost=goalOrientationCost2)\n", + "runningCostModel.addCost(name=\"regx\", weight=1e-7, cost=xRegCost)\n", + "runningCostModel.addCost(name=\"regu\", weight=1e-1, cost=uRegCost)\n", + "runningCostModel.addCost(name=\"limu\", weight=10000, cost=uLimCost)\n", + "terminalCostModel.addCost(name=\"ori1\", weight=5, cost=goalOrientationCost1)\n", + "terminalCostModel.addCost(name=\"ori2\", weight=5, cost=goalOrientationCost2)" + ] + }, + { + "cell_type": "code", + "execution_count": 112, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 0 8.22722e+02 1.53608e-07 2.85796e-11 1.00000e-09 1.00000e-09 1.0000 1\n", + " 1 7.82866e+02 1.64964e+07 1.64366e+03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 2 7.74377e+02 1.59686e+07 1.55226e+03 1.00000e-09 1.00000e-09 0.0156 1\n", + " 3 7.65439e+02 1.66619e+07 1.51114e+03 1.00000e-09 1.00000e-09 0.0156 1\n", + " 4 7.46728e+02 1.71219e+07 1.47746e+03 1.00000e-09 1.00000e-09 0.0625 1\n", + " 5 6.73463e+02 1.67466e+07 1.42448e+03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 6 5.15004e+02 1.34686e+07 1.34587e+03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 7 2.06038e+02 1.11691e+07 9.69961e+02 1.00000e-09 1.00000e-09 0.5000 1\n", + " 8 2.00761e+02 4.14994e+06 4.06760e+02 1.00000e-09 1.00000e-09 0.0312 1\n", + " 9 1.47211e+02 3.94685e+06 3.53679e+02 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 10 1.45307e+02 3.07307e+06 2.93457e+02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 11 1.43810e+02 2.95843e+06 2.80205e+02 1.00000e-09 1.00000e-09 0.0156 1\n", + " 12 1.31407e+02 3.12254e+06 2.61558e+02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 13 1.30515e+02 2.71872e+06 2.55405e+02 1.00000e-09 1.00000e-09 0.0156 1\n", + " 14 1.18786e+02 2.87331e+06 2.45170e+02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 15 1.06145e+02 2.56880e+06 2.14438e+02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 16 9.25951e+01 2.37605e+06 1.97031e+02 1.00000e-09 1.00000e-09 0.2500 1\n", + " 17 8.30065e+01 2.11979e+06 1.83576e+02 1.00000e-09 1.00000e-09 0.2500 1\n", + " 18 8.16102e+01 1.74436e+06 1.63244e+02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 19 3.81373e+01 8.63706e+06 1.59411e+02 1.00000e-09 1.00000e-09 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 20 3.76670e+01 7.76821e+05 7.41861e+01 1.00000e-09 1.00000e-09 0.0625 1\n", + " 21 3.64285e+01 6.99766e+05 7.11054e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 22 3.39374e+01 2.99123e+06 6.26298e+01 1.00000e-09 1.00000e-09 0.1250 1\n", + " 23 3.36298e+01 6.43193e+05 6.04564e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 24 3.33496e+01 6.69338e+05 5.79480e+01 1.00000e-09 1.00000e-09 0.0078 1\n", + " 25 3.14735e+01 1.10352e+06 5.58016e+01 1.00000e-09 1.00000e-09 0.0625 1\n", + " 26 3.12530e+01 6.91668e+05 4.73205e+01 1.00000e-09 1.00000e-09 0.0078 1\n", + " 27 2.78995e+01 1.67839e+06 4.56223e+01 1.00000e-09 1.00000e-09 0.2500 1\n", + " 28 2.72211e+01 6.11993e+05 4.80125e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 29 2.28130e+01 8.76072e+05 4.70907e+01 1.00000e-09 1.00000e-09 0.1250 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 30 2.25688e+01 5.26996e+05 2.87922e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 31 2.22231e+01 5.34503e+05 2.65264e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 32 2.21574e+01 3.32318e+05 3.37833e+01 1.00000e-09 1.00000e-09 0.0078 1\n", + " 33 2.19798e+01 3.88303e+05 2.83477e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 34 2.15549e+01 6.01611e+05 4.21262e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 35 2.13188e+01 5.70678e+05 2.82849e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 36 2.09601e+01 4.95414e+05 2.56437e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 37 2.06580e+01 5.11630e+05 2.49112e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 38 2.03268e+01 4.84106e+05 2.42919e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 39 2.00539e+01 4.87820e+05 2.34225e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 40 1.98552e+01 4.55520e+05 2.32399e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 41 1.29691e+01 4.04156e+05 1.89734e+01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 42 1.28452e+01 3.29528e+05 1.98127e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 43 1.26077e+01 3.40873e+05 1.86347e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 44 1.24248e+01 3.09126e+05 1.68829e+01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 45 1.21672e+01 2.77048e+05 1.51092e+01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 46 1.19678e+01 1.54374e+05 9.19618e+00 1.00000e-09 1.00000e-09 0.0312 1\n", + " 47 1.14039e+01 7.31306e+04 4.50704e+00 1.00000e-09 1.00000e-09 0.2500 1\n", + " 48 1.13527e+01 2.32491e+05 1.85320e+01 1.00000e-09 1.00000e-09 0.0039 1\n", + " 49 1.12639e+01 1.00167e+05 6.47902e+00 1.00000e-09 1.00000e-09 0.0625 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 1.12175e+01 1.58071e+05 5.61753e+00 1.00000e-09 1.00000e-09 0.0156 1\n", + " 51 1.11446e+01 9.74140e+04 3.05637e+00 1.00000e-09 1.00000e-09 0.0625 1\n", + " 52 1.10797e+01 6.36989e+04 3.71029e+00 1.00000e-09 1.00000e-09 0.0312 1\n", + " 53 1.08488e+01 5.33516e+04 1.88867e+00 1.00000e-09 1.00000e-09 0.2500 1\n", + " 54 1.07958e+01 9.80265e+04 5.78745e+00 1.00000e-09 1.00000e-09 0.0312 1\n", + " 55 1.07894e+01 1.98524e+04 1.63667e+00 1.00000e-09 1.00000e-09 0.0039 1\n", + " 56 1.07906e+01 1.95905e+04 1.61528e+00 1.00000e-08 1.00000e-08 0.0020 1\n", + " 57 1.07906e+01 1.95880e+04 1.61494e+00 1.00000e-07 1.00000e-07 0.0020 1\n", + " 58 1.07906e+01 1.95632e+04 1.61153e+00 1.00000e-06 1.00000e-06 0.0020 1\n", + " 59 1.07900e+01 1.93589e+04 1.58081e+00 1.00000e-05 1.00000e-05 0.0020 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 60 1.07879e+01 1.90422e+04 1.42054e+00 1.00000e-04 1.00000e-04 0.0020 1\n", + " 61 1.02103e+01 2.98240e+04 1.10740e+00 1.00000e-05 1.00000e-05 1.0000 1\n", + " 62 1.01981e+01 8.72589e+04 4.89501e+00 1.00000e-05 1.00000e-05 0.0039 1\n", + " 63 1.01948e+01 7.21877e+04 4.09142e+00 1.00000e-05 1.00000e-05 0.0078 1\n", + " 64 1.01577e+01 4.55547e+04 2.65963e+00 1.00000e-05 1.00000e-05 0.0312 1\n", + " 65 1.01547e+01 4.53278e+03 3.03044e-01 1.00000e-05 1.00000e-05 0.0156 1\n", + " 66 1.00715e+01 4.45681e+03 2.69529e-01 1.00000e-06 1.00000e-06 1.0000 1\n", + " 67 1.00615e+01 4.86969e+04 3.84934e+00 1.00000e-06 1.00000e-06 0.0039 1\n", + " 68 1.00290e+01 3.87853e+04 3.45709e+00 1.00000e-06 1.00000e-06 0.0312 1\n", + " 69 1.00273e+01 8.13921e+03 5.75614e-01 1.00000e-06 1.00000e-06 0.0156 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 70 9.90109e+00 6.61931e+03 4.95109e-01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 71 9.87496e+00 3.85419e+04 2.16375e+00 1.00000e-06 1.00000e-06 0.0312 1\n", + " 72 9.85083e+00 1.04511e+04 7.01008e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 73 9.83419e+00 1.65326e+04 9.76490e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + " 74 9.81900e+00 7.15274e+03 5.06347e-01 1.00000e-06 1.00000e-06 0.1250 1\n", + " 75 9.79734e+00 3.63683e+04 2.22425e+00 1.00000e-06 1.00000e-06 0.0312 1\n", + " 76 9.79187e+00 6.94897e+03 4.35140e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 77 9.78163e+00 1.49202e+04 8.83738e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + " 78 9.77308e+00 5.07870e+03 3.13076e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 79 9.76524e+00 9.18986e+03 5.38885e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 80 9.75879e+00 4.07717e+03 2.47685e-01 1.00000e-06 1.00000e-06 0.1250 1\n", + " 81 9.74569e+00 2.27846e+04 1.39813e+00 1.00000e-06 1.00000e-06 0.0156 1\n", + " 82 9.74030e+00 5.15182e+03 2.97725e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 83 9.73264e+00 9.41877e+03 5.59391e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + " 84 9.72719e+00 3.69964e+03 2.10082e-01 1.00000e-06 1.00000e-06 0.1250 1\n", + " 85 9.71550e+00 1.88164e+04 1.09219e+00 1.00000e-06 1.00000e-06 0.0312 1\n", + " 86 9.70972e+00 4.11346e+03 2.28018e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 87 9.70378e+00 6.68727e+03 3.92024e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + " 88 9.69636e+00 3.09346e+03 1.70084e-01 1.00000e-06 1.00000e-06 0.1250 1\n", + " 89 9.68786e+00 1.31137e+04 7.60712e-01 1.00000e-06 1.00000e-06 0.0312 1\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 90 9.68266e+00 3.39338e+03 1.86600e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 91 9.67773e+00 5.36183e+03 3.10928e-01 1.00000e-06 1.00000e-06 0.0312 1\n", + " 92 9.66189e+00 2.90718e+03 1.72239e-01 1.00000e-06 1.00000e-06 0.2500 1\n", + " 93 9.64225e+00 2.91833e+04 1.69669e+00 1.00000e-06 1.00000e-06 0.0312 1\n", + " 94 9.63974e+00 3.81247e+03 2.09775e-01 1.00000e-06 1.00000e-06 0.0625 1\n", + " 95 9.63921e+00 7.92591e+03 4.91333e-01 1.00000e-05 1.00000e-05 0.0020 1\n", + " 96 9.63659e+00 6.15321e+03 3.70180e-01 1.00000e-05 1.00000e-05 0.0078 1\n", + " 97 9.63661e+00 4.43899e+03 2.76598e-01 1.00000e-04 1.00000e-04 0.0020 1\n", + " 98 9.63637e+00 3.23573e+03 1.68842e-01 1.00000e-03 1.00000e-03 0.0020 1\n", + " 99 9.60595e+00 2.74333e+03 5.91110e-02 1.00000e-04 1.00000e-04 1.0000 1\n" + ] + }, + { + "data": { + "text/plain": [ + "([array([-1.57, 2. , 0. , 0. ]),\n", + " array([-1.57729822, 2.25472028, -0.72982157, 25.47202793]),\n", + " array([-1.58761746, 2.67904827, -1.03192475, 42.43279939]),\n", + " array([-1.59731008, 3.25701976, -0.9692615 , 57.7971489 ]),\n", + " array([-1.60946252, 4.05982748, -1.21524398, 80.28077163]),\n", + " array([ -1.6522568 , 5.23211205, -4.27942802, 117.22845748]),\n", + " array([ -1.77571909, 6.84244399, -12.34622953, 161.03319408]),\n", + " array([-1.78004082, 7.21894508, -0.43217242, 37.65010873]),\n", + " array([ -1.75504158, 6.92260739, 2.4999235 , -29.63376914]),\n", + " array([ -1.70629477, 6.09817215, 4.87468119, -82.44352436]),\n", + " array([ -1.62343745, 4.53268252, 8.2857316 , -156.54896297]),\n", + " array([ -1.65617699, 2.43274086, -3.27395349, -209.99416576]),\n", + " array([ -1.51706154, 1.13198405, 13.91154471, -130.0756807 ]),\n", + " array([ -1.33968906, 0.12781729, 17.73724874, -100.41667583]),\n", + " array([ -1.18632898, -0.57513708, 15.33600765, -70.29543771]),\n", + " array([ -1.06266698, -1.03065706, 12.36620031, -45.5519972 ]),\n", + " array([ -0.95895031, -1.30359692, 10.37166617, -27.29398688]),\n", + " array([ -0.86863262, -1.42562081, 9.03176962, -12.20238886]),\n", + " array([-0.7887652 , -1.41375691, 7.98674213, 1.18639031]),\n", + " array([-0.71903626, -1.28140676, 6.97289382, 13.23501526]),\n", + " array([-0.66084481, -1.04181904, 5.8191444 , 23.95877183]),\n", + " array([-0.61615675, -0.70586636, 4.46880612, 33.59526793]),\n", + " array([-0.58524158, -0.29456809, 3.09151774, 41.12982675]),\n", + " array([-0.55812054, 0.05757514, 2.7121037 , 35.21432366]),\n", + " array([-0.5299746 , 0.32937182, 2.81459345, 27.17966714]),\n", + " array([-0.49987966, 0.52367651, 3.00949449, 19.43046966]),\n", + " array([-0.46866911, 0.65226196, 3.12105539, 12.8585447 ]),\n", + " array([-0.43735011, 0.72676502, 3.13189911, 7.45030647]),\n", + " array([-0.40660917, 0.75621649, 3.07409411, 2.94514648]),\n", + " array([-0.37676164, 0.74675187, 2.98475308, -0.94646144]),\n", + " array([-0.34777852, 0.70121889, 2.89831216, -4.55329882]),\n", + " array([-0.31942034, 0.62080112, 2.835818 , -8.04177688]),\n", + " array([ -0.2910036 , 0.50034969, 2.84167399, -12.04514253]),\n", + " array([-0.26802719, 0.44045374, 2.29764129, -5.98959569]),\n", + " array([-0.24460786, 0.34319677, 2.34193254, -9.72569682]),\n", + " array([-0.22572688, 0.29411836, 1.88809813, -4.90784049]),\n", + " array([-0.20556718, 0.20117149, 2.01596965, -9.29468741]),\n", + " array([-0.1902392 , 0.16448097, 1.53279837, -3.66905205]),\n", + " array([-0.17555308, 0.11943583, 1.46861252, -4.5045136 ]),\n", + " array([-0.16295542, 0.09070122, 1.25976544, -2.87346114]),\n", + " array([-0.15460476, 0.11364076, 0.83506599, 2.29395423]),\n", + " array([-0.14400337, 0.08821623, 1.06013876, -2.54245359]),\n", + " array([-0.13585892, 0.08940033, 0.81444583, 0.11841017]),\n", + " array([-0.12900215, 0.10019553, 0.68567639, 1.0795202 ]),\n", + " array([-0.11982961, 0.06545706, 0.91725422, -3.47384749]),\n", + " array([-0.11446431, 0.08196587, 0.5365297 , 1.65088127]),\n", + " array([-0.10628473, 0.04737721, 0.81795833, -3.4588661 ]),\n", + " array([-0.10173975, 0.06330045, 0.45449781, 1.59232381]),\n", + " array([-0.09809684, 0.08796058, 0.36429142, 2.46601341]),\n", + " array([-0.09156342, 0.06292209, 0.6533417 , -2.50384852]),\n", + " array([-0.08860098, 0.08981797, 0.29624414, 2.68958801]),\n", + " array([-8.41113402e-02, 8.98192415e-02, 4.48963844e-01, 1.26682246e-04]),\n", + " array([-0.07661463, 0.04047993, 0.74967094, -4.93393149]),\n", + " array([-0.07248192, 0.0420825 , 0.41327131, 0.16025745]),\n", + " array([-0.07033286, 0.0737576 , 0.21490544, 3.16751019]),\n", + " array([-0.06500669, 0.05565112, 0.53261783, -1.81064785]),\n", + " array([-0.06223331, 0.05606752, 0.27733792, 0.04163911]),\n", + " array([-0.06072503, 0.05537575, 0.1508272 , -0.06917702]),\n", + " array([-0.0588008 , 0.04934024, 0.19242303, -0.60355095]),\n", + " array([-0.05728975, 0.05114879, 0.15110566, 0.18085526]),\n", + " array([-0.055406 , 0.04880485, 0.18837493, -0.23439388]),\n", + " array([-0.05331239, 0.04513304, 0.20936049, -0.36718057]),\n", + " array([-0.05267916, 0.06647398, 0.06332339, 2.13409325]),\n", + " array([-0.04860043, 0.03661077, 0.40787264, -2.98632059]),\n", + " array([-0.04619855, 0.03585542, 0.24018852, -0.07553512]),\n", + " array([-0.04445763, 0.04875379, 0.17409218, 1.28983689]),\n", + " array([-0.04051333, 0.03105542, 0.39442964, -1.76983726]),\n", + " array([-0.03805347, 0.04075067, 0.24598583, 0.96952547]),\n", + " array([-0.03437846, 0.03626091, 0.36750111, -0.44897559]),\n", + " array([-0.02994425, 0.0252697 , 0.44342106, -1.09912161]),\n", + " array([-0.027269 , 0.0259477 , 0.26752522, 0.0678004 ]),\n", + " array([-0.02542369, 0.02427671, 0.18453117, -0.16709934]),\n", + " array([-0.02460686, 0.02364566, 0.08168262, -0.06310455]),\n", + " array([-0.02481139, 0.02407397, -0.02045263, 0.04283052]),\n", + " array([-0.02602649, 0.02535938, -0.12151053, 0.1285416 ]),\n", + " array([-0.02677571, 0.02602598, -0.07492197, 0.06665973]),\n", + " array([-0.02699581, 0.02496493, -0.02200992, -0.10610475]),\n", + " array([-0.02718888, 0.02995008, -0.0193066 , 0.49851444]),\n", + " array([-0.02777722, 0.02583974, -0.05883449, -0.41103367]),\n", + " array([-0.02836596, 0.02807469, -0.05887446, 0.22349431]),\n", + " array([-0.02842209, 0.02826759, -0.00561248, 0.01929074]),\n", + " array([-0.02804609, 0.02797519, 0.03760035, -0.02923988]),\n", + " array([-0.02724169, 0.02731715, 0.08043927, -0.06580413]),\n", + " array([-0.02599902, 0.02627106, 0.12426707, -0.10460939]),\n", + " array([-0.02430443, 0.02482775, 0.16945914, -0.14433051]),\n", + " array([-0.02214184, 0.02301411, 0.21625914, -0.18136414]),\n", + " array([-0.01949498, 0.02093098, 0.26468595, -0.20831347]),\n", + " array([-0.01631936, 0.01832006, 0.31756155, -0.26109166]),\n", + " array([-0.01198065, 0.00582109, 0.43387199, -1.24989718]),\n", + " array([-0.00855068, 0.01634518, 0.34299684, 1.05240916]),\n", + " array([-0.00501021, 0.01295793, 0.35404617, -0.33872542]),\n", + " array([-1.24294444e-03, -5.58053665e-03, 3.76727050e-01, -1.85384633e+00]),\n", + " array([6.41658650e-05, 3.07925391e-03, 1.30711031e-01, 8.65979057e-01]),\n", + " array([ 0.00137679, 0.00082214, 0.1312623 , -0.22571172]),\n", + " array([ 0.00192728, -0.00019212, 0.05504921, -0.10142579]),\n", + " array([ 0.00186848, -0.00046669, -0.00588028, -0.02745668]),\n", + " array([ 0.0015055 , -0.00040407, -0.03629733, 0.00626157]),\n", + " array([ 0.00106432, -0.00022673, -0.04411862, 0.01773411]),\n", + " array([ 6.60498153e-04, -5.22579516e-05, -4.03820501e-02, 1.74473308e-02]),\n", + " array([ 0.00031978, 0.00027062, -0.03407198, 0.03228813]),\n", + " array([ 7.63120643e-05, -1.21393142e-07, -2.43466316e-02, -2.70744739e-02])],\n", + " [array([0.00502226, 0.00625281]),\n", + " array([0.00489282, 0.0039777 ]),\n", + " array([0.00478028, 0.00332897]),\n", + " array([0.00475778, 0.00519445]),\n", + " array([0.00466625, 0.0094731 ]),\n", + " array([0.00411383, 0.00663804]),\n", + " array([ 0.00505131, -0.02061498]),\n", + " array([ 0.00438541, -0.0147986 ]),\n", + " array([ 0.00410653, -0.01100935]),\n", + " array([ 0.00418671, -0.01524423]),\n", + " array([ 0.00327164, -0.01583679]),\n", + " array([0.00374192, 0.01572243]),\n", + " array([0.00293841, 0.01104967]),\n", + " array([0.00277776, 0.00637701]),\n", + " array([0.00274507, 0.00369555]),\n", + " array([0.00261952, 0.0031665 ]),\n", + " array([0.00247602, 0.00309112]),\n", + " array([0.00232936, 0.003006 ]),\n", + " array([0.00218436, 0.00282198]),\n", + " array([0.00204913, 0.00250989]),\n", + " array([0.00193328, 0.00211665]),\n", + " array([0.00185542, 0.00142247]),\n", + " array([ 0.00181241, -0.00136566]),\n", + " array([ 0.0017519 , -0.00164286]),\n", + " array([ 0.00168072, -0.00166064]),\n", + " array([ 0.00160976, -0.00157204]),\n", + " array([ 0.00154407, -0.0014534 ]),\n", + " array([ 0.00148501, -0.00133774]),\n", + " array([ 0.00143259, -0.00124103]),\n", + " array([ 0.00138695, -0.00118182]),\n", + " array([ 0.00134574, -0.00112911]),\n", + " array([ 0.00131417, -0.00118104]),\n", + " array([0.00127332, 0.00098092]),\n", + " array([ 0.00124508, -0.0010138 ]),\n", + " array([0.00121884, 0.00077885]),\n", + " array([ 0.00119889, -0.00104467]),\n", + " array([0.00117496, 0.00100738]),\n", + " array([ 0.00115702, -0.00025267]),\n", + " array([0.00114045, 0.00026378]),\n", + " array([0.00112558, 0.00097862]),\n", + " array([ 0.00111239, -0.00100235]),\n", + " array([0.00110028, 0.00049139]),\n", + " array([0.00108956, 0.00015807]),\n", + " array([ 0.00107994, -0.00093198]),\n", + " array([0.00107162, 0.00099536]),\n", + " array([ 0.00106528, -0.00102585]),\n", + " array([0.001057 , 0.00099499]),\n", + " array([0.00105049, 0.00016548]),\n", + " array([ 0.00104482, -0.00099788]),\n", + " array([0.00103887, 0.00101763]),\n", + " array([ 0.00103559, -0.00054779]),\n", + " array([ 0.00103163, -0.00098835]),\n", + " array([0.00102698, 0.00101591]),\n", + " array([0.0010248 , 0.00060581]),\n", + " array([ 0.00102194, -0.00098234]),\n", + " array([-0.00098061, 0.00024471]),\n", + " array([-0.00098289, -0.00014065]),\n", + " array([ 1.01519924e-03, -9.47907578e-05]),\n", + " array([0.00101353, 0.00016862]),\n", + " array([ 1.01197354e-03, -6.78071478e-05]),\n", + " array([ 1.01060480e-03, -1.03015698e-05]),\n", + " array([0.00100927, 0.00051015]),\n", + " array([ 0.00100809, -0.00100069]),\n", + " array([0.00100694, 0.00059735]),\n", + " array([0.00100597, 0.00029484]),\n", + " array([ 0.0010051 , -0.00058193]),\n", + " array([0.00100432, 0.00056958]),\n", + " array([ 0.00100363, -0.00025239]),\n", + " array([ 1.00301107e-03, -9.74510906e-05]),\n", + " array([-0.00099753, 0.00013933]),\n", + " array([-0.00099798, -0.00013557]),\n", + " array([-9.98333942e-04, -6.73736000e-05]),\n", + " array([-9.98635957e-04, -6.63477125e-05]),\n", + " array([-9.98900230e-04, -7.06702645e-05]),\n", + " array([1.00087811e-03, 2.75223616e-05]),\n", + " array([1.00070763e-03, 5.06084878e-06]),\n", + " array([0.00100053, 0.00015832]),\n", + " array([-0.0009996 , -0.00027063]),\n", + " array([0.00100028, 0.00016338]),\n", + " array([ 1.00021206e-03, -2.95272879e-06]),\n", + " array([1.00017228e-03, 2.74865484e-05]),\n", + " array([1.00016177e-03, 3.01461957e-05]),\n", + " array([1.00018110e-03, 3.03899067e-05]),\n", + " array([1.00023097e-03, 3.12860647e-05]),\n", + " array([1.00031215e-03, 3.32925301e-05]),\n", + " array([1.00042553e-03, 3.71435397e-05]),\n", + " array([1.00057211e-03, 3.42757779e-05]),\n", + " array([ 0.00100063, -0.00014687]),\n", + " array([0.00100057, 0.00050868]),\n", + " array([-0.00099958, -0.0003504 ]),\n", + " array([-0.00099974, -0.00037148]),\n", + " array([-0.00099982, 0.00047292]),\n", + " array([-0.00099989, -0.00028052]),\n", + " array([-9.99948052e-04, -3.98666926e-05]),\n", + " array([-8.34998757e-04, -3.83462283e-05]),\n", + " array([-4.33343683e-04, -2.03126144e-05]),\n", + " array([-1.24132527e-04, -4.99066334e-06]),\n", + " array([3.75674851e-05, 2.82131419e-06]),\n", + " array([9.45901732e-05, 9.20707568e-06]),\n", + " array([ 8.03317879e-05, -6.59839394e-06])],\n", + " False)" + ] + }, + "execution_count": 112, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "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-2\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 = 100\n", + "q0 = [-1.57, 2]\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()" + ] + }, + { + "cell_type": "code", + "execution_count": 108, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl.diagnostic import displayTrajectory\n", + "\n", + "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" + ] + }, + { + "cell_type": "code", + "execution_count": 109, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[array([ 0.03434323, -0.00174103]),\n", + " array([ 0.03144137, -0.00107895]),\n", + " array([0.02866946, 0.0004568 ]),\n", + " array([2.60434255e-02, 5.76080344e-05]),\n", + " array([ 2.35657120e-02, -9.79456185e-05]),\n", + " array([ 2.12411161e-02, -8.49880785e-05]),\n", + " array([ 1.90745430e-02, -1.25102029e-05]),\n", + " array([1.70690156e-02, 7.25447062e-05]),\n", + " array([0.01522504, 0.00014527]),\n", + " array([0.01354063, 0.00019581]),\n", + " array([0.01201112, 0.00022169]),\n", + " array([0.01062994, 0.00022519]),\n", + " array([0.009389 , 0.00021008]),\n", + " array([0.0082792 , 0.00018091]),\n", + " array([0.00729088, 0.00014233]),\n", + " array([6.41421515e-03, 9.89299792e-05]),\n", + " array([5.63949851e-03, 5.51275868e-05]),\n", + " array([4.95734605e-03, 1.46062335e-05]),\n", + " array([ 4.35882837e-03, -2.01188236e-05]),\n", + " array([ 3.83555381e-03, -4.79079750e-05]),\n", + " array([ 3.37971267e-03, -6.87669497e-05]),\n", + " array([ 2.98409523e-03, -8.33785617e-05]),\n", + " array([ 2.64209107e-03, -9.26838536e-05]),\n", + " array([ 2.34767505e-03, -9.76317661e-05]),\n", + " array([ 2.09538333e-03, -9.90719245e-05]),\n", + " array([ 1.88028254e-03, -9.77257033e-05]),\n", + " array([ 1.69793434e-03, -9.41893004e-05]),\n", + " array([ 1.54435716e-03, -8.89467934e-05]),\n", + " array([ 1.41598683e-03, -8.23852371e-05]),\n", + " array([ 1.30963692e-03, -7.48090905e-05]),\n", + " array([ 1.22245988e-03, -6.64531190e-05]),\n", + " array([ 1.15190914e-03, -5.74912624e-05]),\n", + " array([ 1.09570280e-03, -4.80124385e-05]),\n", + " array([ 1.05178880e-03, -3.77322633e-05]),\n", + " array([ 1.01831159e-03, -2.66788009e-05]),\n", + " array([-0.00100442, -0.00011997]),\n", + " array([-0.00102198, -0.00010969]),\n", + " array([-0.00103371, -0.00010054]),\n", + " array([-1.04076513e-03, -9.24780866e-05]),\n", + " array([-1.04413238e-03, -8.51271123e-05]),\n", + " array([-1.04465342e-03, -7.84536313e-05]),\n", + " array([-1.04304415e-03, -7.24468194e-05]),\n", + " array([-1.03990963e-03, -6.70918296e-05]),\n", + " array([-1.03575794e-03, -6.23700911e-05]),\n", + " array([-1.03101199e-03, -5.82612957e-05]),\n", + " array([-1.02601970e-03, -5.47449497e-05]),\n", + " array([-1.02106260e-03, -5.18015004e-05]),\n", + " array([-1.01636299e-03, -4.94131409e-05]),\n", + " array([-1.01208977e-03, -4.75644043e-05]),\n", + " array([-1.00836302e-03, -4.62428029e-05]),\n", + " array([-1.00525746e-03, -4.54441690e-05]),\n", + " array([-1.00280475e-03, -4.52187912e-05]),\n", + " array([-1.00099474e-03, -4.57113061e-05]),\n", + " array([-7.75966286e-04, -3.51857985e-05]),\n", + " array([-5.24712414e-05, 1.08102010e-06]),\n", + " array([3.10358387e-04, 1.84185717e-05]),\n", + " array([4.36981752e-04, 2.37595510e-05]),\n", + " array([4.27189606e-04, 2.24542176e-05]),\n", + " array([3.52255067e-04, 1.81220212e-05]),\n", + " array([2.57768106e-04, 1.30217804e-05]),\n", + " array([1.69252639e-04, 8.38457136e-06]),\n", + " array([9.82161322e-05, 4.73656540e-06]),\n", + " array([4.74149597e-05, 2.17254102e-06]),\n", + " array([1.48700533e-05, 5.60607731e-07]),\n", + " array([-3.38936011e-06, -3.20349510e-07]),\n", + " array([-1.16556271e-05, -6.98741820e-07]),\n", + " array([-1.36725437e-05, -7.68986825e-07]),\n", + " array([-1.22997939e-05, -6.76895006e-07]),\n", + " array([-9.49414836e-06, -5.20512588e-07]),\n", + " array([-6.44875500e-06, -3.58389148e-07]),\n", + " array([-3.78688015e-06, -2.20118658e-07]),\n", + " array([-1.75043220e-06, -1.16259446e-07]),\n", + " array([-3.54928263e-07, -4.63188419e-08]),\n", + " array([ 4.97444614e-07, -4.47770519e-09]),\n", + " array([9.43867321e-07, 1.67324153e-08]),\n", + " array([1.11822224e-06, 2.43586848e-08]),\n", + " array([1.13075756e-06, 2.40830464e-08]),\n", + " array([1.06202328e-06, 1.99848461e-08]),\n", + " array([9.64788912e-07, 1.46882720e-08]),\n", + " array([8.69552669e-07, 9.67391624e-09]),\n", + " array([7.90904233e-07, 5.61950936e-09]),\n", + " array([7.33261449e-07, 2.69903777e-09]),\n", + " array([6.95360548e-07, 8.12476831e-10]),\n", + " array([ 6.73401220e-07, -2.56030771e-10]),\n", + " array([ 6.63018301e-07, -7.40896901e-10]),\n", + " array([ 6.60354040e-07, -8.43626453e-10]),\n", + " array([ 6.62506960e-07, -7.12548348e-10]),\n", + " array([ 6.67585083e-07, -4.41944575e-10]),\n", + " array([ 6.74525619e-07, -8.23506490e-11]),\n", + " array([6.82779843e-07, 3.42849843e-10]),\n", + " array([6.91911700e-07, 8.16791999e-10]),\n", + " array([7.01127444e-07, 1.30508142e-09]),\n", + " array([7.08745180e-07, 1.72848388e-09]),\n", + " array([7.11630984e-07, 1.93336819e-09]),\n", + " array([7.04676293e-07, 1.66330694e-09]),\n", + " array([6.8047287e-07, 5.3907942e-10]),\n", + " array([ 6.29457551e-07, -1.94447535e-09]),\n", + " array([ 5.40946189e-07, -6.44393291e-09]),\n", + " array([ 4.05664486e-07, -1.41542129e-08]),\n", + " array([ 2.20335752e-07, -2.15210389e-08])]" + ] + }, + "execution_count": 109, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "ddp.us" + ] + } + ], + "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.16" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/notebooks/kinton_fixed_base.ipynb b/examples/notebooks/kinton_fixed_base.ipynb index df79af6a9602d6fb0a9628cd187e9db746229e4c..fbbcc39e3b0df2a8b673a363db7e04bced267472 100644 --- a/examples/notebooks/kinton_fixed_base.ipynb +++ b/examples/notebooks/kinton_fixed_base.ipynb @@ -169,7 +169,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4, diff --git a/examples/notebooks/kinton_flying_ee.ipynb b/examples/notebooks/kinton_flying_ee.ipynb index 5bc2d31dc01a91b333e4c15a004f0c338824f149..d20bf6f4096afcbb1794b4903cec27b1b077efe6 100644 --- a/examples/notebooks/kinton_flying_ee.ipynb +++ b/examples/notebooks/kinton_flying_ee.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 21, + "execution_count": 33, "metadata": {}, "outputs": [], "source": [ @@ -14,7 +14,7 @@ }, { "cell_type": "code", - "execution_count": 22, + "execution_count": 34, "metadata": {}, "outputs": [], "source": [ @@ -30,7 +30,7 @@ }, { "cell_type": "code", - "execution_count": 23, + "execution_count": 35, "metadata": {}, "outputs": [], "source": [ @@ -38,6 +38,7 @@ "target_pos = np.array([0,0,1])\n", "[ -0.7071068, 0, 0.7071068, 0 ]\n", "target_quat = pin.Quaternion(-1, 0, 1, 0)\n", + "target_quat = pin.Quaternion(1, 0, 0, 0)\n", "target_quat.normalize()\n", "\n", "# Plot goal frame\n", @@ -48,7 +49,7 @@ }, { "cell_type": "code", - "execution_count": 24, + "execution_count": 36, "metadata": {}, "outputs": [], "source": [ @@ -71,7 +72,7 @@ "\n", "\n", "wBasePos = [1]\n", - "wBaseOri = [5]\n", + "wBaseOri = [1]\n", "wArmPos = [1]\n", "wBaseVel = [10]\n", "wBaseRate = [10]\n", @@ -103,8 +104,8 @@ "runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n", "runningCostModel.addCost(name=\"regx\", weight=1e-4, cost=xRegCost)\n", "runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n", - "# runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n", - "terminalCostModel.addCost(name=\"pos\", weight=0, cost=goalTrackingCost)\n", + "runningCostModel.addCost(name=\"limu\", weight=1e-2, cost=uLimCost)\n", + "terminalCostModel.addCost(name=\"pos\", weight=5, cost=goalTrackingCost)\n", "\n", "# DIFFERENTIAL ACTION MODEL\n", "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n", @@ -113,7 +114,7 @@ }, { "cell_type": "code", - "execution_count": 25, + "execution_count": 37, "metadata": { "scrolled": true }, @@ -123,56 +124,64 @@ "output_type": "stream", "text": [ "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 9.08198e+00 4.56473e-01 1.97554e+01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 1 4.04502e+00 2.73160e-01 1.52749e+01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 2 2.95386e+00 9.48071e-02 4.97010e+00 1.00000e-09 1.00000e-09 0.2500 0\n", - " 3 2.46366e+00 5.13997e-02 2.99065e+00 1.00000e-09 1.00000e-09 0.5000 0\n", - " 4 1.82967e+00 4.92640e-02 1.93473e+00 1.00000e-09 1.00000e-09 0.5000 0\n", - " 5 1.76305e+00 1.16694e-02 6.93346e-01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 6 1.56127e+00 1.93517e-02 5.77282e-01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 7 1.51972e+00 4.57215e-03 2.26322e-01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 8 1.47284e+00 6.55408e-03 1.88064e-01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 9 1.42210e+00 3.88011e-03 1.41680e-01 1.00000e-09 1.00000e-09 0.5000 0\n", + " 0 1.69470e+00 3.76618e-01 2.17448e+01 1.00000e-09 1.00000e-09 0.5000 0\n", + " 1 1.57516e+00 1.32234e-04 3.27743e+00 1.00000e-09 1.00000e-09 0.0625 0\n", + " 2 1.40857e+00 1.44596e-03 2.92461e+00 1.00000e-09 1.00000e-09 0.0625 0\n", + " 3 1.31015e+00 1.23631e-03 2.48624e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 4 1.20843e+00 4.22214e-03 2.12939e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 5 1.13694e+00 5.55300e-03 1.79589e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 6 1.08536e+00 6.39530e-03 1.54614e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 7 1.03600e+00 6.92438e-03 1.35711e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 8 9.77145e-01 7.06627e-03 1.19248e+00 1.00000e-09 1.00000e-09 0.1250 0\n", + " 9 9.09731e-01 6.75431e-03 1.02581e+00 1.00000e-09 1.00000e-09 0.1250 0\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 1.39035e+00 7.66291e-04 7.05487e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 11 1.36621e+00 5.54061e-04 4.43489e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 12 1.35191e+00 6.60168e-04 2.63324e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 13 1.33763e+00 6.67983e-04 3.33965e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 14 1.31112e+00 1.07201e-03 5.27193e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 15 1.28462e+00 7.90939e-04 4.01468e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 16 1.27488e+00 1.77533e-04 1.22286e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 17 1.27045e+00 9.30922e-05 5.35113e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 18 1.26834e+00 4.14692e-05 2.48093e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 19 1.26725e+00 1.98810e-05 1.26676e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 10 8.80585e-01 6.06067e-03 8.49015e-01 1.00000e-09 1.00000e-09 0.0625 0\n", + " 11 8.50285e-01 5.48181e-03 7.81275e-01 1.00000e-09 1.00000e-09 0.0625 0\n", + " 12 8.22672e-01 5.28744e-03 7.12621e-01 1.00000e-09 1.00000e-09 0.0625 0\n", + " 13 6.06262e-01 5.73134e-03 1.22007e+00 1.00000e-09 1.00000e-09 0.2500 0\n", + " 14 5.68371e-01 3.22384e-03 7.08657e-01 1.00000e-09 1.00000e-09 0.1250 0\n", + " 15 5.45416e-01 5.40589e-03 3.63302e-01 1.00000e-09 1.00000e-09 0.5000 0\n", + " 16 5.38146e-01 2.80326e-03 4.36133e-01 1.00000e-09 1.00000e-09 0.0312 0\n", + " 17 5.32731e-01 2.65009e-03 3.95857e-01 1.00000e-09 1.00000e-09 0.0312 0\n", + " 18 5.24787e-01 2.54258e-03 3.60276e-01 1.00000e-09 1.00000e-09 0.1250 0\n", + " 19 5.12394e-01 2.56299e-03 3.26471e-01 1.00000e-09 1.00000e-09 0.2500 0\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 20 1.26666e+00 1.03064e-05 6.83409e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 21 1.26632e+00 5.53840e-06 3.87870e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 22 1.26611e+00 3.14271e-06 2.30334e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 23 1.26598e+00 1.84439e-06 1.42197e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 24 1.26590e+00 1.12726e-06 9.06540e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 25 1.26585e+00 7.07977e-07 5.93357e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 26 1.26581e+00 4.57519e-07 3.96762e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 27 1.26579e+00 3.01730e-07 2.69959e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 28 1.26577e+00 2.02930e-07 1.86307e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 29 1.26576e+00 1.38494e-07 1.30080e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 20 4.51665e-01 1.94864e-03 1.74867e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 21 4.49028e-01 1.06252e-03 1.44774e-01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 22 4.48088e-01 1.00681e-03 1.30878e-01 1.00000e-09 1.00000e-09 0.0156 1\n", + " 23 4.46691e-01 9.63453e-04 1.18004e-01 1.00000e-09 1.00000e-09 0.0312 1\n", + " 24 4.45908e-01 9.16905e-04 1.05126e-01 1.00000e-09 1.00000e-09 0.0625 1\n", + " 25 4.44141e-01 8.90466e-04 9.59775e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 26 4.34659e-01 8.62676e-04 9.03651e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 27 4.14941e-01 7.10088e-04 6.71669e-02 1.00000e-09 1.00000e-09 0.5000 1\n", + " 28 4.06401e-01 1.95611e-04 1.68866e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 29 4.06380e-01 5.53495e-05 1.80089e-02 1.00000e-09 1.00000e-09 0.0078 1\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 30 1.26575e+00 9.57989e-08 9.16982e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 31 1.26574e+00 6.69611e-08 6.51573e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 32 1.26574e+00 4.72426e-08 4.66059e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 33 1.26574e+00 3.35797e-08 3.35217e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 34 1.26573e+00 2.40247e-08 2.42232e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 35 1.26573e+00 1.72804e-08 1.75728e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 36 1.26573e+00 1.24872e-08 1.27906e-06 1.00000e-09 1.00000e-09 1.0000 1\n", - " 37 1.26573e+00 9.05825e-09 9.33607e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 38 1.26573e+00 6.59276e-09 6.83084e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 39 1.26573e+00 4.81171e-09 5.00804e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 30 4.06360e-01 4.36014e-05 9.02576e-03 1.00000e-09 1.00000e-09 0.0039 1\n", + " 31 4.06324e-01 3.60415e-05 5.14856e-03 1.00000e-09 1.00000e-09 0.0078 1\n", + " 32 4.06289e-01 3.31018e-05 4.13608e-03 1.00000e-09 1.00000e-09 0.0312 1\n", + " 33 4.04738e-01 3.02612e-05 3.01915e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 34 4.04647e-01 7.90748e-06 1.60730e-02 1.00000e-09 1.00000e-09 0.0312 1\n", + " 35 4.03663e-01 1.66647e-05 1.52775e-02 1.00000e-09 1.00000e-09 0.1250 1\n", + " 36 4.03263e-01 3.16630e-05 1.31222e-02 1.00000e-09 1.00000e-09 0.0625 1\n", + " 37 4.01802e-01 3.04877e-05 6.67863e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 38 4.00980e-01 1.71436e-05 3.75619e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 39 4.00949e-01 9.64640e-06 2.12202e-03 1.00000e-09 1.00000e-09 0.0156 1\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 40 1.26573e+00 3.52026e-09 3.67802e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 41 1.26573e+00 2.58066e-09 2.70523e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 42 1.26573e+00 1.89516e-09 1.99225e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 43 1.26573e+00 1.39382e-09 1.46878e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 44 1.26573e+00 1.02641e-09 1.08385e-07 1.00000e-09 1.00000e-09 1.0000 1\n", - " 45 1.26573e+00 7.56671e-10 8.00443e-08 1.00000e-09 1.00000e-09 1.0000 1\n" + " 40 4.00875e-01 9.69303e-06 1.21988e-03 1.00000e-09 1.00000e-09 0.0625 1\n", + " 41 4.00611e-01 8.56686e-06 8.46607e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 42 4.00534e-01 4.15531e-06 1.74812e-03 1.00000e-09 1.00000e-09 0.0625 1\n", + " 43 4.00507e-01 4.40068e-06 1.57903e-03 1.00000e-09 1.00000e-09 0.0312 1\n", + " 44 4.00178e-01 5.41947e-06 9.21430e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 45 3.99984e-01 2.80567e-06 4.12701e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 46 3.99974e-01 7.39590e-07 1.87846e-04 1.00000e-09 1.00000e-09 0.1250 1\n", + " 47 3.99912e-01 8.01009e-07 1.64026e-04 1.00000e-09 1.00000e-09 0.5000 1\n", + " 48 3.99897e-01 1.90527e-07 4.11958e-05 1.00000e-09 1.00000e-09 0.5000 1\n", + " 49 3.99897e-01 4.66815e-08 1.03620e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 3.99893e-01 6.56812e-08 9.45983e-06 1.00000e-09 1.00000e-09 0.5000 1\n", + " 51 3.99892e-01 1.66638e-08 2.33213e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 52 3.99892e-01 4.34091e-13 6.47800e-11 1.00000e-09 1.00000e-09 1.0000 1\n" ] }, { @@ -180,200 +189,223 @@ "text/plain": [ "([array([0. , 0. , 0. , 0. , 0. , 0. , 1. , 0. , 0.2, 1.7, 2. , 0. , 0. ,\n", " 0. , 0. , 0. , 0. , 0. , 0. , 0. , 0. , 0. , 0. , 0. , 0. ]),\n", - " array([-3.57544605e-03, -7.44668560e-03, 4.49365233e-01, 1.79681024e-02,\n", - " -4.45620815e-03, -3.01835956e-01, 9.53180122e-01, 6.46208456e-01,\n", - " -1.27364727e-02, 1.70866626e+00, 1.99610746e+00, -4.22029271e-02,\n", - " -1.35228129e-01, 2.31269481e-04, 2.09342835e-03, 8.98934560e+00,\n", - " 7.30155326e-01, -1.81083347e-01, -1.22654650e+01, 1.29241691e+01,\n", - " -4.25472945e+00, 1.73325174e-01, -7.78508082e-02, -8.44058542e-01,\n", - " -2.70456257e+00]),\n", - " array([-2.75335078e-03, -9.70018618e-03, 7.05702573e-01, 3.82496094e-02,\n", - " -2.73270534e-02, -4.96030274e-01, 8.67031814e-01, 1.10225357e+00,\n", - " -1.21343614e-01, 1.66622939e+00, 1.95528582e+00, -9.22865263e-02,\n", - " -1.87437132e-01, 8.35589340e-02, 3.11522254e-01, 5.11765173e+00,\n", - " 1.08505275e+00, -7.88122271e-01, -8.49670771e+00, 9.12090236e+00,\n", - " -2.17214283e+00, -8.48737383e-01, -8.16432846e-01, -1.00167198e+00,\n", - " -1.04418008e+00]),\n", - " array([ 0.00867059, -0.01026122, 0.86379338, 0.05346953, -0.04894238,\n", - " -0.59018798, 0.80400485, 1.3562344 , -0.1672647 , 1.64197677,\n", - " 1.93034605, -0.12060296, -0.20747621, 0.14870916, 0.57758495,\n", - " 3.11393475, 0.95237829, -0.66211333, -4.50978504, 5.07961652,\n", - " -0.91842167, -0.48505247, -0.49879536, -0.56632861, -0.40078151]),\n", - " array([ 0.02667635, -0.00959095, 0.97004453, 0.06238672, -0.06374218,\n", - " -0.63236449, 0.76951932, 1.48897156, -0.18960439, 1.63060646,\n", - " 1.91606496, -0.13475645, -0.21443472, 0.11379098, 0.68812144,\n", - " 2.03954383, 0.62769501, -0.42340064, -2.15750089, 2.65474331,\n", - " -0.44679381, -0.22740607, -0.28562172, -0.28306985, -0.1391703 ]),\n", - " array([ 0.04727513, -0.00825965, 1.04394351, 0.06682622, -0.07184675,\n", - " -0.65037789, 0.75324691, 1.55886051, -0.20070219, 1.62457616,\n", - " 1.90587799, -0.14200632, -0.21653065, 0.07310845, 0.67733473,\n", - " 1.37507282, 0.33636966, -0.22363634, -0.95727276, 1.39777882,\n", - " -0.22195598, -0.12060601, -0.2037394 , -0.14499747, -0.04191861]),\n", - " array([ 0.06792217, -0.00662292, 1.095446 , 0.06809064, -0.07493078,\n", - " -0.65739137, 0.74671656, 1.59761569, -0.20620774, 1.62068612,\n", - " 1.89713287, -0.14600968, -0.21679865, 0.04545764, 0.60847568,\n", - " 0.92752 , 0.11563035, -0.09754393, -0.37659948, 0.7751036 ,\n", - " -0.11011114, -0.07780085, -0.1749025 , -0.08006722, -0.00535991]),\n", - " array([ 0.08700481, -0.0048637 , 1.13083636, 0.06701783, -0.07445228,\n", - " -0.65948193, 0.74501614, 1.62108627, -0.20907217, 1.61746549,\n", - " 1.88876294, -0.1486948 , -0.21635773, 0.02745424, 0.51631686,\n", - " 0.61688863, -0.04626031, -0.02470843, -0.10524384, 0.46941177,\n", - " -0.05728854, -0.06441265, -0.16739864, -0.05370228, 0.00881837]),\n", - " array([ 0.10353608, -0.00306959, 1.15441798, 0.06430428, -0.07155822,\n", - " -0.65944463, 0.7455717 , 1.63693813, -0.21074387, 1.61423813,\n", - " 1.88042852, -0.15102388, -0.21565606, 0.01439063, 0.4177697 ,\n", - " 0.39787037, -0.15858766, 0.01641798, 0.01608986, 0.31703701,\n", - " -0.03343394, -0.06454713, -0.16668827, -0.0465817 , 0.0140334 ]),\n", - " array([ 1.16954483e-01, -1.28567219e-03, 1.16934941e+00, 6.05718981e-02,\n", - " -6.71807434e-02, -6.58547408e-01, 7.47083064e-01, 1.64880892e+00,\n", - " -2.11886693e-01, 1.61077683e+00, 1.87217494e+00, -1.53369531e-01,\n", - " -2.14890762e-01, 3.63424959e-03, 3.21207460e-01, 2.43490883e-01,\n", - " -2.28099133e-01, 3.87308923e-02, 6.60483401e-02, 2.37415891e-01,\n", - " -2.28565069e-02, -6.92260615e-02, -1.65071707e-01, -4.69129804e-02,\n", - " 1.53059754e-02]),\n", - " array([ 1.26986888e-01, 4.58431246e-04, 1.17809203e+00, 5.63680622e-02,\n", - " -6.20924176e-02, -6.57348708e-01, 7.48905768e-01, 1.65839249e+00,\n", - " -2.12781717e-01, 1.60711309e+00, 1.86423796e+00, -1.55762190e-01,\n", - " -2.14156997e-01, -5.89297752e-03, 2.30591438e-01, 1.37272305e-01,\n", - " -2.60857839e-01, 4.91217964e-02, 8.28035861e-02, 1.91671490e-01,\n", - " -1.79004723e-02, -7.32747013e-02, -1.58739549e-01, -4.78531746e-02,\n", - " 1.46752893e-02]),\n", - " array([ 0.13355502, 0.0021378 , 1.1826134 , 0.05215715, -0.05692673,\n", - " -0.65608376, 0.75072837, 1.6664573 , -0.21353399, 1.60340835,\n", - " 1.85691585, -0.15806263, -0.21350386, -0.01454619, 0.14736974,\n", - " 0.06806132, -0.26293908, 0.05140241, 0.08462864, 0.16129607,\n", - " -0.01504551, -0.07409485, -0.14644219, -0.04600889, 0.01306268]),\n", - " array([ 0.13670671, 0.00372954, 1.18445944, 0.04830977, -0.05217919,\n", - " -0.65484719, 0.75240857, 1.6733396 , -0.21417456, 1.5998651 ,\n", - " 1.85048588, -0.16007884, -0.21295589, -0.02244883, 0.07150725,\n", - " 0.02706784, -0.24081629, 0.04800245, 0.08008366, 0.137646 ,\n", - " -0.01281129, -0.07086501, -0.12859949, -0.04032421, 0.01095954]),\n", - " array([ 0.13656066, 0.00521332, 1.1847744 , 0.04509179, -0.04820081,\n", - " -0.65367786, 0.75388903, 1.67918183, -0.21470878, 1.5966692 ,\n", - " 1.8451536 , -0.16164123, -0.21252175, -0.02969929, 0.00213193,\n", - " 0.00650072, -0.20147978, 0.04079307, 0.07300044, 0.11684456,\n", - " -0.01068453, -0.06391793, -0.10664555, -0.03124761, 0.00868266]),\n", - " array([ 1.33261617e-01, 6.57268152e-03, 1.18431879e+00, 4.26573791e-02,\n", - " -4.51936195e-02, -6.52596567e-01, 7.55152703e-01, 1.68404751e+00,\n", - " -2.15137662e-01, 1.59395651e+00, 1.84102603e+00, -1.62646965e-01,\n", - " -2.12198654e-01, -3.64270077e-02, -6.20337654e-02, -7.48049971e-04,\n", - " -1.52235463e-01, 3.14174343e-02, 6.49184637e-02, 9.73136577e-02,\n", - " -8.57757754e-03, -5.42539498e-02, -8.25513641e-02, -2.01147889e-02,\n", - " 6.46196784e-03]),\n", - " array([ 1.26946539e-01, 7.79584497e-03, 1.18351162e+00, 4.10491231e-02,\n", - " -4.32139920e-02, -6.51621714e-01, 7.56198824e-01, 1.68797592e+00,\n", - " -2.15465646e-01, 1.59179834e+00, 1.83810212e+00, -1.63081266e-01,\n", - " -2.11975356e-01, -4.27872828e-02, -1.22391810e-01, -8.28652967e-04,\n", - " -1.00277930e-01, 2.13696868e-02, 5.62838741e-02, 7.85682039e-02,\n", - " -6.55968935e-03, -4.31633282e-02, -5.84782951e-02, -8.68602060e-03,\n", - " 4.46596916e-03]),\n", - " array([ 1.17722827e-01, 8.87571018e-03, 1.18250364e+00, 4.02058296e-02,\n", - " -4.21850196e-02, -6.50775349e-01, 7.57030621e-01, 1.69100668e+00,\n", - " -2.15702127e-01, 1.59020162e+00, 1.83627589e+00, -1.63021020e-01,\n", - " -2.11834966e-01, -4.89384333e-02, -1.80295055e-01, 1.53459755e-03,\n", - " -5.22307437e-02, 1.19714922e-02, 4.70496601e-02, 6.06152679e-02,\n", - " -4.72961508e-03, -3.19343115e-02, -3.65245204e-02, 1.20492609e-03,\n", - " 2.80779397e-03]),\n", - " array([ 1.05658110e-01, 9.80915041e-03, 1.18127340e+00, 3.99756448e-02,\n", - " -4.19152213e-02, -6.50085191e-01, 7.57650517e-01, 1.69318865e+00,\n", - " -2.15860164e-01, 1.58911994e+00, 1.83534887e+00, -1.62625163e-01,\n", - " -2.11757587e-01, -5.50165280e-02, -2.36935657e-01, 3.40162411e-03,\n", - " -1.38257695e-02, 4.33382818e-03, 3.69898731e-02, 4.36394039e-02,\n", - " -3.16074149e-03, -2.16336105e-02, -1.85404038e-02, 7.91713829e-03,\n", - " 1.54758211e-03]),\n", - " array([ 9.07808811e-02, 1.05959671e-02, 1.17972046e+00, 4.01319669e-02,\n", - " -4.21203818e-02, -6.49584562e-01, 7.58060153e-01, 1.69457923e+00,\n", - " -2.15954388e-01, 1.58846990e+00, 1.83504695e+00, -1.62116325e-01,\n", - " -2.11722816e-01, -6.11103545e-02, -2.93254824e-01, 3.49340094e-03,\n", - " 1.02567166e-02, -6.65371462e-04, 2.58899977e-02, 2.78115449e-02,\n", - " -1.88447013e-03, -1.30008275e-02, -6.03832220e-03, 1.01767567e-02,\n", - " 6.95429553e-04]),\n", - " array([ 7.31458905e-02, 1.12407397e-02, 1.17726313e+00, 4.03944572e-02,\n", - " -4.24518001e-02, -6.49310750e-01, 7.58262278e-01, 1.69523882e+00,\n", - " -2.16000820e-01, 1.58812739e+00, 1.83502165e+00, -1.61768016e-01,\n", - " -2.11711788e-01, -6.72373983e-02, -3.49852351e-01, -7.83018584e-03,\n", - " 1.67075601e-02, -2.44892537e-03, 1.36442919e-02, 1.31917639e-02,\n", - " -9.28638165e-04, -6.85029201e-03, -5.06103278e-04, 6.96617765e-03,\n", - " 2.20553509e-04]),\n", - " array([ 5.55212934e-02, 1.18846337e-02, 1.15028081e+00, 4.06569360e-02,\n", - " -4.27832013e-02, -6.49036746e-01, 7.58464181e-01, 1.69589838e+00,\n", - " -2.16047785e-01, 1.58778488e+00, 1.83499634e+00, -1.61419707e-01,\n", - " -2.11700732e-01, -7.33248265e-02, -4.06901338e-01, -4.94661057e-01,\n", - " 1.67074566e-02, -2.44877678e-03, 1.36443350e-02, 1.31912728e-02,\n", - " -9.39314827e-04, -6.85020031e-03, -5.06135132e-04, 6.96617262e-03,\n", - " 2.21115902e-04])],\n", - " [array([73.31311221, 89.54317897, 70.15035367, 53.01906275, 31.14853182,\n", - " -4.58457632, -4.21939376, -3.28976583, -2.34912815, -2.56993469]),\n", - " array([-20.96677807, -36.10120937, -22.93535653, -22.02546588,\n", - " -9.48365654, 1.02099415, 2.08063019, 1.27029142,\n", - " 0.60629532, 1.09480525]),\n", - " array([-10.80616632, -18.15177961, -10.29394147, -5.86507128,\n", - " -10.02351238, 0.18575567, 0.8500055 , 0.6871426 ,\n", - " 0.46018017, 0.98905117]),\n", - " array([-5.01555855, -7.11863201, -5.13583246, 0.47347274, -5.83432046,\n", - " 0.48719645, 0.16921048, 0.17903738, 0.14619236, 0.34068169]),\n", - " array([-1.81014129, -2.47911897, -2.29206602, 1.8203355 , -2.98200078,\n", - " 0.40003903, 0.06784759, 0.07606747, 0.06794457, 0.09823517]),\n", - " array([ 0.11711936, -0.35938356, -0.47384594, 2.09523737, -1.4594199 ,\n", - " 0.22774331, 0.06770523, 0.06199525, 0.0504948 , 0.03012877]),\n", - " array([ 1.30710893, 0.86576737, 0.75227682, 2.31136296, -0.70185548,\n", - " 0.11365101, 0.06389094, 0.05220085, 0.03891677, 0.01056189]),\n", - " array([ 2.03895858, 1.68096641, 1.60426154, 2.53503256, -0.33489837,\n", - " 0.05336425, 0.04969197, 0.03850675, 0.02702695, 0.00418002]),\n", - " array([ 2.51484327e+00, 2.27159472e+00, 2.22803779e+00, 2.75271176e+00,\n", - " -1.59529705e-01, 2.36580357e-02, 3.25558285e-02, 2.49294003e-02,\n", - " 1.67789483e-02, 1.81628741e-03]),\n", - " array([ 2.85205435e+00, 2.72460004e+00, 2.70833754e+00, 2.95657219e+00,\n", - " -7.65895065e-02, 9.26047902e-03, 1.70949941e-02, 1.38942310e-02,\n", - " 9.18632238e-03, 8.81109096e-04]),\n", - " array([ 3.10628901e+00, 3.08044883e+00, 3.08649201e+00, 3.13933946e+00,\n", - " -3.78231053e-02, 2.30284847e-03, 4.73602411e-03, 5.74320084e-03,\n", - " 4.01681500e-03, 5.04632008e-04]),\n", - " array([ 3.30030921e+00, 3.35560879e+00, 3.37899729e+00, 3.29372262e+00,\n", - " -1.99673011e-02, -9.78743151e-04, -4.41252105e-03, 6.52372659e-05,\n", - " 6.73281570e-04, 3.45843215e-04]),\n", - " array([ 3.44286515e+00, 3.55602919e+00, 3.59137528e+00, 3.41443206e+00,\n", - " -1.18464317e-02, -2.36620225e-03, -1.05369585e-02, -3.58955146e-03,\n", - " -1.35469871e-03, 2.63248796e-04]),\n", - " array([ 3.53923346e+00, 3.68593872e+00, 3.72753548e+00, 3.50010801e+00,\n", - " -8.10061953e-03, -2.73350220e-03, -1.38496532e-02, -5.55479744e-03,\n", - " -2.41455568e-03, 2.01267280e-04]),\n", - " array([ 3.59638169e+00, 3.75281537e+00, 3.79502924e+00, 3.55432316e+00,\n", - " -6.16948792e-03, -2.54176492e-03, -1.45963111e-02, -6.08896092e-03,\n", - " -2.73982835e-03, 1.42173280e-04]),\n", - " array([ 3.62463136e+00, 3.76885637e+00, 3.80653123e+00, 3.58537452e+00,\n", - " -4.84931732e-03, -2.05220340e-03, -1.30584497e-02, -5.40276388e-03,\n", - " -2.48406254e-03, 8.31367175e-05]),\n", - " array([ 3.63705735e+00, 3.74976681e+00, 3.77846186e+00, 3.60497454e+00,\n", - " -3.61759997e-03, -1.41116157e-03, -9.48261424e-03, -3.62488965e-03,\n", - " -1.70907553e-03, 2.46370804e-05]),\n", - " array([ 3.64592489e+00, 3.71082244e+00, 3.72695008e+00, 3.62443823e+00,\n", - " -2.36944256e-03, -6.90309154e-04, -4.09873764e-03, -8.39841467e-04,\n", - " -4.23017391e-04, -3.35345754e-05]),\n", - " array([ 3.58659503e+00, 3.59345573e+00, 3.59509465e+00, 3.57778944e+00,\n", - " -1.35828234e-03, 2.09598015e-05, 1.98145545e-03, 2.13912798e-03,\n", - " 8.59804174e-04, -8.04109323e-05]),\n", - " array([ 8.76869348e-08, -1.06208173e-07, -4.56167150e-08, 5.66103164e-08,\n", - " 1.22935923e-10, 6.21020052e-10, 1.49192224e-10, -7.99966095e-10,\n", - " -4.29309670e-11, 1.17057616e-09])],\n", + " array([ 9.15453549e-07, -8.17547458e-08, 1.30947392e-02, 8.35006620e-06,\n", + " 8.60137935e-05, -4.24374481e-06, 9.99999996e-01, -1.50043464e-05,\n", + " 1.99911457e-01, 1.70000828e+00, 1.99669663e+00, 4.01452361e-03,\n", + " -3.76771300e-04, -4.21748902e-06, 5.51789701e-07, 2.61894784e-01,\n", + " 3.34002649e-04, 3.44055174e-03, -1.69749792e-04, -3.00086928e-04,\n", + " -1.77085415e-03, 1.65524087e-04, -6.60674902e-02, 8.02904722e-02,\n", + " -7.53542600e-03]),\n", + " array([ 8.44458709e-06, -7.91156753e-07, 3.83889211e-02, 1.31431254e-05,\n", + " 1.39726592e-04, -5.60633936e-06, 9.99999990e-01, -3.89457229e-05,\n", + " 1.99779194e-01, 1.69955747e+00, 1.99323578e+00, 7.59111178e-03,\n", + " -7.10822661e-04, 3.63843869e-05, -3.31405886e-06, 5.05883660e-01,\n", + " 1.91717941e-04, 2.14851230e-03, -5.45052325e-05, -4.78827531e-04,\n", + " -2.64526105e-03, -9.01621182e-03, -6.92169479e-02, 7.15317634e-02,\n", + " -6.68102722e-03]),\n", + " array([ 2.53863288e-05, -2.38345920e-06, 7.51010581e-02, 1.46993826e-05,\n", + " 1.57587166e-04, -4.76313690e-06, 9.99999987e-01, -6.75916495e-05,\n", + " 1.99610380e-01, 1.69870477e+00, 1.98965054e+00, 1.07444600e-02,\n", + " -1.00458692e-03, 1.20534577e-04, -1.14005086e-05, 7.34242809e-01,\n", + " 6.22415685e-05, 7.14423762e-04, 3.37274059e-05, -5.72918531e-04,\n", + " -3.37629096e-03, -1.70538455e-02, -7.17046862e-02, 6.30669642e-02,\n", + " -5.87528519e-03]),\n", + " array([ 5.21579849e-05, -4.89393107e-06, 1.22560305e-01, 1.33588529e-05,\n", + " 1.42914614e-04, -3.25889123e-06, 9.99999990e-01, -9.83970986e-05,\n", + " 1.99411384e-01, 1.69750881e+00, 1.98598382e+00, 1.35050382e-02,\n", + " -1.26120274e-03, 2.50201632e-04, -2.35738260e-05, 9.49185064e-01,\n", + " -5.36278746e-05, -5.86901452e-04, 6.01700036e-05, -6.16108983e-04,\n", + " -3.97991591e-03, -2.39192675e-02, -7.33345002e-02, 5.52115642e-02,\n", + " -5.13231646e-03]),\n", + " array([ 8.69838008e-05, -8.16117333e-06, 1.80202130e-01, 9.25937463e-06,\n", + " 9.73764114e-05, -1.95545625e-06, 9.99999995e-01, -1.29796419e-04,\n", + " 1.99187336e-01, 1.69601783e+00, 1.98227114e+00, 1.58984513e-02,\n", + " -1.48322258e-03, 4.19500311e-04, -3.92668045e-05, 1.15283662e+00,\n", + " -1.63980647e-04, -1.82152795e-03, 5.21382976e-05, -6.27986413e-04,\n", + " -4.48094902e-03, -2.98196724e-02, -7.42534847e-02, 4.78682623e-02,\n", + " -4.44039666e-03]),\n", + " array([ 1.26043593e-04, -1.18398260e-05, 2.47562844e-01, 2.40632538e-06,\n", + " 2.13379966e-05, -1.17970736e-06, 1.00000000e+00, -1.60967479e-04,\n", + " 1.98942383e-01, 1.69427121e+00, 1.97854143e+00, 1.79457397e-02,\n", + " -1.67273200e-03, 6.21262306e-04, -5.78546434e-05, 1.34721436e+00,\n", + " -2.74119045e-04, -3.04153685e-03, 3.10314258e-05, -6.23421196e-04,\n", + " -4.89907176e-03, -3.49323086e-02, -7.45942298e-02, 4.09457683e-02,\n", + " -3.79018849e-03]),\n", + " array([ 1.63525703e-04, -1.54026133e-05, 3.24273061e-01, -7.28868203e-06,\n", + " -8.56697865e-05, -8.85352119e-07, 9.99999996e-01, -1.91771296e-04,\n", + " 1.98679835e-01, 1.69230091e+00, 1.97481802e+00, 1.96640860e-02,\n", + " -1.83141481e-03, 8.48340457e-04, -7.87446219e-05, 1.53420431e+00,\n", + " -3.87795499e-04, -4.28031176e-03, 1.17762344e-05, -6.16076340e-04,\n", + " -5.25096419e-03, -3.94059683e-02, -7.44682709e-02, 3.43669261e-02,\n", + " -3.17365619e-03]),\n", + " array([ 1.91594455e-04, -1.81335512e-05, 4.10050131e-01, -1.99937178e-05,\n", + " -2.24776445e-04, -6.76535055e-07, 9.99999975e-01, -2.22620718e-04,\n", + " 1.98402233e-01, 1.69013211e+00, 1.97111917e+00, 2.10671597e-02,\n", + " -1.96059008e-03, 1.09395850e-03, -1.01421539e-04, 1.71554114e+00,\n", + " -5.08195797e-04, -5.56426691e-03, 8.35566312e-06, -6.16988446e-04,\n", + " -5.55204215e-03, -4.33759524e-02, -7.39770172e-02, 2.80614729e-02,\n", + " -2.58350541e-03]),\n", + " array([ 2.00273533e-04, -1.91127838e-05, 5.04689572e-01, -3.59620750e-05,\n", + " -3.97878591e-04, 2.40627410e-07, 9.99999920e-01, -2.54438316e-04,\n", + " 1.98111342e-01, 1.68778324e+00, 1.96745803e+00, 2.21650735e-02,\n", + " -2.06121516e-03, 1.35213601e-03, -1.25496763e-04, 1.89278835e+00,\n", + " -6.38721387e-04, -6.92408735e-03, 3.66916306e-05, -6.36351945e-04,\n", + " -5.81780506e-03, -4.69775378e-02, -7.32226766e-02, 2.19582764e-02,\n", + " -2.01250165e-03]),\n", + " array([ 1.77143813e-04, -1.71912226e-05, 6.08055553e-01, -5.55659620e-05,\n", + " -6.08863686e-04, 3.45317792e-06, 9.99999813e-01, -2.88327936e-04,\n", + " 1.97808050e-01, 1.68526378e+00, 1.96384034e+00, 2.29624876e-02,\n", + " -2.13387854e-03, 1.61866347e-03, -1.50788383e-04, 2.06731906e+00,\n", + " -7.84106477e-04, -8.43940932e-03, 1.28510512e-04, -6.77792414e-04,\n", + " -6.06584875e-03, -5.03891684e-02, -7.23539822e-02, 1.59482816e-02,\n", + " -1.45326750e-03]),\n", + " array([ 1.04962345e-04, -1.08463084e-05, 7.20070423e-01, -8.03171492e-05,\n", + " -8.81947327e-04, 1.55247914e-05, 9.99999608e-01, -3.23369896e-04,\n", + " 1.97489139e-01, 1.68253927e+00, 1.96022756e+00, 2.34296678e-02,\n", + " -2.17766370e-03, 1.89623102e-03, -1.77523427e-04, 2.24029708e+00,\n", + " -9.89791494e-04, -1.09233722e-02, 4.82860321e-04, -7.00839199e-04,\n", + " -6.37821815e-03, -5.44901111e-02, -7.22554155e-02, 9.34360403e-03,\n", + " -8.75703143e-04]),\n", + " array([ 6.52796299e-05, -7.12713477e-06, 8.16248830e-01, -6.64954115e-05,\n", + " -6.93167922e-04, 2.09839085e-05, 9.99999757e-01, -3.68384571e-04,\n", + " 1.97145600e-01, 1.67961352e+00, 1.95666708e+00, 2.36186506e-02,\n", + " -2.18902407e-03, 2.23618483e-03, -2.08047162e-04, 1.92356701e+00,\n", + " 5.53179591e-04, 7.55115244e-03, 2.18483395e-04, -9.00293490e-04,\n", + " -6.87077739e-03, -5.85151021e-02, -7.12095991e-02, 3.77965685e-03,\n", + " -2.27207526e-04]),\n", + " array([ 2.34565078e-05, -3.29712932e-06, 8.88558068e-01, -4.83337131e-05,\n", + " -4.57860912e-04, 2.45501002e-05, 9.99999894e-01, -3.92581733e-04,\n", + " 1.96818589e-01, 1.67679680e+00, 1.95334416e+00, 2.36356771e-02,\n", + " -2.18876829e-03, 8.28137902e-04, -8.94640630e-05, 1.44618477e+00,\n", + " 7.26764514e-04, 9.41225725e-03, 1.42769828e-04, -4.83943252e-04,\n", + " -6.54021286e-03, -5.63343704e-02, -6.64585605e-02, 3.40529375e-04,\n", + " 5.11568317e-06]),\n", + " array([-1.98476079e-05, 7.21840321e-07, 9.37000624e-01, -2.35643747e-05,\n", + " -1.20634090e-04, 1.61911718e-05, 9.99999992e-01, -4.01778324e-04,\n", + " 1.96515429e-01, 1.67420123e+00, 1.95036670e+00, 2.35645257e-02,\n", + " -2.17985824e-03, -3.05604768e-04, 1.07451568e-05, 9.68851484e-01,\n", + " 9.90951711e-04, 1.34890653e-02, -3.34158864e-04, -1.83931812e-04,\n", + " -6.06320286e-03, -5.19113196e-02, -5.95492256e-02, -1.42302862e-03,\n", + " 1.78201000e-04]),\n", + " array([-7.25001916e-05, 5.03842363e-06, 9.61750817e-01, 1.53571106e-05,\n", + " 1.65499397e-04, 1.17083374e-05, 9.99999986e-01, -4.05003268e-04,\n", + " 1.96241305e-01, 1.67200654e+00, 1.94786068e+00, 2.34871697e-02,\n", + " -2.16858571e-03, -1.07525782e-03, 8.22988361e-05, 4.95003818e-01,\n", + " 1.55702310e-03, 1.14453186e-02, -1.79231482e-04, -6.44988795e-05,\n", + " -5.48248271e-03, -4.38939046e-02, -5.01202360e-02, -1.54711941e-03,\n", + " 2.25450517e-04]),\n", + " array([-1.25966706e-04, 9.70951942e-06, 9.76047122e-01, 2.28783326e-05,\n", + " 2.49602102e-04, 7.23998397e-06, 9.99999969e-01, -3.97897787e-04,\n", + " 1.96038034e-01, 1.67029722e+00, 1.94588147e+00, 2.34380704e-02,\n", + " -2.16453653e-03, -1.18801667e-03, 1.04375823e-04, 2.85925633e-01,\n", + " 3.00917856e-04, 3.36410199e-03, -1.78735998e-04, 1.42109621e-04,\n", + " -4.06542551e-03, -3.41863272e-02, -3.95841978e-02, -9.81985622e-04,\n", + " 8.09835987e-05]),\n", + " array([-1.71008727e-04, 1.36052174e-05, 9.84544679e-01, 2.35339568e-05,\n", + " 2.66060098e-04, 4.79115449e-06, 9.99999964e-01, -3.91307359e-04,\n", + " 1.95889539e-01, 1.66902732e+00, 1.94440767e+00, 2.34086742e-02,\n", + " -2.16276802e-03, -9.88476695e-04, 8.58131361e-05, 1.69950646e-01,\n", + " 2.62541858e-05, 6.58317447e-04, -9.79616901e-05, 1.31808552e-04,\n", + " -2.96990570e-03, -2.53980011e-02, -2.94760998e-02, -5.87923866e-04,\n", + " 3.53702751e-05]),\n", + " array([-2.05068278e-04, 1.65208501e-05, 9.89406963e-01, 2.19632552e-05,\n", + " 2.55780026e-04, 1.40928240e-06, 9.99999967e-01, -3.80551223e-04,\n", + " 1.95790362e-01, 1.66816578e+00, 1.94341223e+00, 2.33794509e-02,\n", + " -2.16185183e-03, -7.31937255e-04, 6.27414330e-05, 9.72453073e-02,\n", + " -6.27940398e-05, -4.11205781e-04, -1.35281918e-04, 2.15122732e-04,\n", + " -1.98353879e-03, -1.72308292e-02, -1.99088077e-02, -5.84467149e-04,\n", + " 1.83238646e-05]),\n", + " array([-2.27697059e-04, 1.84504725e-05, 9.92009525e-01, 2.20873887e-05,\n", + " 2.70292701e-04, -9.01801361e-06, 9.99999963e-01, -3.55093564e-04,\n", + " 1.95736590e-01, 1.66766136e+00, 1.94285023e+00, 2.33176777e-02,\n", + " -2.16093072e-03, -4.79958588e-04, 4.08817878e-05, 5.20509879e-02,\n", + " 5.07284351e-06, 5.80497858e-04, -4.17103306e-04, 5.09153177e-04,\n", + " -1.07542461e-03, -1.00883357e-02, -1.12399537e-02, -1.23546410e-03,\n", + " 1.84220312e-05]),\n", + " array([-2.35785219e-04, 1.91913469e-05, 9.99945701e-01, 2.92455713e-08,\n", + " 3.69993748e-07, 3.36718673e-10, 1.00000000e+00, -3.72678236e-04,\n", + " 1.95638123e-01, 1.66648454e+00, 1.94232154e+00, 2.32885184e-02,\n", + " -2.14547024e-03, -2.04723877e-04, 1.83263302e-05, 1.58723471e-01,\n", + " -8.82325873e-04, -1.07969084e-02, 3.60734007e-04, -3.51693455e-04,\n", + " -1.96935025e-03, -2.35364172e-02, -1.05738597e-02, -5.83184283e-04,\n", + " 3.09209753e-04])],\n", + " [array([ 5.65633346e+00, 5.69538965e+00, 5.65819681e+00, 5.69129248e+00,\n", + " 2.11564086e-03, -6.78348698e-04, -8.94345265e-03, -8.40371427e-03,\n", + " 4.97581206e-03, -1.18114125e-03]),\n", + " array([ 5.52456276e+00, 5.55697096e+00, 5.52600268e+00, 5.55344661e+00,\n", + " 2.16466466e-03, -8.56192054e-04, -1.12496844e-02, -9.77185618e-03,\n", + " -8.03198793e-03, 3.31075512e-04]),\n", + " array([ 5.40957090e+00, 5.43610515e+00, 5.41063838e+00, 5.43309041e+00,\n", + " 2.00868664e-03, -7.12960682e-04, -9.69475082e-03, -8.46687244e-03,\n", + " -7.10296470e-03, 2.79669209e-04]),\n", + " array([ 5.31092114e+00, 5.33226600e+00, 5.31168074e+00, 5.32972449e+00,\n", + " 1.80033452e-03, -5.84526521e-04, -8.08046518e-03, -7.05422349e-03,\n", + " -6.05875850e-03, 2.34849818e-04]),\n", + " array([ 5.22798844e+00, 5.24477729e+00, 5.22849505e+00, 5.24267120e+00,\n", + " 1.59389702e-03, -4.75790037e-04, -6.70567123e-03, -5.85451480e-03,\n", + " -5.17284099e-03, 1.99852687e-04]),\n", + " array([ 5.15997083e+00, 5.17279682e+00, 5.16027103e+00, 5.17108637e+00,\n", + " 1.39557071e-03, -3.83848147e-04, -5.54733693e-03, -4.84755855e-03,\n", + " -4.43066362e-03, 1.72740567e-04]),\n", + " array([ 5.10589930e+00, 5.11532268e+00, 5.10603436e+00, 5.11396776e+00,\n", + " 1.20647200e-03, -3.06878993e-04, -4.57949698e-03, -4.00911333e-03,\n", + " -3.81382209e-03, 1.52431298e-04]),\n", + " array([ 5.06464568e+00, 5.07119987e+00, 5.06465446e+00, 5.07016176e+00,\n", + " 1.02695882e-03, -2.43922804e-04, -3.78824788e-03, -3.32645930e-03,\n", + " -3.31270647e-03, 1.38308819e-04]),\n", + " array([ 5.03492881e+00, 5.03912586e+00, 5.03485010e+00, 5.03836858e+00,\n", + " 8.55733010e-04, -1.94721413e-04, -3.17103769e-03, -2.79791559e-03,\n", + " -2.92624412e-03, 1.30288783e-04]),\n", + " array([ 5.01531865e+00, 5.01765458e+00, 5.01519366e+00, 5.01714635e+00,\n", + " 6.97138171e-04, -1.59954681e-04, -2.76759995e-03, -2.46452955e-03,\n", + " -2.68737159e-03, 1.28406860e-04]),\n", + " array([ 5.00423821e+00, 5.00519593e+00, 5.00411710e+00, 5.00491480e+00,\n", + " 6.48924928e-04, -1.67905829e-04, -3.24517252e-03, -3.00214782e-03,\n", + " -3.13305665e-03, 1.39532955e-04]),\n", + " array([ 1.24627814e+00, 1.37576951e+00, 1.25639793e+00, 1.36450165e+00,\n", + " 9.63921274e-04, -2.20031092e-03, -1.97043232e-02, -1.52898345e-02,\n", + " -1.11809626e-02, 9.37139894e-04]),\n", + " array([ 9.90312448e-02, 9.88204240e-02, 9.90333779e-02, 9.88657631e-02,\n", + " -1.00189462e-04, 1.27527683e-04, 1.73218487e-03, 1.67947447e-03,\n", + " 6.68626476e-04, 1.02656959e-05]),\n", + " array([ 9.94128016e-02, 9.91269144e-02, 9.94671212e-02, 9.92436448e-02,\n", + " -5.03069193e-04, 1.93977115e-04, 3.79339379e-03, 3.73830741e-03,\n", + " 2.29264691e-03, 3.04118211e-06]),\n", + " array([ 1.50082657e-01, 9.98483242e-02, 1.52631689e-01, 9.99011198e-02,\n", + " -2.49401556e-03, 1.77699800e-05, 1.40781492e-02, 1.20705052e-02,\n", + " 8.16684965e-03, -3.05900047e-05]),\n", + " array([ 2.17561287e+00, 2.06862914e+00, 2.16494467e+00, 2.08193137e+00,\n", + " -2.63361010e-03, 2.79490984e-03, 2.15928246e-02, 1.80449043e-02,\n", + " 1.22324122e-02, -7.41522012e-04]),\n", + " array([ 2.85797242e+00, 2.79070888e+00, 2.85405672e+00, 2.79746263e+00,\n", + " -2.78181291e-03, 1.44387954e-03, 1.63234790e-02, 1.39942765e-02,\n", + " 9.43227761e-03, -3.22577819e-04]),\n", + " array([ 3.17771052e+00, 3.12400241e+00, 3.17494042e+00, 3.12906870e+00,\n", + " -2.32216013e-03, 1.13927628e-03, 1.40099668e-02, 1.21307167e-02,\n", + " 8.10148341e-03, -2.47452341e-04]),\n", + " array([ 3.37652257e+00, 3.34074517e+00, 3.37437021e+00, 3.34413824e+00,\n", + " -1.43688486e-03, 8.96961386e-04, 1.06302367e-02, 9.37602731e-03,\n", + " 6.13520826e-03, -2.02755932e-04]),\n", + " array([ 4.52281082e+00, 4.48585809e+00, 4.52110011e+00, 4.48812757e+00,\n", + " -1.72466702e-05, -7.29908502e-06, -2.15857077e-04, 1.19563289e-04,\n", + " -1.42328739e-05, 1.82883633e-06])],\n", " True)" ] }, - "execution_count": 25, + "execution_count": 37, "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 = 5e-2\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 = 20\n", + "T = int(1/dt)\n", "q0 = rmodel.referenceConfigurations[\"centered\"].copy()\n", "v0 = pin.utils.zero(rmodel.nv)\n", "x0 = m2a(np.concatenate([q0, v0]))\n", @@ -399,7 +431,7 @@ }, { "cell_type": "code", - "execution_count": 26, + "execution_count": 41, "metadata": {}, "outputs": [], "source": [ @@ -408,87 +440,39 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": 44, "metadata": {}, "outputs": [ { - "ename": "ValueError", - "evalue": "could not broadcast input array from shape (20) into shape (10)", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mValueError\u001b[0m Traceback (most recent call last)", - "\u001b[0;32m<ipython-input-27-83867ff4d1ba>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[0;32m----> 1\u001b[0;31m \u001b[0mpltUAM\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mPlotUAM\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mfddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mxs\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mfddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mus\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mT\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdistanceRotorCOG\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcf\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcm\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 2\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 3\u001b[0m \u001b[0mfig\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mpltUAM\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplotMotorForces\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/plots.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, stateTraj, controlTraj, knots, dt, d, cf, cm)\u001b[0m\n\u001b[1;32m 11\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcf\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mcf\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 12\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcm\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mcm\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 13\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mPlotDataType\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mPlotDataUAM\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 14\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 15\u001b[0m \u001b[0;32mdef\u001b[0m \u001b[0mplotMotorForces\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/plots.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, model)\u001b[0m\n\u001b[1;32m 52\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 53\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mzeros\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msize\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcontrol\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;36m3\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 54\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;36m0\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mMx\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 55\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mMy\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 56\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;36m2\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mMz\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;31mValueError\u001b[0m: could not broadcast input array from shape (20) into shape (10)" - ] + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 4 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" } ], "source": [ "pltUAM = PlotUAM(fddp.xs, fddp.us, T, dt, distanceRotorCOG, cf, cm)\n", "\n", - "fig, axs = pltUAM.plotMotorForces()\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import matplotlib.pyplot as plt\n", - "\n", - "fig,axs = pltUAM.plotActuation()\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import matplotlib.pyplot as plt\n", - "t = np.arange(0., 1, dt)\n", - "\n", - "fig, axs = plt.subplots(2,2, figsize=(15,10))\n", - "fig.suptitle('Motor forces')\n", - "axs[0, 0].plot(t,f1)\n", - "axs[0, 0].set_title('Motor 1')\n", - "axs[0, 1].plot(t,f2)\n", - "axs[0, 1].set_title('Motor 2')\n", - "axs[1, 0].plot(t,f3)\n", - "axs[1, 0].set_title('Motor 3')\n", - "axs[1, 1].plot(t,f4)\n", - "axs[1, 1].set_title('Motor 4')\n", - "\n", - "plt.figure()\n", - "t = np.append(t, 1)\n", - "plt.plot(t,Xx,t,Xy,t,Xz)\n", - "plt.legend(['x','y','z'])\n", - "plt.title('State - Position')\n", - "plt.ylabel('Position, [m]')\n", - "plt.xlabel('[s]')\n", - "\n", - "plt.figure()\n", - "plt.plot(t,Vx,t,Vy,t,Vz)\n", - "plt.legend(['x','y','z'])\n", - "plt.title('State - Velocity')\n", - "plt.ylabel('Velocity, [m/s]')\n", - "plt.xlabel('[s]')\n", - "\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "t = np.arange(0,T*dt,dt)\n", - "t_state = np.append(t, t[-1]+dt)\n", - "t_state" + "fig, axs = pltUAM.plotMotorForces()\n", + "fig,axs = pltUAM.plotActuation()" ] }, { @@ -515,7 +499,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4, diff --git a/examples/notebooks/kinton_flying_mission.ipynb b/examples/notebooks/kinton_flying_mission.ipynb index 733826adb45f3fab52447136e25e7186c8dda164..6eb8f24c7ebafee8ec0c08569d55f69b1f78caa3 100644 --- a/examples/notebooks/kinton_flying_mission.ipynb +++ b/examples/notebooks/kinton_flying_mission.ipynb @@ -52,7 +52,7 @@ " SE3ref.rotation = targetQuat.matrix()\n", "\n", " wBasePos = [1]\n", - " wBaseOri = [500]\n", + " wBaseOri = [1]\n", " wArmPos = [1]\n", " wBaseVel = [10]\n", " wBaseRate = [10]\n", @@ -84,7 +84,7 @@ " runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n", " runningCostModel.addCost(name=\"regx\", weight=1e-4, cost=xRegCost)\n", " runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n", - " #runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n", + " runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n", " terminalCostModel.addCost(name=\"pos\", weight=10, cost=goalTrackingCost)\n", "\n", " # DIFFERENTIAL ACTION MODEL\n", @@ -105,11 +105,11 @@ "# DEFINING THE SHOOTING PROBLEM & SOLVING\n", "\n", "# Defining the time duration for running action models and the terminal one\n", - "dt = 1e-2\n", + "dt = 5e-2\n", "\n", "# For this optimal control problem, we define 250 knots (or running action\n", "# models) plus a terminal knot\n", - "T = 50\n", + "T = 25\n", "\n", "\n", "# DEFINE POSITION WAYPOINTS\n", @@ -138,37 +138,26 @@ "output_type": "stream", "text": [ "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 3.51425e+00 1.27336e-04 1.22872e+01 1.00000e-09 1.00000e-09 0.5000 0\n", - " 1 2.32067e+00 4.16275e-05 3.89873e+00 1.00000e-09 1.00000e-09 0.5000 0\n", - " 2 1.17724e+00 5.80554e-05 2.00231e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - " 3 1.09163e+00 1.06224e-05 2.37892e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 4 1.06827e+00 1.78135e-06 7.83426e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 5 1.06011e+00 1.57027e-06 2.81042e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 6 1.05728e+00 1.83779e-07 1.06911e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 7 1.05611e+00 3.19838e-07 4.55371e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 8 1.05558e+00 3.47870e-08 2.19753e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 9 1.05530e+00 9.59146e-08 1.17187e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 0 5.67251e-01 4.20441e-02 8.76805e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 1 5.55684e-01 3.58469e-04 2.99271e-01 1.00000e-09 1.00000e-09 0.0625 1\n", + " 2 5.31309e-01 3.20341e-04 2.39454e-01 1.00000e-09 1.00000e-09 0.1250 1\n", + " 3 4.97230e-01 2.51906e-04 1.73594e-01 1.00000e-09 1.00000e-09 0.2500 1\n", + " 4 4.68044e-01 1.74315e-04 1.00853e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 5 4.65799e-01 6.36329e-05 5.31715e-02 1.00000e-09 1.00000e-09 0.5000 1\n", + " 6 4.51048e-01 5.56021e-05 4.73253e-02 1.00000e-09 1.00000e-09 0.5000 1\n", + " 7 4.44854e-01 2.33241e-05 1.81715e-02 1.00000e-09 1.00000e-09 0.5000 1\n", + " 8 4.44295e-01 1.05396e-05 6.67558e-03 1.00000e-09 1.00000e-09 0.1250 1\n", + " 9 4.42921e-01 7.87399e-06 4.86690e-03 1.00000e-09 1.00000e-09 1.0000 1\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 1.05514e+00 1.33286e-08 6.87744e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 11 1.05505e+00 3.73615e-08 4.35857e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 12 1.05499e+00 7.66134e-09 2.97648e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 13 1.05496e+00 1.79607e-08 2.15688e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 14 1.05493e+00 5.28123e-09 1.64650e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 15 1.05491e+00 1.02704e-08 1.30749e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 16 1.05490e+00 3.91971e-09 1.07069e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 17 1.05488e+00 6.66467e-09 8.96834e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 18 1.05487e+00 3.00024e-09 7.63338e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 19 1.05487e+00 4.68907e-09 6.57508e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 20 1.05486e+00 2.32762e-09 5.70767e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 21 1.05486e+00 3.45906e-09 4.98511e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 22 1.05485e+00 1.81663e-09 4.36968e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 23 1.05485e+00 2.62022e-09 3.84228e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 24 1.05484e+00 1.42137e-09 3.38379e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 25 1.05484e+00 2.01389e-09 2.98487e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 26 1.05484e+00 1.11298e-09 2.63449e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 27 1.05484e+00 1.56013e-09 2.32720e-05 1.00000e-09 1.00000e-09 1.0000 1\n", - " 28 1.05484e+00 8.71453e-10 2.05599e-05 1.00000e-09 1.00000e-09 1.0000 1\n" + " 10 4.42520e-01 4.38005e-06 3.31173e-03 1.00000e-09 1.00000e-09 0.2500 1\n", + " 11 4.41775e-01 2.86854e-06 2.17099e-03 1.00000e-09 1.00000e-09 0.5000 1\n", + " 12 4.41435e-01 1.02347e-06 6.58074e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 13 4.41416e-01 1.12909e-07 3.50598e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 14 4.41414e-01 5.37554e-08 1.54028e-05 1.00000e-09 1.00000e-09 0.2500 1\n", + " 15 4.41413e-01 2.96505e-08 7.30863e-06 1.00000e-09 1.00000e-09 0.5000 1\n", + " 16 4.41410e-01 9.54558e-09 3.97368e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 17 4.41410e-01 1.32501e-09 4.39187e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 18 4.41410e-01 8.83488e-10 2.60795e-07 1.00000e-09 1.00000e-09 1.0000 1\n" ] }, { @@ -176,996 +165,496 @@ "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([-8.31866622e-07, -3.25978404e-04, 7.24283918e-02, 4.63047162e-03,\n", - " -1.18178567e-05, 5.23085205e-08, 9.99989279e-01, -1.27197423e-06,\n", - " 5.68737200e-04, 4.60060741e-05, 2.97355493e-05, 1.39762510e-05,\n", - " 2.71695010e-04, 2.40795347e-06, 9.40273736e-04, 7.24293836e+00,\n", - " 9.26097633e-01, -2.36357979e-03, 1.04617415e-05, -1.27197423e-04,\n", - " 5.68737200e-02, 4.60060741e-03, 2.97355493e-03, 1.39762510e-03,\n", - " 2.71695010e-02]),\n", - " array([-2.17056282e-06, -1.84710123e-03, 1.69575435e-01, 1.81171485e-02,\n", - " -1.95111637e-05, 1.27774207e-06, 9.99835871e-01, -3.59344339e-06,\n", - " 1.00033350e-02, 9.57875415e-05, 6.85058127e-05, 3.88288910e-05,\n", - " 2.51552967e-03, 1.70445776e-04, 6.89062970e-02, 9.71594535e+00,\n", - " 2.69753033e+00, -1.53806035e-03, 2.20340373e-04, -2.32146916e-04,\n", - " 9.43459785e-01, 4.97814674e-03, 3.87702635e-03, 2.48526400e-03,\n", - " 2.24383466e-01]),\n", - " array([-3.28713098e-06, -3.89111420e-03, 2.70942109e-01, 3.43933137e-02,\n", - " -2.25735850e-05, 2.81880821e-06, 9.99408375e-01, -6.50413410e-06,\n", - " 1.99619344e-02, 1.37998102e-04, 1.03847345e-04, 6.35346217e-05,\n", - " 4.97181203e-03, 3.15256012e-04, 3.28010240e-01, 1.01338690e+01,\n", - " 3.25639163e+00, -6.12654409e-04, 2.55866275e-04, -2.91069071e-04,\n", - " 9.95859934e-01, 4.22105606e-03, 3.53415324e-03, 2.47057307e-03,\n", - " 2.45628237e-01]),\n", - " array([-3.88522924e-06, -5.55100420e-03, 3.67471544e-01, 5.02709364e-02,\n", - " -2.20949592e-05, 4.27432057e-06, 9.98735617e-01, -9.57795582e-06,\n", - " 2.78217813e-02, 1.70219289e-04, 1.31865410e-04, 8.39111246e-05,\n", - " 6.94154758e-03, 3.73007932e-04, 6.51185705e-01, 9.63279156e+00,\n", - " 3.17840730e+00, 9.36959495e-05, 2.16343351e-04, -3.07382172e-04,\n", - " 7.85984686e-01, 3.22211871e-03, 2.80180651e-03, 2.03765029e-03,\n", - " 1.96973555e-01]),\n", - " array([-3.95213360e-06, -6.10803764e-03, 4.55257242e-01, 6.41005580e-02,\n", - " -1.92972714e-05, 5.45324628e-06, 9.97943444e-01, -1.24197413e-05,\n", - " 3.31486196e-02, 1.93076377e-04, 1.52275929e-04, 9.91360942e-05,\n", - " 8.28838000e-03, 3.60541761e-04, 9.47090385e-01, 8.72779131e+00,\n", - " 2.77048038e+00, 5.55377932e-04, 1.46927459e-04, -2.84178553e-04,\n", - " 5.32683832e-01, 2.28570875e-03, 2.04105193e-03, 1.52249695e-03,\n", - " 1.34683242e-01]),\n", - " array([-3.60252851e-06, -5.11226723e-03, 5.32831412e-01, 7.50862824e-02,\n", - " -1.52232186e-05, 6.27804665e-06, 9.97177040e-01, -1.47536662e-05,\n", - " 3.62505855e-02, 2.08135461e-04, 1.66066471e-04, 1.09655390e-04,\n", - " 9.07874290e-03, 3.09351019e-04, 1.17576495e+00, 7.66860108e+00,\n", - " 2.20249624e+00, 8.08785763e-04, 7.08294205e-05, -2.33392488e-04,\n", - " 3.10196593e-01, 1.50590848e-03, 1.37905418e-03, 1.05192959e-03,\n", - " 7.90362902e-02]),\n", - " array([-2.98351106e-06, -2.35446710e-03, 5.99930985e-01, 8.29315744e-02,\n", - " -1.06668488e-05, 6.74142812e-06, 9.96555244e-01, -1.64458992e-05,\n", - " 3.76190323e-02, 2.17085128e-04, 1.74534513e-04, 1.16292258e-04,\n", - " 9.43226034e-03, 2.44990858e-04, 1.32933725e+00, 6.58280907e+00,\n", - " 1.57398295e+00, 9.03925767e-04, 8.85121702e-07, -1.69223299e-04,\n", - " 1.36844683e-01, 8.94966641e-04, 8.46804195e-04, 6.63686793e-04,\n", - " 3.53517440e-02]),\n", - " array([-2.22830333e-06, 2.18931296e-03, 6.56907620e-01, 8.76402967e-02,\n", - " -6.18563364e-06, 6.87836578e-06, 9.96152186e-01, -1.74783410e-05,\n", - " 3.77248738e-02, 2.21437640e-04, 1.78918071e-04, 1.19895515e-04,\n", - " 9.46626580e-03, 1.83318489e-04, 1.41609608e+00, 5.53757567e+00,\n", - " 9.45189149e-01, 8.88221709e-04, -5.65358780e-05, -1.03244180e-04,\n", - " 1.05841456e-02, 4.35251248e-04, 4.38355776e-04, 3.60325693e-04,\n", - " 3.40054562e-03]),\n", - " array([-1.43864319e-06, 8.41323548e-03, 7.04432389e-01, 8.93978346e-02,\n", - " -2.13945434e-06, 6.74511299e-06, 9.95995998e-01, -1.79075020e-05,\n", - " 3.69570717e-02, 2.22445897e-04, 1.80274723e-04, 1.21214880e-04,\n", - " 9.27855592e-03, 1.32092866e-04, 1.45070648e+00, 4.56824733e+00,\n", - " 3.52892919e-01, 8.01175801e-04, -9.94291664e-05, -4.29160997e-05,\n", - " -7.67802050e-02, 1.00825624e-04, 1.35665220e-04, 1.31936485e-04,\n", - " -1.87709877e-02]),\n", - " array([-6.82029646e-07, 1.61292511e-02, 7.43341128e-01, 8.84971614e-02,\n", - " 1.26591087e-06, 6.40425984e-06, 9.96076429e-01, -1.78276791e-05,\n", - " 3.56157994e-02, 2.21106174e-04, 1.79461677e-04, 1.20869872e-04,\n", - " 8.94494866e-03, 9.36437983e-05, 1.44881600e+00, 3.69258784e+00,\n", - " -1.80851495e-01, 6.73501252e-04, -1.28507260e-04, 7.98228577e-06,\n", - " -1.34127239e-01, -1.33972219e-04, -8.13046335e-05, -3.45007853e-05,\n", - " -3.33607255e-02]),\n", - " array([ 4.12148280e-09, 2.51053151e-02, 7.74549692e-01, 8.52917213e-02,\n", - " 3.93938809e-06, 5.91535429e-06, 9.96356022e-01, -1.73448326e-05,\n", - " 3.39244341e-02, 2.18190930e-04, 1.77153764e-04, 1.19355214e-04,\n", - " 8.52201776e-03, 6.71956771e-05, 1.42437314e+00, 2.91832818e+00,\n", - " -6.43522398e-01, 5.27979995e-04, -1.45886417e-04, 4.82846496e-05,\n", - " -1.69136528e-01, -2.91524482e-04, -2.30791302e-04, -1.51465792e-04,\n", - " -4.22930907e-02]),\n", - " array([ 6.05710071e-07, 3.50947329e-02, 7.99005634e-01, 8.01649736e-02,\n", - " 5.87168861e-06, 5.33000569e-06, 9.96781609e-01, -1.65610325e-05,\n", - " 3.20461709e-02, 2.14288765e-04, 1.73872975e-04, 1.17058620e-04,\n", - " 8.05117042e-03, 5.05288641e-05, 1.38852854e+00, 2.24741309e+00,\n", - " -1.02887754e+00, 3.80798449e-04, -1.54148399e-04, 7.83800111e-05,\n", - " -1.87826319e-01, -3.90216454e-04, -3.28078847e-04, -2.29659406e-04,\n", - " -4.70847340e-02]),\n", - " array([ 1.12483724e-06, 4.58576618e-02, 8.17659828e-01, 7.35104424e-02,\n", - " 7.10871661e-06, 4.69013449e-06, 9.97294447e-01, -1.55669861e-05,\n", - " 3.01000071e-02, 2.09842968e-04, 1.70019079e-04, 1.14281115e-04,\n", - " 7.56263656e-03, 4.10331577e-05, 1.34941700e+00, 1.67849294e+00,\n", - " -1.33485510e+00, 2.42843597e-04, -1.55758142e-04, 9.94046441e-05,\n", - " -1.94616379e-01, -4.44579740e-04, -3.85389596e-04, -2.77750486e-04,\n", - " -4.88533854e-02]),\n", - " array([ 1.57346908e-06, 5.71759720e-02, 8.31449167e-01, 6.57182129e-02,\n", - " 7.73036746e-06, 4.02814930e-06, 9.97838222e-01, -1.44398270e-05,\n", - " 2.81743028e-02, 2.05185673e-04, 1.65897421e-04, 1.11256033e-04,\n", - " 7.07887118e-03, 3.63002704e-05, 1.31239695e+00, 1.20837873e+00,\n", - " -1.56223995e+00, 1.20798664e-04, -1.52768575e-04, 1.12715913e-04,\n", - " -1.92570430e-01, -4.65729479e-04, -4.12165864e-04, -3.02508174e-04,\n", - " -4.83765387e-02]),\n", - " array([ 1.96833868e-06, 6.88626969e-02, 8.41284688e-01, 5.71649963e-02,\n", - " 7.83378562e-06, 3.36811957e-06, 9.98364745e-01, -1.32437935e-05,\n", - " 2.63372666e-02, 2.00566552e-04, 1.61742394e-04, 1.08165176e-04,\n", - " 6.61718978e-03, 3.43990204e-05, 1.28049916e+00, 8.32796038e-01,\n", - " -1.71388669e+00, 1.80406295e-05, -1.46729749e-04, 1.19603349e-04,\n", - " -1.83703620e-01, -4.61912114e-04, -4.15502651e-04, -3.09085730e-04,\n", - " -4.61681392e-02]),\n", - " array([ 2.32716222e-06, 8.07671524e-02, 8.48040976e-01, 4.82057272e-02,\n", - " 7.52044995e-06, 2.72731436e-06, 9.98837428e-01, -1.20320744e-05,\n", - " 2.46440636e-02, 1.96175342e-04, 1.57735843e-04, 1.05151468e-04,\n", - " 6.19155820e-03, 3.39479967e-05, 1.25494683e+00, 5.46620136e-01,\n", - " -1.79435194e+00, -6.45972527e-05, -1.38726370e-04, 1.21171909e-04,\n", - " -1.69320296e-01, -4.39120982e-04, -4.00655174e-04, -3.01370800e-04,\n", - " -4.25631583e-02]),\n", - " array([ 2.66604918e-06, 9.27765341e-02, 8.52543825e-01, 3.91654548e-02,\n", - " 6.88677106e-06, 2.11772370e-06, 9.99232739e-01, -1.08487367e-05,\n", - " 2.31404907e-02, 1.92157760e-04, 1.54019987e-04, 1.02327837e-04,\n", - " 5.81352491e-03, 3.40702145e-05, 1.23567589e+00, 3.43742614e-01,\n", - " -1.80978844e+00, -1.28130789e-04, -1.29481781e-04, 1.18333767e-04,\n", - " -1.50357291e-01, -4.01758188e-04, -3.71585527e-04, -2.82363083e-04,\n", - " -3.78033289e-02]),\n", - " array([ 2.99791761e-06, 1.04814523e-01, 8.55554578e-01, 3.03311462e-02,\n", - " 6.01806754e-06, 1.54735523e-06, 9.99539905e-01, -9.73019823e-06,\n", - " 2.18635600e-02, 1.88624815e-04, 1.50704961e-04, 9.97824066e-05,\n", - " 5.49238392e-03, 3.42896214e-05, 1.22181898e+00, 2.16740745e-01,\n", - " -1.76793517e+00, -1.74758776e-04, -1.19481162e-04, 1.11853848e-04,\n", - " -1.27693069e-01, -3.53294480e-04, -3.31502628e-04, -2.54543056e-04,\n", - " -3.21140995e-02]),\n", - " array([ 3.33172891e-06, 1.16837315e-01, 8.57751293e-01, 2.19438468e-02,\n", - " 4.98577097e-06, 1.02121988e-06, 9.99759205e-01, -8.70613089e-06,\n", - " 2.08398413e-02, 1.85656320e-04, 1.47871646e-04, 9.75805268e-05,\n", - " 5.23478046e-03, 3.44104896e-05, 1.21213017e+00, 1.56545025e-01,\n", - " -1.67803810e+00, -2.07226738e-04, -1.09080722e-04, 1.02406734e-04,\n", - " -1.02371873e-01, -2.96849550e-04, -2.83331510e-04, -2.20187981e-04,\n", - " -2.57603458e-02]),\n", - " array([ 3.67238477e-06, 1.28827584e-01, 8.59708701e-01, 1.41922518e-02,\n", - " 3.84750892e-06, 5.42004878e-07, 9.99899285e-01, -7.79995688e-06,\n", - " 2.00828341e-02, 1.83300222e-04, 1.45571191e-04, 9.57646121e-05,\n", - " 5.04407479e-03, 3.44059015e-05, 1.20532833e+00, 1.52293071e-01,\n", - " -1.55057602e+00, -2.28259507e-04, -9.85834853e-05, 9.06174019e-05,\n", - " -7.57007206e-02, -2.35609751e-04, -2.30045500e-04, -1.81591469e-04,\n", - " -1.90705667e-02]),\n", - " array([ 4.02115213e-06, 1.40787143e-01, 8.61880206e-01, 7.20894860e-03,\n", - " 2.64940009e-06, 1.10491440e-07, 9.99974015e-01, -7.02921659e-06,\n", - " 1.95907695e-02, 1.81569984e-04, 1.43823052e-04, 9.43530556e-05,\n", - " 4.91980998e-03, 3.43292025e-05, 1.20033884e+00, 1.91508808e-01,\n", - " -1.39674344e+00, -2.40124922e-04, -8.82757059e-05, 7.70740286e-05,\n", - " -4.92064632e-02, -1.73023805e-04, -1.74813843e-04, -1.41155658e-04,\n", - " -1.24264814e-02]),\n", - " array([ 4.37648247e-06, 1.52729289e-01, 8.64585820e-01, 1.07034559e-03,\n", - " 1.42957892e-06, -2.74189953e-07, 9.99999427e-01, -6.40607217e-06,\n", - " 1.93459970e-02, 1.80442419e-04, 1.42613555e-04, 9.33395835e-05,\n", - " 4.85756991e-03, 3.42523153e-05, 1.19642117e+00, 2.60666500e-01,\n", - " -1.22773305e+00, -2.44391872e-04, -7.84293310e-05, 6.23144423e-05,\n", - " -2.44772490e-02, -1.12756526e-04, -1.20949774e-04, -1.01347203e-04,\n", - " -6.22400644e-03]),\n", - " array([ 4.73506966e-06, 1.64671878e-01, 8.68009544e-01, -4.19929572e-03,\n", - " 2.21772715e-07, -6.14359152e-07, 9.99991183e-01, -5.93810824e-06,\n", - " 1.93165965e-02, 1.79858215e-04, 1.41896764e-04, 9.26942437e-05,\n", - " 4.84938604e-03, 3.42281980e-05, 1.19318733e+00, 3.46109172e-01,\n", - " -1.05393077e+00, -2.41921661e-04, -6.92826932e-05, 4.67963930e-05,\n", - " -2.94004592e-03, -5.84203852e-05, -7.16791216e-05, -6.45339822e-05,\n", - " -8.18387667e-04]),\n", - " array([ 5.09295541e-06, 1.76632007e-01, 8.72208538e-01, -8.62005087e-03,\n", - " -9.42196007e-07, -9.13541174e-07, 9.99962847e-01, -5.62945308e-06,\n", - " 1.94602245e-02, 1.79726753e-04, 1.41598906e-04, 9.23667877e-05,\n", - " 4.88469427e-03, 3.42722345e-05, 1.19053583e+00, 4.35198133e-01,\n", - " -8.84169912e-01, -2.33083110e-04, -6.10132077e-05, 3.08655151e-05,\n", - " 1.43627998e-02, -1.31461849e-05, -2.97857934e-05, -3.27455984e-05,\n", - " 3.53082360e-03]),\n", - " array([ 5.44647375e-06, 1.88622770e-01, 8.77134190e-01, -1.22458043e-02,\n", - " -2.03173495e-06, -1.17611178e-06, 9.99925017e-01, -5.48210297e-06,\n", - " 1.97295594e-02, 1.79935683e-04, 1.41626605e-04, 9.22925450e-05,\n", - " 4.95168382e-03, 3.43581654e-05, 1.18854053e+00, 5.17477469e-01,\n", - " -7.25190547e-01, -2.18117079e-04, -5.37143415e-05, 1.47350115e-05,\n", - " 2.69334921e-02, 2.08930046e-05, 2.76991394e-06, -7.42426731e-06,\n", - " 6.69895475e-03]),\n", - " array([ 5.79286042e-06, 2.00652082e-01, 8.82662465e-01, -1.51526233e-02,\n", - " -3.01873276e-06, -1.40683436e-06, 9.99885192e-01, -5.49722833e-06,\n", - " 2.00781462e-02, 1.80364130e-04, 1.41877963e-04, 9.24001007e-05,\n", - " 5.03874207e-03, 3.44257804e-05, 1.18733625e+00, 5.85576214e-01,\n", - " -5.81418577e-01, -1.97519893e-04, -4.73866300e-05, -1.51253580e-06,\n", - " 3.48586810e-02, 4.28446434e-05, 2.51358410e-05, 1.07555681e-05,\n", - " 8.70582436e-03]),\n", - " array([ 6.13045347e-06, 2.12723151e-01, 8.88628414e-01, -1.74278429e-02,\n", - " -3.88011908e-06, -1.61036150e-06, 9.99848124e-01, -5.67622182e-06,\n", - " 2.04651929e-02, 1.80896919e-04, 1.42254423e-04, 9.26194439e-05,\n", - " 5.13564259e-03, 3.43975293e-05, 1.18703246e+00, 6.35601761e-01,\n", - " -4.55104404e-01, -1.72303392e-04, -4.19480174e-05, -1.78993495e-05,\n", - " 3.87046696e-02, 5.32788811e-05, 3.76460060e-05, 2.19343223e-05,\n", - " 9.69005209e-03]),\n", - " array([ 6.45854317e-06, 2.24835862e-01, 8.94858690e-01, -1.91612999e-02,\n", - " -4.60065065e-06, -1.79081041e-06, 9.99816405e-01, -6.02133971e-06,\n", - " 2.08582169e-02, 1.81436684e-04, 1.42670959e-04, 9.28890357e-05,\n", - " 5.23420859e-03, 3.41992028e-05, 1.18766865e+00, 6.66922870e-01,\n", - " -3.46749478e-01, -1.44038445e-04, -3.72607934e-05, -3.45117886e-05,\n", - " 3.93024010e-02, 5.39765227e-05, 4.16536175e-05, 2.69591705e-05,\n", - " 9.85660061e-03]),\n", - " array([ 6.77702748e-06, 2.36988407e-01, 9.01196863e-01, -2.04393079e-02,\n", - " -5.17480421e-06, -1.95149191e-06, 9.99791096e-01, -6.53594929e-06,\n", - " 2.12333367e-02, 1.81911438e-04, 1.43062695e-04, 9.31605706e-05,\n", - " 5.32840110e-03, 3.37781267e-05, 1.18920735e+00, 6.81435812e-01,\n", - " -2.55651738e-01, -1.14674910e-04, -3.31638451e-05, -5.14609578e-05,\n", - " 3.75119760e-02, 4.74753940e-05, 3.91736080e-05, 2.71534911e-05,\n", - " 9.41925041e-03]),\n", - " array([ 7.08604916e-06, 2.49178627e-01, 9.07518710e-01, -2.13410257e-02,\n", - " -5.60702800e-06, -2.09479759e-06, 9.99772254e-01, -7.22453428e-06,\n", - " 2.15739843e-02, 1.82276742e-04, 1.43387215e-04, 9.34009216e-05,\n", - " 5.41401752e-03, 3.31132623e-05, 1.19155103e+00, 6.82553113e-01,\n", - " -1.80382913e-01, -8.62123364e-05, -2.94961345e-05, -6.88584990e-05,\n", - " 3.40647588e-02, 3.65304716e-05, 3.24520012e-05, 2.40351065e-05,\n", - " 8.56164205e-03]),\n", - " array([ 7.38573623e-06, 2.61404827e-01, 9.13737476e-01, -2.19363349e-02,\n", - " -5.91020919e-06, -2.22218502e-06, 9.99759370e-01, -8.09264714e-06,\n", - " 2.18692863e-02, 1.82513212e-04, 1.43623059e-04, 9.35915171e-05,\n", - " 5.48830094e-03, 3.22152826e-05, 1.19456821e+00, 6.74193629e-01,\n", - " -1.19089724e-01, -6.03425770e-05, -2.61035416e-05, -8.68112864e-05,\n", - " 2.95302032e-02, 2.36469203e-05, 2.35843243e-05, 1.90595494e-05,\n", - " 7.42834200e-03]),\n", - " array([ 7.67608410e-06, 2.73666078e-01, 9.19801252e-01, -2.22844281e-02,\n", - " -6.10281984e-06, -2.33419020e-06, 9.99751671e-01, -9.14692241e-06,\n", - " 2.21130654e-02, 1.82621071e-04, 1.43765683e-04, 9.37259182e-05,\n", - " 5.54969138e-03, 3.11188630e-05, 1.19811841e+00, 6.59991714e-01,\n", - " -6.96356740e-02, -3.81852680e-05, -2.28326393e-05, -1.05427527e-04,\n", - " 2.43779095e-02, 1.07859063e-05, 1.42624227e-05, 1.34401086e-05,\n", - " 6.13904415e-03]),\n", - " array([ 7.95695219e-06, 2.85962148e-01, 9.25685703e-01, -2.24328254e-02,\n", - " -6.20558090e-06, -2.43043742e-06, 9.99748352e-01, -1.03951413e-05,\n", - " 2.23036315e-02, 1.82613692e-04, 1.43822376e-04, 9.38065278e-05,\n", - " 5.59776367e-03, 2.98717311e-05, 1.20207051e+00, 6.42827618e-01,\n", - " -2.96868790e-02, -2.01914753e-05, -1.95230793e-05, -1.24821887e-04,\n", - " 1.90566122e-02, -7.37831223e-07, 5.66930880e-06, 8.06095920e-06,\n", - " 4.80722950e-03]),\n", - " array([ 8.22812117e-06, 2.98293239e-01, 9.31385199e-01, -2.24170486e-02,\n", - " -6.23851120e-06, -2.50966789e-06, 9.99748706e-01, -1.18462509e-05,\n", - " 2.24438402e-02, 1.82511595e-04, 1.43807324e-04, 9.38412363e-05,\n", - " 5.63322954e-03, 2.85247115e-05, 1.20631324e+00, 6.24667257e-01,\n", - " 3.15614918e-03, -6.22082036e-06, -1.60092603e-05, -1.45110966e-04,\n", - " 1.40208671e-02, -1.02096991e-05, -1.50524284e-06, 3.47084703e-06,\n", - " 3.54658639e-03]),\n", - " array([ 8.48936313e-06, 3.10659704e-01, 9.36904606e-01, -2.22613333e-02,\n", - " -6.21894722e-06, -2.56982583e-06, 9.99752186e-01, -1.35102365e-05,\n", - " 2.25407164e-02, 1.82337731e-04, 1.43737566e-04, 9.38405408e-05,\n", - " 5.65783641e-03, 2.71250637e-05, 1.21075850e+00, 6.06627403e-01,\n", - " 3.11508335e-02, 4.26402498e-06, -1.21333909e-05, -1.66398557e-04,\n", - " 9.68761501e-03, -1.73864235e-05, -6.97572934e-06, -6.95422374e-08,\n", - " 2.46068769e-03]),\n", - " array([ 8.74049724e-06, 3.23061796e-01, 9.42252891e-01, -2.19805064e-02,\n", - " -6.16071027e-06, -2.60822063e-06, 9.99758399e-01, -1.53978095e-05,\n", - " 2.26042804e-02, 1.82114293e-04, 1.43630124e-04, 9.38153891e-05,\n", - " 5.67407490e-03, 2.57133845e-05, 1.21533948e+00, 5.89160785e-01,\n", - " 5.61791256e-02, 1.19675106e-05, -7.76386719e-06, -1.88757295e-04,\n", - " 6.35639997e-03, -2.23438117e-05, -1.07442715e-05, -2.51517553e-06,\n", - " 1.62384888e-03]),\n", - " array([ 8.98142241e-06, 3.35499517e-01, 9.47438812e-01, -2.15827357e-02,\n", - " -6.07421584e-06, -2.62174239e-06, 9.99767066e-01, -1.75199513e-05,\n", - " 2.26457435e-02, 1.81860905e-04, 1.43500242e-04, 9.37757767e-05,\n", - " 5.68473386e-03, 2.43231401e-05, 1.22000575e+00, 5.72269948e-01,\n", - " 7.95730236e-02, 1.75723238e-05, -2.80904952e-06, -2.12214188e-04,\n", - " 4.14631827e-03, -2.53387857e-05, -1.29881809e-05, -3.96123685e-06,\n", - " 1.06589568e-03]),\n", - " array([ 9.21212992e-06, 3.47972527e-01, 9.52468374e-01, -2.10725486e-02,\n", - " -5.96713035e-06, -2.60708667e-06, 9.99777949e-01, -1.98874098e-05,\n", - " 2.26756038e-02, 1.81593837e-04, 1.43360531e-04, 9.37299855e-05,\n", - " 5.69243079e-03, 2.29816037e-05, 1.22471751e+00, 5.55690572e-01,\n", - " 1.02060636e-01, 2.16295848e-05, 2.77861057e-06, -2.36745847e-04,\n", - " 2.98602275e-03, -2.67068218e-05, -1.39710640e-05, -4.57911781e-06,\n", - " 7.69692555e-04]),\n", - " array([ 9.43270317e-06, 3.60480115e-01, 9.57343508e-01, -2.04534839e-02,\n", - " -5.84516306e-06, -2.56094461e-06, 9.99790806e-01, -2.25102356e-05,\n", - " 2.27021975e-02, 1.81325864e-04, 1.43220708e-04, 9.36842934e-05,\n", - " 5.69925281e-03, 2.17112214e-05, 1.22944028e+00, 5.39020915e-01,\n", - " 1.23839632e-01, 2.45317121e-05, 9.00829150e-06, -2.62282579e-04,\n", - " 2.65937334e-03, -2.67973032e-05, -1.39822780e-05, -4.56921377e-06,\n", - " 6.82202737e-04]),\n", - " array([ 9.64331052e-06, 3.73021197e-01, 9.62061504e-01, -1.97299505e-02,\n", - " -5.71272495e-06, -2.48014144e-06, 9.99805346e-01, -2.53974065e-05,\n", - " 2.27310199e-02, 1.81066469e-04, 1.43087695e-04, 9.36429889e-05,\n", - " 5.70658531e-03, 2.05308366e-05, 1.23414115e+00, 5.21802957e-01,\n", - " 1.44735913e-01, 2.65391256e-05, 1.58606315e-05, -2.88717088e-04,\n", - " 2.88223666e-03, -2.59394557e-05, -1.33013199e-05, -4.13045291e-06,\n", - " 7.33249597e-04]),\n", - " array([ 9.84419456e-06, 3.85594350e-01, 9.66614931e-01, -1.89081756e-02,\n", - " -5.57336270e-06, -2.36173798e-06, 9.99821224e-01, -2.85565194e-05,\n", - " 2.27648011e-02, 1.80822211e-04, 1.42965909e-04, 9.36085618e-05,\n", - " 5.71512677e-03, 1.94565522e-05, 1.23878661e+00, 5.03574152e-01,\n", - " 1.64385659e-01, 2.78255729e-05, 2.32949686e-05, -3.15911294e-04,\n", - " 3.37812241e-03, -2.44257908e-05, -1.21786456e-05, -3.44270556e-06,\n", - " 8.54146468e-04]),\n", - " array([ 1.00356595e-05, 3.98197853e-01, 9.70991926e-01, -1.79963852e-02,\n", - " -5.43000388e-06, -2.20313560e-06, 9.99838052e-01, -3.19934781e-05,\n", - " 2.28040974e-02, 1.80597181e-04, 1.42857654e-04, 9.35819847e-05,\n", - " 5.72503197e-03, 1.85022089e-05, 1.24334181e+00, 4.83906249e-01,\n", - " 1.82389134e-01, 2.85163050e-05, 3.12485417e-05, -3.43695870e-04,\n", - " 3.92962719e-03, -2.25030904e-05, -1.08255135e-05, -2.65771337e-06,\n", - " 9.90519601e-04]),\n", - " array([ 1.02180577e-05, 4.10829750e-01, 9.75176801e-01, -1.70044858e-02,\n", - " -5.28509473e-06, -2.00224047e-06, 9.99855413e-01, -3.57120706e-05,\n", - " 2.28480841e-02, 1.80393506e-04, 1.42763560e-04, 9.35630289e-05,\n", - " 5.73610704e-03, 1.76795195e-05, 1.24777099e+00, 4.62437187e-01,\n", - " 1.98410276e-01, 2.87099770e-05, 3.96245399e-05, -3.71859244e-04,\n", - " 4.39867094e-03, -2.03674606e-05, -9.40932834e-06, -1.89557741e-06,\n", - " 1.10750735e-03]),\n", - " array([ 1.03917773e-05, 4.23487922e-01, 9.79150889e-01, -1.59435244e-02,\n", - " -5.14069399e-06, -1.75775086e-06, 9.99872894e-01, -3.97133167e-05,\n", - " 2.28952987e-02, 1.80211859e-04, 1.42683018e-04, 9.35505724e-05,\n", - " 5.74799401e-03, 1.69978618e-05, 1.25203834e+00, 4.38893633e-01,\n", - " 2.12221085e-01, 2.84878308e-05, 4.82674965e-05, -4.00124616e-04,\n", - " 4.72146306e-03, -1.81646456e-05, -8.05427221e-06, -1.24564736e-06,\n", - " 1.18869665e-03]),\n", - " array([ 1.05572335e-05, 4.36170155e-01, 9.82893486e-01, -1.48251340e-02,\n", - " -4.99854622e-06, -1.46963862e-06, 9.99890102e-01, -4.39944545e-05,\n", - " 2.29441941e-02, 1.80051885e-04, 1.42614536e-04, 9.35428530e-05,\n", - " 5.76030930e-03, 1.64636620e-05, 1.25610915e+00, 4.13099550e-01,\n", - " 2.23704568e-01, 2.79181031e-05, 5.69245916e-05, -4.28113780e-04,\n", - " 4.88954344e-03, -1.59974579e-05, -6.84816017e-06, -7.71948153e-07,\n", - " 1.23152863e-03]),\n", - " array([ 1.07148655e-05, 4.48874201e-01, 9.86382727e-01, -1.36610845e-02,\n", - " -4.86012598e-06, -1.13991072e-06, 9.99906683e-01, -4.85474077e-05,\n", - " 2.29934622e-02, 1.79912478e-04, 1.42555968e-04, 9.35376052e-05,\n", - " 5.77272521e-03, 1.60792290e-05, 1.25995091e+00, 3.84968023e-01,\n", - " 2.32833533e-01, 2.70620842e-05, 6.51899311e-05, -4.55295316e-04,\n", - " 4.92680222e-03, -1.39406863e-05, -5.85677088e-06, -5.24774427e-07,\n", - " 1.24159105e-03]),\n", - " array([ 1.08651436e-05, 4.61597824e-01, 9.89596182e-01, -1.24629958e-02,\n", - " -4.72662122e-06, -7.73764768e-07, 9.99922334e-01, -5.33565297e-05,\n", - " 2.30421318e-02, 1.79791835e-04, 1.42504463e-04, 9.35319532e-05,\n", - " 5.78499398e-03, 1.58408273e-05, 1.26353421e+00, 3.54472358e-01,\n", - " 2.39638193e-01, 2.59864310e-05, 7.24261332e-05, -4.80912201e-04,\n", - " 4.86695992e-03, -1.20643008e-05, -5.15049870e-06, -5.65198767e-07,\n", - " 1.22687706e-03]),\n", - " array([ 1.10085910e-05, 4.74338819e-01, 9.92510752e-01, -1.12422459e-02,\n", - " -4.59877252e-06, -3.81299924e-07, 9.99936804e-01, -5.83953344e-05,\n", - " 2.30894136e-02, 1.79687088e-04, 1.42455821e-04, 9.35216805e-05,\n", - " 5.79690487e-03, 1.57356964e-05, 1.26683331e+00, 3.21575975e-01,\n", - " 2.44167164e-01, 2.47920958e-05, 7.76538022e-05, -5.03880468e-04,\n", - " 4.72818844e-03, -1.04747272e-05, -4.86419160e-06, -1.02726844e-06,\n", - " 1.19108953e-03]),\n", - " array([ 1.11458341e-05, 4.87094998e-01, 9.95100611e-01, -1.00101436e-02,\n", - " -4.47623775e-06, 1.99818664e-08, 9.99949897e-01, -6.36217958e-05,\n", - " 2.31341054e-02, 1.79592839e-04, 1.42402211e-04, 9.34987839e-05,\n", - " 5.80812433e-03, 1.57375586e-05, 1.26982639e+00, 2.86035894e-01,\n", - " 2.46434375e-01, 2.37091530e-05, 7.93945865e-05, -5.22646141e-04,\n", - " 4.46917971e-03, -9.42486150e-06, -5.36106401e-06, -2.28966700e-06,\n", - " 1.12194546e-03]),\n", - " array([ 1.12777230e-05, 4.99864062e-01, 9.97328794e-01, -8.77856820e-03,\n", - " -4.35459983e-06, 4.01545053e-07, 9.99961468e-01, -6.89715934e-05,\n", - " 2.31729731e-02, 1.79494909e-04, 1.42325721e-04, 9.34461671e-05,\n", - " 5.81778570e-03, 1.57997003e-05, 1.27249506e+00, 2.46769363e-01,\n", - " 2.46325972e-01, 2.35679062e-05, 7.54497444e-05, -5.34979760e-04,\n", - " 3.88676914e-03, -9.79302905e-06, -7.64893821e-06, -5.26167462e-06,\n", - " 9.66137120e-04]),\n", - " array([ 1.14045915e-05, 5.12643208e-01, 9.99117120e-01, -7.56161746e-03,\n", - " -4.20946169e-06, 8.01323095e-07, 9.99971411e-01, -7.41828783e-05,\n", - " 2.31964309e-02, 1.79315792e-04, 1.42192852e-04, 9.33640396e-05,\n", - " 5.82380883e-03, 1.58430451e-05, 1.27482224e+00, 1.99689421e-01,\n", - " 2.43398288e-01, 2.82355494e-05, 7.91467028e-05, -5.21128496e-04,\n", - " 2.34578224e-03, -1.79116725e-05, -1.32869084e-05, -8.21275604e-06,\n", - " 6.02312748e-04]),\n", - " array([ 1.15267645e-05, 5.25431380e-01, 1.00048554e+00, -6.36266332e-03,\n", - " -4.04870377e-06, 1.19169412e-06, 9.99979758e-01, -7.91924964e-05,\n", - " 2.32100117e-02, 1.79075670e-04, 1.42007464e-04, 9.32449176e-05,\n", - " 5.82736102e-03, 1.59675601e-05, 1.27678817e+00, 1.54635354e-01,\n", - " 2.39796654e-01, 3.13751831e-05, 7.73043822e-05, -5.00961807e-04,\n", - " 1.35807474e-03, -2.40122446e-05, -1.85388099e-05, -1.19122011e-05,\n", - " 3.55219807e-04]),\n", - " array([ 1.16442711e-05, 5.38227736e-01, 1.00147914e+00, -5.18306844e-03,\n", - " -3.88182595e-06, 1.55612104e-06, 9.99986568e-01, -8.39596402e-05,\n", - " 2.32195702e-02, 1.78799637e-04, 1.41786439e-04, 9.30972591e-05,\n", - " 5.82986045e-03, 1.61117268e-05, 1.27840337e+00, 1.14127585e-01,\n", - " 2.35922920e-01, 3.26355220e-05, 7.21394919e-05, -4.76714378e-04,\n", - " 9.55845782e-04, -2.76032558e-05, -2.21024969e-05, -1.47658506e-05,\n", - " 2.49942297e-04]),\n", - " array([ 1.17570670e-05, 5.51031273e-01, 1.00214655e+00, -4.02461597e-03,\n", - " -3.71546949e-06, 1.88535911e-06, 9.99991901e-01, -8.84588976e-05,\n", - " 2.32287010e-02, 1.78507296e-04, 1.41545922e-04, 9.29320768e-05,\n", - " 5.83221576e-03, 1.62365779e-05, 1.27968523e+00, 7.85268107e-02,\n", - " 2.31692962e-01, 3.25731607e-05, 6.51181499e-05, -4.49925747e-04,\n", - " 9.13081585e-04, -2.92341569e-05, -2.40516802e-05, -1.65182253e-05,\n", - " 2.35531665e-04]),\n", - " array([ 1.18650980e-05, 5.63840777e-01, 1.00253421e+00, -2.88997091e-03,\n", - " -3.55353569e-06, 2.17495951e-06, 9.99995824e-01, -9.26755678e-05,\n", - " 2.32391006e-02, 1.78212337e-04, 1.41298167e-04, 9.27584966e-05,\n", - " 5.83486659e-03, 1.63175283e-05, 1.28065196e+00, 4.76219741e-02,\n", - " 2.26930381e-01, 3.17284713e-05, 5.72053404e-05, -4.21667012e-04,\n", - " 1.03996235e-03, -2.94958244e-05, -2.47755062e-05, -1.73580190e-05,\n", - " 2.65082870e-04]),\n", - " array([ 1.19683178e-05, 5.76654834e-01, 1.00268525e+00, -1.78261997e-03,\n", - " -3.39796466e-06, 2.42358193e-06, 9.99998411e-01, -9.66024180e-05,\n", - " 2.32512613e-02, 1.77923864e-04, 1.41051748e-04, 9.25831929e-05,\n", - " 5.83794674e-03, 1.63401773e-05, 1.28132149e+00, 2.10916951e-02,\n", - " 2.21470805e-01, 3.04905306e-05, 4.90260777e-05, -3.92685025e-04,\n", - " 1.21607399e-03, -2.88473048e-05, -2.46419625e-05, -1.75303712e-05,\n", - " 3.08015073e-04]),\n", - " array([ 1.20666938e-05, 5.89471874e-01, 1.00263957e+00, -7.06684701e-04,\n", - " -3.24944277e-06, 2.63184803e-06, 9.99999750e-01, -1.00237423e-04,\n", - " 2.32649929e-02, 1.77647731e-04, 1.40812454e-04, 9.24108347e-05,\n", - " 5.84141458e-03, 1.62973894e-05, 1.28171157e+00, -1.37732283e-03,\n", - " 2.15187231e-01, 2.91094703e-05, 4.09742662e-05, -3.63500500e-04,\n", - " 1.37315968e-03, -2.76132875e-05, -2.39293993e-05, -1.72358195e-05,\n", - " 3.46784184e-04]),\n", - " array([ 1.21602088e-05, 6.02290195e-01, 1.00243407e+00, 3.33286153e-04,\n", - " -3.10792140e-06, 2.80156543e-06, 9.99999944e-01, -1.03582184e-04,\n", - " 2.32797508e-02, 1.77387582e-04, 1.40584123e-04, 9.22446408e-05,\n", - " 5.84513670e-03, 1.61870970e-05, 1.28183995e+00, -2.00712726e-02,\n", - " 2.07994184e-01, 2.77330019e-05, 3.32875133e-05, -3.34476125e-04,\n", - " 1.47578458e-03, -2.60149211e-05, -2.28330385e-05, -1.66193859e-05,\n", - " 3.72211390e-04]),\n", - " array([ 1.22488632e-05, 6.15108008e-01, 1.00210287e+00, 1.33251731e-03,\n", - " -2.97296603e-06, 2.93520723e-06, 9.99999112e-01, -1.06640826e-04,\n", - " 2.32948301e-02, 1.77145576e-04, 1.40369262e-04, 9.20868245e-05,\n", - " 5.84893777e-03, 1.60106446e-05, 1.28172454e+00, -3.52558788e-02,\n", - " 1.99846310e-01, 2.64395857e-05, 2.60987266e-05, -3.05864154e-04,\n", - " 1.50793403e-03, -2.42006060e-05, -2.14861041e-05, -1.57816350e-05,\n", - " 3.80107119e-04]),\n", - " array([ 1.23326755e-05, 6.27923463e-01, 1.00167737e+00, 2.28619341e-03,\n", - " -2.84397797e-06, 3.03556763e-06, 9.99997387e-01, -1.09419223e-04,\n", - " 2.33094790e-02, 1.76922876e-04, 1.40169469e-04, 9.19389052e-05,\n", - " 5.85262971e-03, 1.57715617e-05, 1.28138339e+00, -4.71871412e-02,\n", - " 1.90735540e-01, 2.52634661e-05, 1.94716531e-05, -2.77839715e-04,\n", - " 1.46489059e-03, -2.22699626e-05, -1.99793628e-05, -1.47919269e-05,\n", - " 3.69193731e-04]),\n", - " array([ 1.24116835e-05, 6.40734689e-01, 1.00118631e+00, 3.18962945e-03,\n", - " -2.72032653e-06, 3.10553862e-06, 9.99994913e-01, -1.11924464e-04,\n", - " 2.33229650e-02, 1.76719967e-04, 1.39985709e-04, 9.18019139e-05,\n", - " 5.85602883e-03, 1.54746739e-05, 1.28083463e+00, -5.61203358e-02,\n", - " 1.80687890e-01, 2.42123251e-05, 1.34252572e-05, -2.50524152e-04,\n", - " 1.34860237e-03, -2.02909902e-05, -1.83759270e-05, -1.36991330e-05,\n", - " 3.39912307e-04]),\n", - " array([ 1.24859441e-05, 6.53539821e-01, 1.00065569e+00, 4.03842414e-03,\n", - " -2.60142049e-06, 3.14796936e-06, 9.99991846e-01, -1.14164478e-04,\n", - " 2.33346163e-02, 1.76536848e-04, 1.39818493e-04, 9.16765208e-05,\n", - " 5.85896643e-03, 1.51254750e-05, 1.28009633e+00, -6.23160238e-02,\n", - " 1.69760052e-01, 2.32792940e-05, 7.95035707e-06, -2.24001352e-04,\n", - " 1.16512114e-03, -1.83118223e-05, -1.67216168e-05, -1.25393138e-05,\n", - " 2.93759549e-04]),\n", - " array([ 1.25555332e-05, 6.66337035e-01, 1.00010871e+00, 4.82859487e-03,\n", - " -2.48673982e-06, 3.16558156e-06, 9.99988342e-01, -1.16147770e-04,\n", - " 2.33438480e-02, 1.76373163e-04, 1.39667975e-04, 9.15631121e-05,\n", - " 5.86129560e-03, 1.47296964e-05, 1.27918630e+00, -6.60431007e-02,\n", - " 1.58035704e-01, 2.24508665e-05, 3.02087900e-06, -1.98329164e-04,\n", - " 9.23176280e-04, -1.63684881e-05, -1.50518495e-05, -1.13408689e-05,\n", - " 2.32917667e-04]),\n", - " array([ 1.26205454e-05, 6.79124583e-01, 9.99565689e-01, 5.55669236e-03,\n", - " -2.37584231e-06, 3.16092252e-06, 9.99984561e-01, -1.17883243e-04,\n", - " 2.33501812e-02, 1.76228266e-04, 1.39534015e-04, 9.14618343e-05,\n", - " 5.86289592e-03, 1.42930240e-05, 1.27812197e+00, -6.75792568e-02,\n", - " 1.45621465e-01, 2.17118938e-05, -1.39861755e-06, -1.73547363e-04,\n", - " 6.33315596e-04, -1.44897847e-05, -1.33959638e-05, -1.01277779e-05,\n", - " 1.60031687e-04]),\n", - " array([ 1.26810923e-05, 6.91900813e-01, 9.99044018e-01, 6.21989309e-03,\n", - " -2.26835594e-06, 3.13634276e-06, 9.99980656e-01, -1.19380075e-04,\n", - " 2.33532540e-02, 1.76101265e-04, 1.39416218e-04, 9.13726197e-05,\n", - " 5.86367642e-03, 1.38209208e-05, 1.27692017e+00, -6.72092940e-02,\n", - " 1.32642448e-01, 2.10485081e-05, -5.34799346e-06, -1.49683185e-04,\n", - " 3.07286857e-04, -1.27000920e-05, -1.17796987e-05, -8.92145688e-06,\n", - " 7.80503711e-05]),\n", - " array([ 1.27373012e-05, 7.04664201e-01, 9.98558139e-01, 6.81606771e-03,\n", - " -2.16396392e-06, 3.09398960e-06, 9.99976770e-01, -1.20647627e-04,\n", - " 2.33528289e-02, 1.75991057e-04, 1.39313954e-04, 9.12952033e-05,\n", - " 5.86357729e-03, 1.33185264e-05, 1.27559709e+00, -6.52217736e-02,\n", - " 1.19237458e-01, 2.04495893e-05, -8.86836026e-06, -1.26755154e-04,\n", - " -4.25098856e-05, -1.10207445e-05, -1.02263733e-05, -7.74163677e-06,\n", - " -9.91311552e-06]),\n", - " array([ 1.27893135e-05, 7.17413370e-01, 9.98119572e-01, 7.34382423e-03,\n", - " -2.06238793e-06, 3.03581046e-06, 9.99973034e-01, -1.21695384e-04,\n", - " 2.33487933e-02, 1.75896353e-04, 1.39226382e-04, 9.12291375e-05,\n", - " 5.86257010e-03, 1.27906067e-05, 1.27416815e+00, -6.19044798e-02,\n", - " 1.05553950e-01, 1.99072239e-05, -1.20001257e-05, -1.04775707e-04,\n", - " -4.03569335e-04, -9.47043190e-06, -8.75719129e-06, -6.60658083e-06,\n", - " -1.00719195e-04]),\n", - " array([ 1.28372825e-05, 7.30147105e-01, 9.97737000e-01, 7.80252582e-03,\n", - " -1.96337252e-06, 2.96356183e-06, 9.99969560e-01, -1.22532914e-04,\n", - " 2.33411549e-02, 1.75815703e-04, 1.39152472e-04, 9.11738087e-05,\n", - " 5.86065669e-03, 1.22415388e-05, 1.27264796e+00, -5.75391921e-02,\n", - " 9.17429503e-02, 1.94164942e-05, -1.47818612e-05, -8.37529878e-05,\n", - " -7.63835803e-04, -8.06499767e-06, -7.39099969e-06, -5.53288860e-06,\n", - " -1.91341167e-04]),\n", - " array([ 1.28813714e-05, 7.42864362e-01, 9.97416401e-01, 8.19228412e-03,\n", - " -1.86667285e-06, 2.87882119e-06, 9.99966443e-01, -1.23169834e-04,\n", - " 2.33300325e-02, 1.75747534e-04, 1.39091035e-04, 9.11284578e-05,\n", - " 5.85786669e-03, 1.16753160e-05, 1.27105036e+00, -5.23962495e-02,\n", - " 7.79541544e-02, 1.89748689e-05, -1.72497141e-05, -6.36920598e-05,\n", - " -1.11223928e-03, -6.81692933e-06, -6.14376491e-06, -4.53508228e-06,\n", - " -2.78999479e-04]),\n", - " array([ 1.29217515e-05, 7.55564281e-01, 9.97161232e-01, 8.51393011e-03,\n", - " -1.77204669e-06, 2.78299999e-06, 9.99963756e-01, -1.23615791e-04,\n", - " 2.33156408e-02, 1.75690186e-04, 1.39040755e-04, 9.10922066e-05,\n", - " 5.85425389e-03, 1.10955651e-05, 1.26938841e+00, -4.67293493e-02,\n", - " 6.43314425e-02, 1.85814030e-05, -1.94371718e-05, -4.45957302e-05,\n", - " -1.43917099e-03, -5.73476831e-06, -5.02797063e-06, -3.62512782e-06,\n", - " -3.61280731e-04]),\n", - " array([ 1.29586000e-05, 7.68246179e-01, 9.96972666e-01, 8.76896574e-03,\n", - " -1.67925061e-06, 2.67735682e-06, 9.99961552e-01, -1.23880443e-04,\n", - " 2.32982722e-02, 1.75641960e-04, 1.39000234e-04, 9.10640865e-05,\n", - " 5.84989158e-03, 1.05055687e-05, 1.26767445e+00, -4.07709607e-02,\n", - " 5.10090306e-02, 1.82359229e-05, -2.13750416e-05, -2.64651131e-05,\n", - " -1.73685632e-03, -4.82260180e-06, -4.05208516e-06, -2.81200196e-06,\n", - " -4.36231028e-04]),\n", - " array([ 1.29920986e-05, 7.80909547e-01, 9.96849853e-01, 8.95950037e-03,\n", - " -1.58804014e-06, 2.56300991e-06, 9.99959863e-01, -1.23973443e-04,\n", - " 2.32782763e-02, 1.75601162e-04, 1.38968032e-04, 9.10430726e-05,\n", - " 5.84486742e-03, 9.90829020e-06, 1.26592015e+00, -3.47286433e-02,\n", - " 3.81084224e-02, 1.79382589e-05, -2.30915534e-05, -9.30002559e-06,\n", - " -1.99959333e-03, -4.07977283e-06, -3.22021619e-06, -2.10139097e-06,\n", - " -5.02415751e-04]),\n", - " array([ 1.30224315e-05, 7.93554048e-01, 9.96790213e-01, 9.08817646e-03,\n", - " -1.49817298e-06, 2.44094893e-06, 9.99958702e-01, -1.23904436e-04,\n", - " 2.32560379e-02, 1.75566154e-04, 1.38942712e-04, 9.10281171e-05,\n", - " 5.83927800e-03, 9.30639774e-06, 1.26413657e+00, -2.87824528e-02,\n", - " 2.57362655e-02, 1.76876597e-05, -2.46125233e-05, 6.90071915e-06,\n", - " -2.22384085e-03, -3.50082517e-06, -2.53198032e-06, -1.49554806e-06,\n", - " -5.58941804e-04]),\n", - " array([ 1.30497845e-05, 8.06179501e-01, 9.96789736e-01, 9.15808924e-03,\n", - " -1.40941500e-06, 2.31204575e-06, 9.99958064e-01, -1.23683045e-04,\n", - " 2.32319563e-02, 1.75535396e-04, 1.38922886e-04, 9.10181839e-05,\n", - " 5.83322357e-03, 8.70228702e-06, 1.26233420e+00, -2.30835107e-02,\n", - " 1.39831397e-02, 1.74822432e-05, -2.59615367e-05, 2.21390827e-05,\n", - " -2.40815863e-03, -3.07580389e-06, -1.98264543e-06, -9.93326803e-07,\n", - " -6.05442869e-04]),\n", - " array([ 1.30743436e-05, 8.18785867e-01, 9.96843283e-01, 9.17270483e-03,\n", - " -1.32154083e-06, 2.17706433e-06, 9.99957930e-01, -1.23318869e-04,\n", - " 2.32064261e-02, 1.75507497e-04, 1.38907256e-04, 9.10122828e-05,\n", - " 5.82680325e-03, 8.09810037e-06, 1.26052300e+00, -1.77537067e-02,\n", - " 2.92323950e-03, 1.73200653e-05, -2.71601624e-05, 3.64175964e-05,\n", - " -2.55301782e-03, -2.78993847e-06, -1.56295637e-06, -5.90105640e-07,\n", - " -6.42032232e-04]),\n", - " array([ 1.30962944e-05, 8.31373241e-01, 9.96944882e-01, 9.13578061e-03,\n", - " -1.23435050e-06, 2.03666983e-06, 9.99958268e-01, -1.22821477e-04,\n", - " 2.31798210e-02, 1.75481239e-04, 1.38894650e-04, 9.10094961e-05,\n", - " 5.82011094e-03, 7.49574915e-06, 1.25871240e+00, -1.28864223e-02,\n", - " -7.38515314e-03, 1.71959392e-05, -2.82280596e-05, 4.97392118e-05,\n", - " -2.66051203e-03, -2.62577662e-06, -1.26063643e-06, -2.78673904e-07,\n", - " -6.69230687e-04]),\n", - " array([ 1.31158211e-05, 8.43941830e-01, 9.97088001e-01, 9.05129138e-03,\n", - " -1.14767034e-06, 1.89143693e-06, 9.99959036e-01, -1.22200406e-04,\n", - " 2.31524809e-02, 1.75455618e-04, 1.38884053e-04, 9.10090071e-05,\n", - " 5.81323216e-03, 6.89692589e-06, 1.25691133e+00, -8.54810115e-03,\n", - " -1.68985445e-02, 1.71045518e-05, -2.91832027e-05, 6.21071185e-05,\n", - " -2.73400552e-03, -2.56210053e-06, -1.05972116e-06, -4.88956351e-08,\n", - " -6.87878583e-04]),\n", - " array([ 1.31331065e-05, 8.56491943e-01, 9.97265800e-01, 8.92336344e-03,\n", - " -1.06136020e-06, 1.74185739e-06, 9.99960186e-01, -1.21465159e-04,\n", - " 2.31247034e-02, 1.75429867e-04, 1.38874639e-04, 9.10101250e-05,\n", - " 5.80624174e-03, 6.30311983e-06, 1.25512816e+00, -4.78045844e-03,\n", - " -2.55866208e-02, 1.70392009e-05, -3.00419959e-05, 7.35246094e-05,\n", - " -2.77775493e-03, -2.57504729e-06, -9.41381948e-07, 1.11783467e-07,\n", - " -6.99041162e-04]),\n", - " array([ 1.31483311e-05, 8.69023975e-01, 9.97471353e-01, 8.75621835e-03,\n", - " -9.75324963e-07, 1.58834723e-06, 9.99961664e-01, -1.20625210e-04,\n", - " 2.30967380e-02, 1.75403480e-04, 1.38865795e-04, 9.10123050e-05,\n", - " 5.79920259e-03, 5.71562983e-06, 1.25337073e+00, -1.60311220e-03,\n", - " -3.34303250e-02, 1.69909386e-05, -3.08193901e-05, 8.39949519e-05,\n", - " -2.79653684e-03, -2.63870063e-06, -8.84416098e-07, 2.18000711e-07,\n", - " -7.03915178e-04]),\n", - " array([ 1.31616734e-05, 8.81538392e-01, 9.97697844e-01, 8.55412703e-03,\n", - " -8.89524432e-07, 1.43125308e-06, 9.99963413e-01, -1.19689997e-04,\n", - " 2.30687850e-02, 1.75376233e-04, 1.38857145e-04, 9.10151712e-05,\n", - " 5.79216516e-03, 5.13557297e-06, 1.25164626e+00, 9.83566409e-04,\n", - " -4.04197775e-02, 1.69488777e-05, -3.15290172e-05, 9.35212674e-05,\n", - " -2.79530489e-03, -2.72469077e-06, -8.64989313e-07, 2.86619466e-07,\n", - " -7.03742789e-04]),\n", - " array([ 1.31733095e-05, 8.94035720e-01, 9.97938725e-01, 8.32137443e-03,\n", - " -8.03988372e-07, 1.27085817e-06, 9.99965377e-01, -1.18668933e-04,\n", - " 2.30409961e-02, 1.75348214e-04, 1.38848581e-04, 9.10185404e-05,\n", - " 5.78516780e-03, 4.56389152e-06, 1.24996138e+00, 2.99556042e-03,\n", - " -4.65521787e-02, 1.68991534e-05, -3.21833011e-05, 1.02106433e-04,\n", - " -2.77889037e-03, -2.80190430e-06, -8.56383810e-07, 3.36919146e-07,\n", - " -6.99736210e-04]),\n", - " array([ 1.31834130e-05, 9.06516534e-01, 9.98187856e-01, 8.06223409e-03,\n", - " -7.18838733e-07, 1.10738757e-06, 9.99967500e-01, -1.17571403e-04,\n", - " 2.30134786e-02, 1.75319858e-04, 1.38840298e-04, 9.10224515e-05,\n", - " 5.77823766e-03, 4.00135609e-06, 1.24832203e+00, 4.46241091e-03,\n", - " -5.18298059e-02, 1.68234859e-05, -3.27935710e-05, 1.09753001e-04,\n", - " -2.75174975e-03, -2.83559585e-06, -8.28262326e-07, 3.91118058e-07,\n", - " -6.93013975e-04]),\n", - " array([ 1.31921552e-05, 9.18981444e-01, 9.98439612e-01, 7.78095199e-03,\n", - " -6.34321535e-07, 9.41012913e-07, 9.99969728e-01, -1.16406771e-04,\n", - " 2.29863011e-02, 1.75292001e-04, 1.38832845e-04, 9.10272050e-05,\n", - " 5.77139219e-03, 3.44856377e-06, 1.24673346e+00, 5.42461654e-03,\n", - " -5.62581863e-02, 1.66972381e-05, -3.33701841e-05, 1.16463148e-04,\n", - " -2.71775216e-03, -2.78575717e-06, -7.45300904e-07, 4.75348727e-07,\n", - " -6.84547106e-04]),\n", - " array([ 1.31997042e-05, 9.31431090e-01, 9.98688963e-01, 7.48173817e-03,\n", - " -5.50853299e-07, 7.71856294e-07, 9.99972011e-01, -1.15184385e-04,\n", - " 2.29595012e-02, 1.75265954e-04, 1.38827194e-04, 9.10334165e-05,\n", - " 5.76464108e-03, 2.90592934e-06, 1.24520019e+00, 5.93128930e-03,\n", - " -5.98445062e-02, 1.64865048e-05, -3.39226628e-05, 1.22238643e-04,\n", - " -2.67999058e-03, -2.60470088e-06, -5.65128877e-07, 6.21145805e-07,\n", - " -6.75111068e-04]),\n", - " array([ 1.32062254e-05, 9.43866130e-01, 9.98931545e-01, 7.16876508e-03,\n", - " -4.69087674e-07, 5.99993292e-07, 9.99974304e-01, -1.13913576e-04,\n", - " 2.29330952e-02, 1.75243618e-04, 1.38824841e-04, 9.10420926e-05,\n", - " 5.75798871e-03, 2.37366685e-06, 1.24372597e+00, 6.03809243e-03,\n", - " -6.25962973e-02, 1.61440674e-05, -3.44598622e-05, 1.27080868e-04,\n", - " -2.64059108e-03, -2.23356899e-06, -2.35335871e-07, 8.67616131e-07,\n", - " -6.65237028e-04]),\n", - " array([ 1.32118797e-05, 9.56287234e-01, 9.99163699e-01, 6.84617085e-03,\n", - " -3.90010101e-07, 4.25454781e-07, 9.99976565e-01, -1.12603667e-04,\n", - " 2.29070904e-02, 1.75227643e-04, 1.38827948e-04, 9.10547375e-05,\n", - " 5.75143718e-03, 1.85175727e-06, 1.24231376e+00, 5.80545771e-03,\n", - " -6.45204304e-02, 1.56037864e-05, -3.49901898e-05, 1.30990901e-04,\n", - " -2.60048413e-03, -1.59748350e-06, 3.10708755e-07, 1.26448300e-06,\n", - " -6.55153331e-04]),\n", - " array([ 1.32168230e-05, 9.68695075e-01, 9.99382507e-01, 6.51806594e-03,\n", - " -3.15070829e-07, 2.48227065e-07, 9.99978757e-01, -1.11263971e-04,\n", - " 2.28814995e-02, 1.75221654e-04, 1.38839544e-04, 9.10735003e-05,\n", - " 5.74499013e-03, 1.33989660e-06, 1.24096571e+00, 5.29705573e-03,\n", - " -6.56224478e-02, 1.47729268e-05, -3.55219162e-05, 1.33969685e-04,\n", - " -2.55908939e-03, -5.98908196e-07, 1.15959858e-06, 1.87627948e-06,\n", - " -6.44704824e-04]),\n", - " array([ 1.32212041e-05, 9.81090323e-01, 9.99585806e-01, 6.18854121e-03,\n", - " -2.46370241e-07, 6.82495581e-08, 9.99980851e-01, -1.09903787e-04,\n", - " 2.28563610e-02, 1.75230568e-04, 1.38863801e-04, 9.11013809e-05,\n", - " 5.73865780e-03, 8.37416201e-07, 1.23968312e+00, 4.57847299e-03,\n", - " -6.59062760e-02, 1.35216963e-05, -3.60636357e-05, 1.36018362e-04,\n", - " -2.51384721e-03, 8.91357824e-07, 2.42569948e-06, 2.78806120e-06,\n", - " -6.33233056e-04]),\n", - " array([ 1.32251612e-05, 9.93473641e-01, 9.99772199e-01, 5.86167520e-03,\n", - " -1.86915258e-07, -1.14591243e-07, 9.99982820e-01, -1.08532399e-04,\n", - " 2.28317660e-02, 1.75261031e-04, 1.38906418e-04, 9.11425123e-05,\n", - " 5.73246386e-03, 3.43164152e-07, 1.23846648e+00, 3.71602508e-03,\n", - " -6.53743894e-02, 1.16690242e-05, -3.66249695e-05, 1.37138834e-04,\n", - " -2.45950307e-03, 3.04634917e-06, 4.26171147e-06, 4.11313742e-06,\n", - " -6.19393426e-04]),\n", - " array([ 1.32288177e-05, 1.00584567e+00, 9.99941044e-01, 5.54153771e-03,\n", - " -1.40972177e-07, -3.00473451e-07, 9.99984646e-01, -1.07159052e-04,\n", - " 2.28078959e-02, 1.75322025e-04, 1.38975147e-04, 9.12025470e-05,\n", - " 5.72645512e-03, -1.44668195e-07, 1.23731537e+00, 2.77558843e-03,\n", - " -6.40285382e-02, 8.96327355e-06, -3.72176545e-05, 1.37334696e-04,\n", - " -2.38700888e-03, 6.09934349e-06, 6.87289609e-06, 6.00347160e-06,\n", - " -6.00874531e-04]),\n", - " array([ 1.32322757e-05, 1.01820705e+00, 1.00009244e+00, 5.23218611e-03,\n", - " -1.14549940e-07, -4.89660221e-07, 9.99986312e-01, -1.05792924e-04,\n", - " 2.27850775e-02, 1.75425684e-04, 1.39080508e-04, 9.12891822e-05,\n", - " 5.72071544e-03, -6.28796148e-07, 1.23622855e+00, 1.82119420e-03,\n", - " -6.18712194e-02, 5.05614584e-06, -3.78572356e-05, 1.36612742e-04,\n", - " -2.28183791e-03, 1.03659272e-05, 1.05361141e-05, 8.66352355e-06,\n", - " -5.73967659e-04]),\n", - " array([ 1.32356059e-05, 1.03055835e+00, 1.00022718e+00, 4.93764909e-03,\n", - " -1.16058653e-07, -6.82533641e-07, 9.99987810e-01, -1.04443071e-04,\n", - " 2.27638635e-02, 1.75588419e-04, 1.39236757e-04, 9.14128642e-05,\n", - " 5.71538638e-03, -1.11319845e-06, 1.23520390e+00, 9.12675570e-04,\n", - " -5.89081657e-02, -5.32378706e-07, -3.85656832e-05, 1.34985334e-04,\n", - " -2.12139920e-03, 1.62734905e-05, 1.56249044e-05, 1.23681964e-05,\n", - " -5.32905779e-04]),\n", - " array([ 1.32388341e-05, 1.04290016e+00, 1.00034667e+00, 4.66189102e-03,\n", - " -1.57199564e-07, -8.79649114e-07, 9.99989133e-01, -1.03118330e-04,\n", - " 2.27451531e-02, 1.75832419e-04, 1.39463168e-04, 9.15877085e-05,\n", - " 5.71069796e-03, -1.60362318e-06, 1.23423842e+00, 1.00117156e-04,\n", - " -5.51522484e-02, -8.46035164e-06, -3.93754052e-05, 1.32474077e-04,\n", - " -1.87104741e-03, 2.43999857e-05, 2.26411147e-05, 1.74844305e-05,\n", - " -4.68842133e-04]),\n", - " array([ 1.32419217e-05, 1.05523299e+00, 1.00045261e+00, 4.40874695e-03,\n", - " -2.54146692e-07, -1.08182049e-06, 9.99990281e-01, -1.01827177e-04,\n", - " 2.27303746e-02, 1.76187643e-04, 1.39785666e-04, 9.18326198e-05,\n", - " 5.70701546e-03, -2.10830315e-06, 1.23332830e+00, -5.92446701e-04,\n", - " -5.06293352e-02, -1.96222146e-05, -4.03352842e-05, 1.29115354e-04,\n", - " -1.47784342e-03, 3.55224732e-05, 3.22497852e-05, 2.44911346e-05,\n", - " -3.68250557e-04]),\n", - " array([ 1.32447391e-05, 1.06755733e+00, 1.00054629e+00, 4.18181504e-03,\n", - " -4.29045330e-07, -1.29024963e-06, 9.99991256e-01, -1.00577493e-04,\n", - " 2.27217686e-02, 1.76694337e-04, 1.40238656e-04, 9.21723608e-05,\n", - " 5.70491172e-03, -2.63897144e-06, 1.23246894e+00, -1.21993974e-03,\n", - " -4.53868003e-02, -3.52122207e-05, -4.15194608e-05, 1.24968386e-04,\n", - " -8.60604073e-04, 5.06693818e-05, 4.52990227e-05, 3.39740935e-05,\n", - " -2.10373769e-04]),\n", - " array([ 1.32470313e-05, 1.07987364e+00, 1.00062592e+00, 3.98428846e-03,\n", - " -7.11664969e-07, -1.50671512e-06, 9.99992063e-01, -9.93762328e-05,\n", - " 2.27228310e-02, 1.77405780e-04, 1.40866183e-04, 9.26374502e-05,\n", - " 5.70528057e-03, -3.21233567e-06, 1.23165499e+00, -2.09487484e-03,\n", - " -3.95056467e-02, -5.67553801e-05, -4.30391890e-05, 1.20125991e-04,\n", - " 1.06242674e-04, 7.11442639e-05, 6.27526486e-05, 4.65089440e-05,\n", - " 3.68845477e-05]),\n", - " array([ 1.32483875e-05, 1.09218241e+00, 1.00067797e+00, 3.81869764e-03,\n", - " -1.14026727e-06, -1.73382271e-06, 9.99992709e-01, -9.82289726e-05,\n", - " 2.27390162e-02, 1.78389690e-04, 1.41718968e-04, 9.32587841e-05,\n", - " 5.70951217e-03, -3.85238508e-06, 1.23088060e+00, -4.39960862e-03,\n", - " -3.31184150e-02, -8.59505597e-05, -4.50558584e-05, 1.14726014e-04,\n", - " 1.61851578e-03, 9.83909682e-05, 8.52785252e-05, 6.21333942e-05,\n", - " 4.23160386e-04]),\n", - " array([ 1.32482904e-05, 1.10448438e+00, 1.00064732e+00, 3.68648617e-03,\n", - " -1.75750319e-06, -1.97525847e-06, 9.99993205e-01, -9.71394410e-05,\n", - " 2.27788025e-02, 1.79721365e-04, 1.42835493e-04, 9.40438651e-05,\n", - " 5.71970806e-03, -4.59481225e-06, 1.23013961e+00, -1.22968223e-02,\n", - " -2.64424813e-02, -1.23676411e-04, -4.77850695e-05, 1.08953164e-04,\n", - " 3.97863580e-03, 1.33167542e-04, 1.11652521e-04, 7.85080994e-05,\n", - " 1.01958875e-03]),\n", - " array([ 1.32466234e-05, 1.11678125e+00, 1.00033456e+00, 3.58692493e-03,\n", - " -2.57996836e-06, -2.23577307e-06, 9.99993567e-01, -9.61093619e-05,\n", - " 2.28546968e-02, 1.81434350e-04, 1.44174808e-04, 9.49098300e-05,\n", - " 5.73819911e-03, -5.49951066e-06, 1.22942620e+00, -4.02198038e-02,\n", - " -1.99123781e-02, -1.64723199e-04, -5.14610268e-05, 1.03007909e-04,\n", - " 7.58943106e-03, 1.71298540e-04, 1.33931449e-04, 8.65964833e-05,\n", - " 1.84910561e-03])],\n", - " [array([ 2.64384428e+02, 2.89350425e+02, 2.89367532e+02, 2.64366573e+02,\n", - " 4.83533174e-04, -4.41156021e+00, -4.19269086e-02, -1.18985927e-02,\n", - " 5.90701266e-03, -9.34680397e-01]),\n", - " array([ 7.98280190e+01, 1.14110646e+02, 1.14055984e+02, 7.98819088e+01,\n", - " 9.26741194e-04, -4.30262850e+00, -2.57209930e-02, -1.23123856e-02,\n", - " -3.04843177e-03, -7.63272289e-01]),\n", - " array([ 1.21236991e+01, 2.69303001e+01, 2.68790947e+01, 1.21738072e+01,\n", - " 1.03939795e-03, -2.56442623e+00, -1.39105060e-02, -9.58008857e-03,\n", - " -5.57199220e-03, -5.38590207e-01]),\n", - " array([-1.55764650e+01, -1.40395013e+01, -1.40760398e+01, -1.55410139e+01,\n", - " 9.75124349e-04, -7.27969860e-01, -5.87178669e-03, -6.08991303e-03,\n", - " -5.09818526e-03, -2.00405587e-01]),\n", - " array([-2.61857516e+01, -3.31622065e+01, -3.31836821e+01, -2.61651815e+01,\n", - " 7.96443981e-04, 7.20992751e-01, -4.34233940e-04, -2.94851521e-03,\n", - " -3.72573713e-03, 1.02492742e-01]),\n", - " array([-2.92766233e+01, -4.13055690e+01, -4.13145149e+01, -2.92683136e+01,\n", - " 5.55954831e-04, 1.70371546e+00, 3.15545747e-03, -4.85705998e-04,\n", - " -2.29598519e-03, 3.21733494e-01]),\n", - " array([-2.90143234e+01, -4.36209119e+01, -4.36204673e+01, -2.90151121e+01,\n", - " 3.04838036e-04, 2.27737878e+00, 5.40126250e-03, 1.28233978e-03,\n", - " -1.09604574e-03, 4.56739308e-01]),\n", - " array([-2.72575802e+01, -4.27100701e+01, -4.27031503e+01, -2.72645778e+01,\n", - " 8.23043411e-05, 2.53247326e+00, 6.66277924e-03, 2.44819681e-03,\n", - " -1.90223982e-04, 5.22346107e-01]),\n", - " array([-2.48519595e+01, -3.99695993e+01, -3.99586336e+01, -2.48627928e+01,\n", - " -8.92620400e-05, 2.55558592e+00, 7.20565998e-03, 3.12981096e-03,\n", - " 4.40834700e-04, 5.35863975e-01]),\n", - " array([-2.21897555e+01, -3.61939063e+01, -3.61808039e+01, -2.22025830e+01,\n", - " -2.02625324e-04, 2.41819092e+00, 7.22943088e-03, 3.43879882e-03,\n", - " 8.42716597e-04, 5.12606463e-01]),\n", - " array([-1.94574519e+01, -3.18590185e+01, -3.18452195e+01, -1.94708998e+01,\n", - " -2.61172768e-04, 2.17543145e+00, 6.88516741e-03, 3.47039296e-03,\n", - " 1.06438408e-03, 4.64789441e-01]),\n", - " array([-1.67454402e+01, -2.72615686e+01, -2.72481185e+01, -1.67585197e+01,\n", - " -2.74239584e-04, 1.86833744e+00, 6.28768431e-03, 3.30213847e-03,\n", - " 1.15001257e-03, 4.01679790e-01]),\n", - " array([-1.40968805e+01, -2.25907880e+01, -2.25784105e+01, -1.41089107e+01,\n", - " -2.53467057e-04, 1.52688188e+00, 5.52441440e-03, 2.99579706e-03,\n", - " 1.13689224e-03, 3.30134896e-01]),\n", - " array([-1.15310387e+01, -1.79701804e+01, -1.79593413e+01, -1.15415831e+01,\n", - " -2.10426687e-04, 1.17291850e+00, 4.66223857e-03, 2.60012744e-03,\n", - " 1.05558713e-03, 2.55197479e-01]),\n", - " array([-9.05710125e+00, -1.34858428e+01, -1.34768028e+01, -9.06591563e+00,\n", - " -1.55315644e-04, 8.22674131e-01, 3.75298381e-03, 2.15360705e-03,\n", - " 9.30715333e-04, 1.80621349e-01]),\n", - " array([-6.68469468e+00, -9.20796741e+00, -9.20082604e+00, -6.69168565e+00,\n", - " -9.64056655e-05, 4.88677105e-01, 2.83787633e-03, 1.68674450e-03,\n", - " 7.81726091e-04, 1.09283435e-01]),\n", - " array([-4.43229276e+00, -5.20651604e+00, -5.20124878e+00, -4.43748288e+00,\n", - " -3.99475683e-05, 1.81065027e-01, 1.95093617e-03, 1.22386496e-03,\n", - " 6.23521094e-04, 4.34668581e-02]),\n", - " array([-2.33241068e+00, -1.55972305e+00, -1.55621396e+00, -2.33590825e+00,\n", - " 9.69220623e-06, -9.17401405e-02, 1.12117264e-03, 7.84348974e-04,\n", - " 4.66967358e-04, -1.49847970e-02]),\n", - " array([-4.32091757e-01, 1.64586289e+00, 1.64779212e+00, -4.34063804e-01,\n", - " 4.98026628e-05, -3.22928613e-01, 3.73496975e-04, 3.83365603e-04,\n", - " 3.19401232e-04, -6.46265524e-02]),\n", - " array([ 1.21197603e+00, 4.32349419e+00, 4.32405835e+00, 1.21132792e+00,\n", - " 7.90749855e-05, -5.07614068e-01, -2.71539111e-04, 3.21950526e-05,\n", - " 1.85196777e-04, -1.04452271e-01]),\n", - " array([ 2.54304391e+00, 6.40016390e+00, 6.39959205e+00, 2.54350431e+00,\n", - " 9.73446819e-05, -6.43321624e-01, -7.98840397e-04, -2.61713922e-04,\n", - " 6.64188381e-05, -1.33970594e-01]),\n", - " array([ 3.51676030e+00, 7.83265360e+00, 7.83117147e+00, 3.51811646e+00,\n", - " 1.05327023e-04, -7.30389631e-01, -1.20020186e-03, -4.94774748e-04,\n", - " -3.64611954e-05, -1.53267353e-01]),\n", - " array([ 4.11392574e+00, 8.62161030e+00, 8.61942823e+00, 4.11597883e+00,\n", - " 1.04344267e-04, -7.72071835e-01, -1.47553369e-03, -6.67205571e-04,\n", - " -1.23836717e-04, -1.63013993e-01]),\n", - " array([ 4.35034099e+00, 8.81971163e+00, 8.81701823e+00, 4.35291196e+00,\n", - " 9.60559854e-05, -7.74230431e-01, -1.63336412e-03, -7.82747917e-04,\n", - " -1.96313943e-04, -1.64400765e-01]),\n", - " array([ 4.28007976e+00, 8.53028600e+00, 8.52724675e+00, 4.28301054e+00,\n", - " 8.22157138e-05, -7.44629477e-01, -1.69019073e-03, -8.48098731e-04,\n", - " -2.54280191e-04, -1.58996998e-01]),\n", - " array([ 3.98934834e+00, 7.89430048e+00, 7.89105918e+00, 3.99250048e+00,\n", - " 6.44785575e-05, -6.91947438e-01, -1.66847008e-03, -8.72075934e-04,\n", - " -2.97831182e-04, -1.48562299e-01]),\n", - " array([ 3.58122251e+00, 7.06754099e+00, 7.06422143e+00, 3.58447569e+00,\n", - " 4.42754286e-05, -6.24718201e-01, -1.59346753e-03, -8.64607011e-04,\n", - " -3.27062431e-04, -1.34847191e-01]),\n", - " array([ 3.15564700e+00, 6.19446387e+00, 6.19117016e+00, 3.15889907e+00,\n", - " 2.27570307e-05, -5.50452925e-01, -1.48967622e-03, -8.35675851e-04,\n", - " -3.42535656e-04, -1.19425617e-01]),\n", - " array([ 2.79122843e+00, 5.38700992e+00, 5.38382496e+00, 2.79439725e+00,\n", - " 7.99421301e-07, -4.75142762e-01, -1.37772991e-03, -7.94381467e-04,\n", - " -3.45641405e-04, -1.03591323e-01]),\n", - " array([ 2.53424085e+00, 4.71415856e+00, 4.71114186e+00, 2.53726681e+00,\n", - " -2.09472764e-05, -4.03189942e-01, -1.27252569e-03, -7.48243936e-04,\n", - " -3.38661370e-04, -8.83267555e-02]),\n", - " array([ 2.39708329e+00, 4.20313620e+00, 4.20032252e+00, 2.39993086e+00,\n", - " -4.19943605e-05, -3.37636970e-01, -1.18279395e-03, -7.02834928e-04,\n", - " -3.24505293e-04, -7.43267637e-02]),\n", - " array([ 2.36501417e+00, 3.84895037e+00, 3.84635068e+00, 2.36767114e+00,\n", - " -6.19641555e-05, -2.80468953e-01, -1.11187577e-03, -6.61732664e-04,\n", - " -3.06244381e-04, -6.20441670e-02]),\n", - " array([ 2.40758080e+00, 3.62708950e+00, 3.62469483e+00, 2.41005458e+00,\n", - " -8.05738189e-05, -2.32808058e-01, -1.05918717e-03, -6.26736003e-04,\n", - " -2.86626014e-04, -5.17281233e-02]),\n", - " array([ 2.49045080e+00, 3.50498082e+00, 3.50276849e+00, 2.49276234e+00,\n", - " -9.76521922e-05, -1.94959536e-01, -1.02182414e-03, -5.98238865e-04,\n", - " -2.67726330e-04, -4.34447599e-02]),\n", - " array([ 2.58431649e+00, 3.44999644e+00, 3.44793714e+00, 2.58649336e+00,\n", - " -1.13167194e-04, -1.66400877e-01, -9.95924306e-04, -5.75664584e-04,\n", - " -2.50811997e-04, -3.70893658e-02]),\n", - " array([ 2.66937347e+00, 3.43384994e+00, 3.43191422e+00, 2.67144350e+00,\n", - " -1.27233564e-04, -1.45845800e-01, -9.77614848e-04, -5.57880544e-04,\n", - " -2.36396772e-04, -3.24079538e-02]),\n", - " array([ 2.73562062e+00, 3.43426031e+00, 3.43242315e+00, 2.73760750e+00,\n", - " -1.40082583e-04, -1.31455521e-01, -9.63543936e-04, -5.43542837e-04,\n", - " -2.24427533e-04, -2.90397563e-02]),\n", - " array([ 2.78039965e+00, 3.43494742e+00, 3.43319038e+00, 2.78232083e+00,\n", - " -1.51995559e-04, -1.21169471e-01, -9.51084015e-04, -5.31348735e-04,\n", - " -2.14521298e-04, -2.65779754e-02]),\n", - " array([ 2.80503388e+00, 3.42487245e+00, 3.42318371e+00, 2.80690046e+00,\n", - " -1.63220325e-04, -1.13056849e-01, -9.38335830e-04, -5.20194974e-04,\n", - " -2.06180737e-04, -2.46343929e-02]),\n", - " array([ 2.81211087e+00, 3.39736788e+00, 3.39574085e+00, 2.81392885e+00,\n", - " -1.73891188e-04, -1.05584399e-01, -9.24049228e-04, -5.09254282e-04,\n", - " -1.98941703e-04, -2.28908442e-02]),\n", - " array([ 2.80410471e+00, 3.34943733e+00, 3.34786890e+00, 2.80587661e+00,\n", - " -1.83963811e-04, -9.77419516e-02, -9.07534408e-04, -4.97990570e-04,\n", - " -1.92441198e-04, -2.11266040e-02]),\n", - " array([ 2.78315344e+00, 3.28116505e+00, 3.27965385e+00, 2.78487965e+00,\n", - " -1.93162901e-04, -8.90281352e-02, -8.88583380e-04, -4.86135685e-04,\n", - " -1.86426693e-04, -1.92203272e-02]),\n", - " array([ 2.75135574e+00, 3.19503907e+00, 3.19358420e+00, 2.75303549e+00,\n", - " -2.00930163e-04, -7.93413400e-02, -8.67389347e-04, -4.73647269e-04,\n", - " -1.80740465e-04, -1.71329885e-02]),\n", - " array([ 2.71101803e+00, 3.09509178e+00, 3.09369185e+00, 2.71264991e+00,\n", - " -2.06354592e-04, -6.88336483e-02, -8.44450616e-04, -4.60661190e-04,\n", - " -1.75304893e-04, -1.48815939e-02]),\n", - " array([ 2.66460959e+00, 2.98593632e+00, 2.98458858e+00, 2.66619179e+00,\n", - " -2.08065170e-04, -5.77742029e-02, -8.20461361e-04, -4.47446767e-04,\n", - " -1.70119000e-04, -1.25125696e-02]),\n", - " array([ 2.61443809e+00, 2.87183414e+00, 2.87053364e+00, 2.61596846e+00,\n", - " -2.04064434e-04, -4.64475185e-02, -7.96202577e-04, -4.34371412e-04,\n", - " -1.65268284e-04, -1.00806398e-02]),\n", - " array([ 2.56202064e+00, 2.75574422e+00, 2.75448267e+00, 2.56349664e+00,\n", - " -1.91477502e-04, -3.50940396e-02, -7.72438362e-04, -4.21886249e-04,\n", - " -1.60960930e-04, -7.63594401e-03]),\n", - " array([ 2.50658233e+00, 2.63768767e+00, 2.63645162e+00, 2.50800129e+00,\n", - " -1.66183024e-04, -2.38920223e-02, -7.49782559e-04, -4.10565202e-04,\n", - " -1.57653750e-04, -5.22093081e-03]),\n", - " array([ 2.44030386e+00, 2.50993023e+00, 2.50869689e+00, 2.44166481e+00,\n", - " -1.22278876e-04, -1.29858973e-02, -7.28393221e-04, -4.01300199e-04,\n", - " -1.56484158e-04, -2.88086304e-03]),\n", - " array([ 2.33186427e+00, 2.34043828e+00, 2.33916078e+00, 2.33317939e+00,\n", - " -5.13154415e-05, -2.59531886e-03, -7.07160727e-04, -3.95941231e-04,\n", - " -1.60558591e-04, -6.99099466e-04]),\n", - " array([ 2.06873291e+00, 2.01497992e+00, 2.01354723e+00, 2.07012061e+00,\n", - " 5.88096667e-05, 6.68195771e-03, -6.83581654e-04, -3.98558836e-04,\n", - " -1.76183052e-04, 1.13539256e-03]),\n", - " array([ 2.15845186e+00, 2.07603045e+00, 2.07457995e+00, 2.15976706e+00,\n", - " 1.30048469e-04, 1.30826557e-02, -6.93503398e-04, -4.01580454e-04,\n", - " -1.75202503e-04, 2.62719465e-03]),\n", - " array([ 2.33749528e+00, 2.23708284e+00, 2.23562073e+00, 2.33876619e+00,\n", - " 1.74471347e-04, 1.76222818e-02, -7.20375466e-04, -4.09858768e-04,\n", - " -1.72250115e-04, 3.73652589e-03]),\n", - " array([ 2.52912759e+00, 2.41236092e+00, 2.41086927e+00, 2.53039572e+00,\n", - " 2.00464728e-04, 2.13802950e-02, -7.55261904e-04, -4.23309804e-04,\n", - " -1.72002689e-04, 4.63180507e-03]),\n", - " array([ 2.71336023e+00, 2.57865551e+00, 2.57711800e+00, 2.71465787e+00,\n", - " 2.13868271e-04, 2.50176595e-02, -7.93846438e-04, -4.40450129e-04,\n", - " -1.74772338e-04, 5.46012131e-03]),\n", - " array([ 2.88639825e+00, 2.73127925e+00, 2.72968527e+00, 2.88774678e+00,\n", - " 2.18746167e-04, 2.88456962e-02, -8.33812388e-04, -4.59798289e-04,\n", - " -1.79792199e-04, 6.30328412e-03]),\n", - " array([ 3.04841062e+00, 2.87052340e+00, 2.86886739e+00, 3.04982272e+00,\n", - " 2.17923143e-04, 3.29544628e-02, -8.73762955e-04, -4.80192703e-04,\n", - " -1.86233227e-04, 7.19218343e-03]),\n", - " array([ 3.20007176e+00, 2.99764456e+00, 2.99592477e+00, 3.20155377e+00,\n", - " 2.13358933e-04, 3.73087337e-02, -9.12776522e-04, -5.00785741e-04,\n", - " -1.93437219e-04, 8.12643599e-03]),\n", - " array([ 3.34172689e+00, 3.11376873e+00, 3.11198605e+00, 3.34328079e+00,\n", - " 2.06410102e-04, 4.18082865e-02, -9.50202900e-04, -5.20970701e-04,\n", - " -2.00927646e-04, 9.08860639e-03]),\n", - " array([ 3.47330327e+00, 3.21966914e+00, 3.21782628e+00, 3.47492802e+00,\n", - " 1.98012955e-04, 4.63235441e-02, -9.85559387e-04, -5.40312581e-04,\n", - " -2.08371524e-04, 1.00530778e-02]),\n", - " array([ 3.59441078e+00, 3.31579435e+00, 3.31389522e+00, 3.59610332e+00,\n", - " 1.88811125e-04, 5.07163030e-02, -1.01847456e-03, -5.58496768e-04,\n", - " -2.15539868e-04, 1.09913229e-02]),\n", - " array([ 3.70447452e+00, 3.40235814e+00, 3.40040744e+00, 3.70623047e+00,\n", - " 1.79244402e-04, 5.48519621e-02, -1.04865811e-03, -5.75294531e-04,\n", - " -2.22277005e-04, 1.18750205e-02]),\n", - " array([ 3.80285863e+00, 3.47943531e+00, 3.47743825e+00, 3.80467273e+00,\n", - " 1.69610460e-04, 5.86070534e-02, -1.07588592e-03, -5.90541151e-04,\n", - " -2.28478869e-04, 1.26779463e-02]),\n", - " array([ 3.88897212e+00, 3.54704725e+00, 3.54500933e+00, 3.89083859e+00,\n", - " 1.60107636e-04, 6.18741568e-02, -1.09999413e-03, -6.04122690e-04,\n", - " -2.34078247e-04, 1.33771685e-02]),\n", - " array([ 3.96235530e+00, 3.60523278e+00, 3.60315961e+00, 3.96426807e+00,\n", - " 1.50864553e-04, 6.45652396e-02, -1.12087801e-03, -6.15968297e-04,\n", - " -2.39034931e-04, 1.39538283e-02]),\n", - " array([ 4.02274610e+00, 3.65410311e+00, 3.65200032e+00, 4.02469903e+00,\n", - " 1.41960610e-04, 6.66138610e-02, -1.13849291e-03, -6.26045722e-04,\n", - " -2.43329180e-04, 1.43936363e-02]),\n", - " array([ 4.07012550e+00, 3.69388069e+00, 3.69175381e+00, 4.07211248e+00,\n", - " 1.33440205e-04, 6.79763708e-02, -1.15285509e-03, -6.34358436e-04,\n", - " -2.46957340e-04, 1.46871334e-02]),\n", - " array([ 4.10474155e+00, 3.72492208e+00, 3.72277645e+00, 4.10675666e+00,\n", - " 1.25322674e-04, 6.86321031e-02, -1.16404127e-03, -6.40943224e-04,\n", - " -2.49928842e-04, 1.48297328e-02]),\n", - " array([ 4.12711237e+00, 3.74772562e+00, 3.74556633e+00, 4.12914994e+00,\n", - " 1.17609346e-04, 6.85825504e-02, -1.17218599e-03, -6.45867567e-04,\n", - " -2.52264037e-04, 1.48215437e-02]),\n", - " array([ 4.13800943e+00, 3.76292548e+00, 3.76075729e+00, 4.14006414e+00,\n", - " 1.10288658e-04, 6.78495525e-02, -1.17747659e-03, -6.49226423e-04,\n", - " -2.53992495e-04, 1.46669921e-02]),\n", - " array([ 4.13842425e+00, 3.77127426e+00, 3.76910156e+00, 4.14049119e+00,\n", - " 1.03339971e-04, 6.64726106e-02, -1.18014581e-03, -6.51138267e-04,\n", - " -2.55151547e-04, 1.43742594e-02]),\n", - " array([ 4.12952231e+00, 3.77361713e+00, 3.77144391e+00, 4.13159702e+00,\n", - " 9.67365116e-05, 6.45055165e-02, -1.18046251e-03, -6.51740434e-04,\n", - " -2.55784895e-04, 1.39545792e-02]),\n", - " array([ 4.11258927e+00, 3.77086073e+00, 3.76869051e+00, 4.11466777e+00,\n", - " 9.04477011e-05, 6.20125434e-02, -1.17872105e-03, -6.51183923e-04,\n", - " -2.55941191e-04, 1.34214423e-02]),\n", - " array([ 4.08897434e+00, 3.76394015e+00, 3.76177603e+00, 4.09105315e+00,\n", - " 8.44410256e-05, 5.90644744e-02, -1.17523010e-03, -6.49627921e-04,\n", - " -2.55672530e-04, 1.27897670e-02]),\n", - " array([ 4.06003565e+00, 3.75378715e+00, 3.75163172e+00, 4.06211182e+00,\n", - " 7.86835449e-05, 5.57347411e-02, -1.17030198e-03, -6.47234069e-04,\n", - " -2.55032516e-04, 1.20750873e-02]),\n", - " array([ 4.02709148e+00, 3.74130178e+00, 3.73915722e+00, 4.02916252e+00,\n", - " 7.31430925e-05, 5.20959108e-02, -1.16424041e-03, -6.44161285e-04,\n", - " -2.54075198e-04, 1.12928124e-02]),\n", - " array([ 3.99138006e+00, 3.72732947e+00, 3.72519751e+00, 3.99344399e+00,\n", - " 6.77891771e-05, 4.82167047e-02, -1.15733394e-03, -6.40560446e-04,\n", - " -2.52852114e-04, 1.04575925e-02]),\n", - " array([ 3.95402961e+00, 3.71264407e+00, 3.71052605e+00, 3.95608487e+00,\n", - " 6.25936375e-05, 4.41596623e-02, -1.14984610e-03, -6.36569871e-04,\n", - " -2.51410891e-04, 9.58281710e-03]),\n", - " array([ 3.91603883e+00, 3.69793735e+00, 3.69583429e+00, 3.91808420e+00,\n", - " 5.75310551e-05, 3.99795017e-02, -1.14200871e-03, -6.32310877e-04,\n", - " -2.49792814e-04, 8.68025791e-03]),\n", - " array([ 3.87826718e+00, 3.68381421e+00, 3.68172685e+00, 3.88030176e+00,\n", - " 5.25789513e-05, 3.57221641e-02, -1.13401701e-03, -6.27883681e-04,\n", - " -2.48030058e-04, 7.75985493e-03]),\n", - " array([ 3.84143381e+00, 3.67079274e+00, 3.66872167e+00, 3.84345687e+00,\n", - " 4.77178145e-05, 3.14244880e-02, -1.12602430e-03, -6.23363368e-04,\n", - " -2.46142943e-04, 6.82963632e-03]),\n", - " array([ 3.80612314e+00, 3.65930809e+00, 3.65725385e+00, 3.80813403e+00,\n", - " 4.29309937e-05, 2.71144344e-02, -1.11813711e-03, -6.18795397e-04,\n", - " -2.44136436e-04, 5.89575722e-03]),\n", - " array([ 3.77279543e+00, 3.64971868e+00, 3.64768193e+00, 3.77479341e+00,\n", - " 3.82045091e-05, 2.28117750e-02, -1.11040974e-03, -6.14190274e-04,\n", - " -2.41995834e-04, 4.96264066e-03]),\n", - " array([ 3.74180053e+00, 3.64231369e+00, 3.64029538e+00, 3.74378456e+00,\n", - " 3.35268443e-05, 1.85291715e-02, -1.10283714e-03, -6.09516715e-04,\n", - " -2.39681287e-04, 4.03320695e-03]),\n", - " array([ 3.71339317e+00, 3.63732053e+00, 3.63532216e+00, 3.71536168e+00,\n", - " 2.88887994e-05, 1.42736011e-02, -1.09534507e-03, -6.04692458e-04,\n", - " -2.37120556e-04, 3.10918395e-03]),\n", - " array([ 3.68774895e+00, 3.63491135e+00, 3.63293530e+00, 3.68969949e+00,\n", - " 2.42835109e-05, 1.00481324e-02, -1.08777612e-03, -5.99571634e-04,\n", - " -2.34199338e-04, 2.19150136e-03]),\n", - " array([ 3.66497986e+00, 3.63520750e+00, 3.63325746e+00, 3.66690870e+00,\n", - " 1.97067896e-05, 5.85412142e-03, -1.07986968e-03, -5.93927297e-04,\n", - " -2.30748161e-04, 1.28078692e-03]),\n", - " array([ 3.64514924e+00, 3.63828090e+00, 3.63636239e+00, 3.64705079e+00,\n", - " 1.51579955e-05, 1.69398546e-03, -1.07123388e-03, -5.87427270e-04,\n", - " -2.26524586e-04, 3.78003045e-04]),\n", - " array([ 3.62828565e+00, 3.64415066e+00, 3.64227183e+00, 3.63015170e+00,\n", - " 1.06417762e-05, -2.42516251e-03, -1.06130603e-03, -5.79600857e-04,\n", - " -2.21189014e-04, -5.14709000e-04]),\n", - " array([ 3.61439495e+00, 3.65277231e+00, 3.65094491e+00, 3.61621367e+00,\n", - " 6.17115790e-06, -6.48656633e-03, -1.04929788e-03, -5.69793192e-04,\n", - " -2.14271878e-04, -1.39286939e-03]),\n", - " array([ 3.60346679e+00, 3.66401267e+00, 3.66225340e+00, 3.60522136e+00,\n", - " 1.77272959e-06, -1.04568625e-02, -1.03411973e-03, -5.57103013e-04,\n", - " -2.05129536e-04, -2.24801676e-03]),\n", - " array([ 3.59546071e+00, 3.67759093e+00, 3.67592323e+00, 3.59712748e+00,\n", - " -2.50497553e-06, -1.42760232e-02, -1.01427525e-03, -5.40298605e-04,\n", - " -1.92886184e-04, -3.06532334e-03]),\n", - " array([ 3.59021700e+00, 3.69292430e+00, 3.69138077e+00, 3.59176307e+00,\n", - " -6.57826075e-06, -1.78425538e-02, -9.87713408e-04, -5.17706365e-04,\n", - " -1.76361520e-04, -3.82006639e-03]),\n", - " array([ 3.58709708e+00, 3.70867301e+00, 3.70729848e+00, 3.58847710e+00,\n", - " -1.03078273e-05, -2.09913680e-02, -9.51611398e-04, -4.87069750e-04,\n", - " -1.53995366e-04, -4.47231978e-03]),\n", - " array([ 3.58367064e+00, 3.72128649e+00, 3.72014175e+00, 3.58482302e+00,\n", - " -1.34678176e-05, -2.34602133e-02, -9.02026028e-04, -4.45393945e-04,\n", - " -1.23824369e-04, -4.95883366e-03]),\n", - " array([ 3.57107534e+00, 3.72015252e+00, 3.71931764e+00, 3.57191872e+00,\n", - " -1.57002893e-05, -2.48378328e-02, -8.33235570e-04, -3.88860236e-04,\n", - " -8.37231873e-05, -5.18042207e-03]),\n", - " array([ 3.51782116e+00, 3.67107341e+00, 3.67064616e+00, 3.51825577e+00,\n", - " -1.64520078e-05, -2.44824373e-02, -7.36215199e-04, -3.13139791e-04,\n", - " -3.26658630e-05, -4.98243519e-03]),\n", - " array([ 3.31356513e+00, 3.45946346e+00, 3.45953460e+00, 3.31349722e+00,\n", - " -1.48985113e-05, -2.13919115e-02, -5.94487640e-04, -2.15263700e-04,\n", - " 2.44565878e-05, -4.12851385e-03]),\n", - " array([ 2.57458619e+00, 2.69413091e+00, 2.69464954e+00, 2.57406254e+00,\n", - " -9.89238399e-06, -1.39969790e-02, -3.72692469e-04, -1.00585553e-04,\n", - " 6.12364647e-05, -2.31966354e-03])],\n", + " array([ 3.29449644e-07, 1.63660054e-04, 3.09880729e-02, -5.65126477e-03,\n", + " 1.13741448e-05, 2.02669533e-07, 9.99984031e-01, 1.69754705e-05,\n", + " -1.43469196e-02, 7.03532505e-05, 3.34424866e-05, 7.59222065e-06,\n", + " -3.08530834e-03, -4.59944556e-07, -2.29288498e-04, 6.19773357e-01,\n", + " -2.26051794e-01, 4.54968213e-04, 8.10682447e-06, 3.39509410e-04,\n", + " -2.86938391e-01, 1.40706501e-03, 6.68849733e-04, 1.51844413e-04,\n", + " -6.17061667e-02]),\n", + " array([ 1.70307596e-06, 1.05067791e-03, 8.67033339e-02, -1.18028131e-02,\n", + " 1.60772680e-05, -1.12760134e-06, 9.99930344e-01, 3.43543505e-05,\n", + " -2.78309916e-02, 1.43433192e-04, 7.36477075e-05, 2.31722477e-05,\n", + " -6.01418829e-03, -3.12894729e-06, -1.71087723e-03, 1.11445215e+00,\n", + " -2.46071690e-01, 1.88498116e-04, -5.49454968e-05, 3.47577601e-04,\n", + " -2.69681440e-01, 1.46159882e-03, 8.04104417e-04, 3.11600542e-04,\n", + " -5.85775991e-02]),\n", + " array([ 4.14297837e-06, 3.07962438e-03, 1.62070715e-01, -1.76519617e-02,\n", + " 1.46611328e-05, -2.73119019e-06, 9.99844192e-01, 5.08074069e-05,\n", + " -3.90685308e-02, 2.16994394e-04, 1.18011670e-04, 4.44985943e-05,\n", + " -8.45565215e-03, 2.37762854e-06, -3.83265458e-03, 1.50789746e+00,\n", + " -2.33991656e-01, -5.60931210e-05, -6.85734714e-05, 3.29061128e-04,\n", + " -2.24750786e-01, 1.47122406e-03, 8.87279249e-04, 4.26526931e-04,\n", + " -4.88292771e-02]),\n", + " array([ 7.23458267e-06, 6.53940574e-03, 2.53120370e-01, -2.25885822e-02,\n", + " 7.52952019e-06, -3.83553425e-06, 9.99744845e-01, 6.55157123e-05,\n", + " -4.70939235e-02, 2.90510284e-04, 1.65750486e-04, 7.07526039e-05,\n", + " -1.01987491e-02, 2.11845933e-05, -4.12355652e-03, 1.82231005e+00,\n", + " -1.97505002e-01, -2.84922517e-04, -5.21084809e-05, 2.94166108e-04,\n", + " -1.60507854e-01, 1.47031780e-03, 9.54776316e-04, 5.25080192e-04,\n", + " -3.48619389e-02]),\n", + " array([ 1.01650152e-05, 1.16001442e-02, 3.56886545e-01, -2.60940124e-02,\n", + " -5.84221615e-06, -3.93841614e-06, 9.99659493e-01, 7.80447501e-05,\n", + " -5.09611665e-02, 3.63509076e-04, 2.16103526e-04, 1.01109506e-04,\n", + " -1.10372156e-02, 5.47094027e-05, 9.24772651e-05, 2.07779443e+00,\n", + " -1.40258834e-01, -5.35153219e-04, -1.72650667e-05, 2.50580756e-04,\n", + " -7.73448599e-02, 1.45997583e-03, 1.00706081e-03, 6.07138044e-04,\n", + " -1.67693297e-02]),\n", + " array([ 1.16581493e-05, 1.83196770e-02, 4.71289680e-01, -2.76862447e-02,\n", + " -2.70773649e-05, -2.65962495e-06, 9.99616662e-01, 8.84270696e-05,\n", + " -4.94894480e-02, 4.34989628e-04, 2.67742962e-04, 1.34272615e-04,\n", + " -1.07141427e-02, 1.04796440e-04, 1.11881687e-02, 2.29197971e+00,\n", + " -6.37123338e-02, -8.50712676e-04, 2.93351725e-05, 2.07646389e-04,\n", + " 2.94343710e-02, 1.42961104e-03, 1.03278872e-03, 6.63262169e-04,\n", + " 6.46145691e-03]),\n", + " array([ 9.41386315e-06, 2.66417392e-02, 5.95004647e-01, -2.69195735e-02,\n", + " -6.22579651e-05, 2.95365659e-07, 9.99637601e-01, 9.75356565e-05,\n", + " -4.11592966e-02, 4.96924981e-04, 3.11861773e-04, 1.62945544e-04,\n", + " -8.91909672e-03, 1.76246084e-04, 3.11323188e-02, 2.47969594e+00,\n", + " 3.06782902e-02, -1.40985297e-03, 7.83654233e-05, 1.82171738e-04,\n", + " 1.66603027e-01, 1.23870707e-03, 8.82376214e-04, 5.73458584e-04,\n", + " 3.59009203e-02]),\n", + " array([ 1.06578432e-05, 3.59925260e-02, 7.19365298e-01, -2.34883439e-02,\n", + " -4.33040428e-05, 2.85758876e-07, 9.99724110e-01, 1.03143736e-04,\n", + " -2.85145508e-02, 5.13117718e-04, 3.28371926e-04, 1.76320914e-04,\n", + " -6.18274332e-03, 2.87920492e-04, 6.14426717e-02, 2.49348202e+00,\n", + " 1.37292868e-01, 7.58068866e-04, 1.14792736e-05, 1.12161596e-04,\n", + " 2.52894917e-01, 3.23854737e-04, 3.30203065e-04, 2.67507412e-04,\n", + " 5.47270679e-02]),\n", + " array([ 1.05794932e-05, 4.56492170e-02, 8.19533278e-01, -2.21582090e-02,\n", + " -3.28089085e-05, 4.88409396e-07, 9.99754476e-01, 1.09632425e-04,\n", + " -2.15548433e-02, 5.11052403e-04, 3.29068936e-04, 1.78461944e-04,\n", + " -4.66867565e-03, 1.51324100e-04, 1.01509982e-01, 2.01008667e+00,\n", + " 5.32192633e-02, 4.19536675e-04, 1.56599662e-05, 1.29773775e-04,\n", + " 1.39194150e-01, -4.13063059e-05, 1.39402009e-05, 4.28205927e-05,\n", + " 3.02813534e-02]),\n", + " array([ 1.00016132e-05, 5.55056951e-02, 8.95405904e-01, -2.29448524e-02,\n", + " -2.53707493e-05, 9.33980494e-07, 9.99736732e-01, 1.16369948e-04,\n", + " -1.97722880e-02, 5.01999128e-04, 3.24582123e-04, 1.77228262e-04,\n", + " -4.27239813e-03, 7.71953651e-05, 1.28504714e-01, 1.52479810e+00,\n", + " -3.14737420e-02, 2.97050509e-04, 2.54438252e-05, 1.34750452e-04,\n", + " 3.56511055e-02, -1.81065491e-04, -8.97362546e-05, -2.46736320e-05,\n", + " 7.92555039e-03]),\n", + " array([ 9.08334547e-06, 6.55140240e-02, 9.47601519e-01, -2.63281587e-02,\n", + " -2.03652177e-05, 1.12029567e-06, 9.99653354e-01, 1.23545677e-04,\n", + " -2.19854588e-02, 4.88776278e-04, 3.16914597e-04, 1.73833240e-04,\n", + " -4.73115896e-03, 2.99489936e-05, 1.48502711e-01, 1.05250691e+00,\n", + " -1.35373406e-01, 2.00039717e-04, 1.54813176e-05, 1.43514595e-04,\n", + " -4.42634159e-02, -2.64457014e-04, -1.53350520e-04, -6.79004424e-05,\n", + " -9.17521650e-03]),\n", + " array([ 7.88625658e-06, 7.57010100e-02, 9.77856722e-01, -3.37546053e-02,\n", + " -1.75773702e-05, 1.27350750e-06, 9.99430151e-01, 1.30593537e-04,\n", + " -2.58274744e-02, 4.73407755e-04, 3.07432579e-04, 1.69063715e-04,\n", + " -5.55637234e-03, -3.15687140e-07, 1.67033342e-01, 6.16253329e-01,\n", + " -2.97192682e-01, 1.11465888e-04, 1.51220938e-05, 1.40957202e-04,\n", + " -7.68403115e-02, -3.07370460e-04, -1.89640362e-04, -9.53905156e-05,\n", + " -1.65042676e-02]),\n", + " array([ 6.48684120e-06, 8.60158373e-02, 9.87165622e-01, -4.62094243e-02,\n", + " -1.69131052e-05, 1.53517220e-06, 9.98931774e-01, 1.37201014e-04,\n", + " -3.08948403e-02, 4.56575978e-04, 2.96467003e-04, 1.63025040e-04,\n", + " -6.65742183e-03, -2.07289212e-05, 1.90765978e-01, 2.02071418e-01,\n", + " -4.98594678e-01, 2.64868952e-05, 2.01403314e-05, 1.32149526e-04,\n", + " -1.01347319e-01, -3.36635544e-04, -2.19311515e-04, -1.20773498e-04,\n", + " -2.20209898e-02]),\n", + " array([ 4.97660234e-06, 9.63931475e-02, 9.76121533e-01, -6.47902605e-02,\n", + " -2.01996446e-05, 2.19043479e-06, 9.97898904e-01, 1.43938224e-04,\n", + " -3.90128667e-02, 4.34466711e-04, 2.80019142e-04, 1.52590797e-04,\n", + " -8.46486314e-03, -3.71476048e-05, 2.30761906e-01, -1.96529221e-01,\n", + " -7.44391606e-01, -1.32097711e-04, 3.27434420e-05, 1.34744203e-04,\n", + " -1.62360527e-01, -4.42185325e-04, -3.28957223e-04, -2.08684860e-04,\n", + " -3.61488263e-02]),\n", + " array([ 2.34379784e-06, 1.09626349e-01, 9.62414147e-01, -8.05307903e-02,\n", + " -3.09122937e-06, -2.12089870e-06, 9.96752122e-01, 1.54278528e-04,\n", + " -4.48389075e-02, 3.99466097e-04, 2.56043929e-04, 1.37947402e-04,\n", + " -9.75097850e-03, -5.85413466e-05, 3.01617116e-01, -2.32901676e-01,\n", + " -6.31296520e-01, 6.94553442e-04, -1.14938821e-04, 2.06806082e-04,\n", + " -1.16520817e-01, -7.00012294e-04, -4.79504258e-04, -2.92867894e-04,\n", + " -2.57223071e-02]),\n", + " array([-3.02305724e-07, 1.27762733e-01, 9.53449594e-01, -9.02846187e-02,\n", + " 6.56762733e-06, -4.97309230e-06, 9.95916004e-01, 1.61215870e-04,\n", + " -4.75204565e-02, 3.67587820e-04, 2.33638657e-04, 1.24069077e-04,\n", + " -1.03331291e-02, -5.50745948e-05, 3.87956065e-01, -1.14943353e-01,\n", + " -3.91585551e-01, 3.93362435e-04, -8.14699674e-05, 1.38746838e-04,\n", + " -5.36309797e-02, -6.37565527e-04, -4.48105455e-04, -2.77566492e-04,\n", + " -1.16430119e-02]),\n", + " array([-2.46376564e-06, 1.51392678e-01, 9.49619174e-01, -9.49169669e-02,\n", + " 1.19029004e-05, -6.78235321e-06, 9.95485193e-01, 1.63648432e-04,\n", + " -4.83444158e-02, 3.42102445e-04, 2.16208579e-04, 1.13686008e-04,\n", + " -1.05101976e-02, -4.82417432e-05, 4.78622677e-01, 1.18556968e-02,\n", + " -1.86093685e-01, 2.18265772e-04, -5.41099872e-05, 4.86512319e-05,\n", + " -1.64791861e-02, -5.09707510e-04, -3.48601552e-04, -2.07661388e-04,\n", + " -3.54136941e-03]),\n", + " array([-3.85367839e-06, 1.80803971e-01, 9.51265566e-01, -9.50126814e-02,\n", + " 1.40616890e-05, -7.71404656e-06, 9.95476062e-01, 1.61036947e-04,\n", + " -4.78261203e-02, 3.23524316e-04, 2.04200390e-04, 1.07127921e-04,\n", + " -1.03962579e-02, -3.85430220e-05, 5.71390541e-01, 1.43550557e-01,\n", + " -3.84596047e-03, 8.94774017e-05, -2.89512996e-05, -5.22296930e-05,\n", + " 1.03659098e-02, -3.71562579e-04, -2.40163773e-04, -1.31161729e-04,\n", + " 2.27879341e-03]),\n", + " array([-4.37148217e-06, 2.15990256e-01, 9.58622781e-01, -9.09337101e-02,\n", + " 1.35762686e-05, -7.82704521e-06, 9.95856948e-01, 1.52939364e-04,\n", + " -4.62439024e-02, 3.12045094e-04, 1.97739696e-04, 1.04463698e-04,\n", + " -1.00522247e-02, -2.68900164e-05, 6.64318986e-01, 2.74889953e-01,\n", + " 1.63868749e-01, -1.78551932e-05, -3.93253656e-06, -1.61951647e-04,\n", + " 3.16443589e-02, -2.29584442e-04, -1.29213895e-04, -5.32844609e-05,\n", + " 6.88066471e-03]),\n", + " array([-4.08759759e-06, 2.56668228e-01, 9.71821494e-01, -8.28784543e-02,\n", + " 1.04629145e-05, -7.10646032e-06, 9.96559663e-01, 1.39024230e-04,\n", + " -4.38302987e-02, 3.07728641e-04, 1.96827266e-04, 1.05657243e-04,\n", + " -9.52932301e-03, -1.41017113e-05, 7.55569669e-01, 4.00863799e-01,\n", + " 3.23434841e-01, -1.24500242e-04, 2.19742847e-05, -2.78302689e-04,\n", + " 4.82720739e-02, -8.63290567e-05, -1.82485864e-05, 2.38708998e-05,\n", + " 1.04580329e-02]),\n", + " array([-3.25307323e-06, 3.02287459e-01, 9.90859572e-01, -7.09000261e-02,\n", + " 4.23283750e-06, -5.48612640e-06, 9.97483427e-01, 1.19103674e-04,\n", + " -4.09523268e-02, 3.10480719e-04, 2.01318587e-04, 1.10555346e-04,\n", + " -8.90789037e-03, -9.97092332e-07, 8.43235923e-01, 5.16164006e-01,\n", + " 4.80562702e-01, -2.50705042e-04, 4.92137531e-05, -3.98411122e-04,\n", + " 5.75594369e-02, 5.50415677e-05, 8.98264213e-05, 9.79620460e-05,\n", + " 1.24286530e-02]),\n", + " array([-2.33286871e-06, 3.52040911e-01, 1.01557053e+00, -5.49055543e-02,\n", + " -6.17320752e-06, -2.85717584e-06, 9.98491552e-01, 9.31720586e-05,\n", + " -3.82419052e-02, 3.19845469e-04, 2.10738762e-04, 1.18749540e-04,\n", + " -8.32179918e-03, 1.14787449e-05, 9.25179235e-01, 6.15275577e-01,\n", + " 6.41055311e-01, -4.19328736e-04, 7.83144906e-05, -5.18632306e-04,\n", + " 5.42084321e-02, 1.87295003e-04, 1.88403493e-04, 1.63883882e-04,\n", + " 1.17218237e-02]),\n", + " array([-2.10064335e-06, 4.04902859e-01, 1.04582647e+00, -3.47598504e-02,\n", + " -2.33985444e-05, 1.01289688e-06, 9.99395694e-01, 6.17671932e-05,\n", + " -3.60668358e-02, 3.33343122e-04, 2.22384092e-04, 1.27968347e-04,\n", + " -7.81130092e-03, 2.20774028e-05, 9.98849769e-01, 6.97440578e-01,\n", + " 8.06652976e-01, -6.93995063e-04, 1.11875100e-04, -6.28097310e-04,\n", + " 4.35013882e-02, 2.69953058e-04, 2.32906594e-04, 1.84376135e-04,\n", + " 1.02099652e-02]),\n", + " array([-1.66298287e-06, 4.58941869e-01, 1.06387932e+00, -1.63315689e-02,\n", + " -2.13548710e-05, 8.82796628e-07, 9.99866631e-01, 2.82516479e-05,\n", + " -3.58905857e-02, 3.32204641e-04, 2.24195865e-04, 1.30919681e-04,\n", + " -7.77335852e-03, 2.81676097e-05, 1.06098790e+00, 4.15812176e-01,\n", + " 7.37382361e-01, 8.15771819e-05, -1.96273444e-05, -6.70310905e-04,\n", + " 3.52500232e-03, -2.27696306e-05, 3.62354735e-05, 5.90266812e-05,\n", + " 7.58847999e-04]),\n", + " array([-1.56293581e-06, 5.13554255e-01, 1.06345467e+00, 1.43270848e-03,\n", + " -2.08090795e-05, 1.47542869e-06, 9.99998973e-01, -1.04353849e-05,\n", + " -3.60469201e-02, 3.25313550e-04, 2.20188398e-04, 1.29130158e-04,\n", + " -7.81915185e-03, 4.56018214e-06, 1.09231048e+00, 7.78169218e-03,\n", + " 7.10600158e-01, 2.09284581e-05, 8.88030607e-06, -7.73740656e-04,\n", + " -3.12668817e-03, -1.37821816e-04, -8.01493503e-05, -3.57904532e-05,\n", + " -9.15866654e-04]),\n", + " array([-1.65801093e-06, 5.68557847e-01, 1.04403891e+00, 2.07739976e-02,\n", + " -2.13949967e-05, 1.69173392e-06, 9.99784197e-01, -4.40230784e-05,\n", + " -3.53856644e-02, 3.12320043e-04, 2.10080819e-04, 1.22416739e-04,\n", + " -7.65947101e-03, -1.53329634e-05, 1.09124554e+00, -4.12673767e-01,\n", + " 7.73711326e-01, -2.47460508e-05, -7.40098470e-06, -6.71753871e-04,\n", + " 1.32251143e-02, -2.59870131e-04, -2.02151585e-04, -1.34268381e-04,\n", + " 3.19361676e-03]),\n", + " array([-3.13979733e-06, 6.23036847e-01, 1.01696113e+00, 3.97381365e-02,\n", + " -4.61654299e-06, 4.51036249e-06, 9.99210128e-01, -7.48096633e-05,\n", + " -3.36600636e-02, 2.87289242e-04, 1.92156997e-04, 1.10815289e-04,\n", + " -7.26005111e-03, -3.79729770e-05, 1.05489109e+00, -6.06505855e-01,\n", + " 7.58924419e-01, 6.71601198e-04, 8.25928840e-05, -6.15731697e-04,\n", + " 3.45120157e-02, -5.00616022e-04, -3.58476439e-04, -2.32028999e-04,\n", + " 7.98839809e-03]),\n", + " array([-4.59421778e-06, 6.74971846e-01, 9.94911224e-01, 5.42488069e-02,\n", + " 5.34203323e-06, 6.38473804e-06, 9.98527449e-01, -9.85470939e-05,\n", + " -3.22851805e-02, 2.66587008e-04, 1.76626116e-04, 1.00380430e-04,\n", + " -6.96582184e-03, -1.76767623e-05, 9.92743591e-01, -5.36588155e-01,\n", + " 5.81073928e-01, 3.98277785e-04, 5.65319792e-05, -4.74748613e-04,\n", + " 2.74976610e-02, -4.14044695e-04, -3.10617606e-04, -2.08697178e-04,\n", + " 5.88458537e-03]),\n", + " array([-5.52169750e-06, 7.23481568e-01, 9.78298611e-01, 6.47966737e-02,\n", + " 1.10147298e-05, 7.39167216e-06, 9.97898487e-01, -1.14828074e-04,\n", + " -3.14111848e-02, 2.53015903e-04, 1.66403347e-04, 9.34883173e-05,\n", + " -6.77941414e-03, 8.81243557e-07, 9.23853172e-01, -4.45200243e-01,\n", + " 4.22666062e-01, 2.26203520e-04, 3.03236500e-05, -3.25619608e-04,\n", + " 1.74799149e-02, -2.71422092e-04, -2.04455385e-04, -1.37842255e-04,\n", + " 3.72815395e-03]),\n", + " array([-5.62238619e-06, 7.67922663e-01, 9.67401017e-01, 7.17094556e-02,\n", + " 1.32825163e-05, 7.55035306e-06, 9.97425563e-01, -1.23983321e-04,\n", + " -3.12239692e-02, 2.47113421e-04, 1.62004477e-04, 9.05595345e-05,\n", + " -6.73970115e-03, 1.77690210e-05, 8.50864930e-01, -3.36971321e-01,\n", + " 2.77158163e-01, 8.90973047e-05, 3.64165074e-06, -1.83104926e-04,\n", + " 3.74431235e-03, -1.18049644e-04, -8.79774104e-05, -5.85756552e-05,\n", + " 7.94259839e-04]),\n", + " array([-4.79642075e-06, 8.07894149e-01, 9.62309212e-01, 7.51771540e-02,\n", + " 1.23999523e-05, 6.86364828e-06, 9.97170194e-01, -1.26645045e-04,\n", + " -3.16017432e-02, 2.48956604e-04, 1.63544423e-04, 9.17150382e-05,\n", + " -6.82120152e-03, 3.20199751e-05, 7.75889149e-01, -2.17846523e-01,\n", + " 1.39083617e-01, -3.80930941e-05, -2.29464798e-05, -5.32344851e-05,\n", + " -7.55547996e-03, 3.68636698e-05, 3.07989299e-05, 2.31100741e-05,\n", + " -1.63000733e-03]),\n", + " array([-3.14114798e-06, 8.43225060e-01, 9.63001444e-01, 7.52821566e-02,\n", + " 8.04507156e-06, 5.28321938e-06, 9.97162272e-01, -1.23669881e-04,\n", + " -3.22741262e-02, 2.58351030e-04, 1.70907736e-04, 9.69024905e-05,\n", + " -6.96617635e-03, 4.24816127e-05, 7.00697168e-01, -9.23280827e-02,\n", + " 4.21203978e-03, -1.78479678e-04, -4.98885058e-05, 5.95032867e-05,\n", + " -1.34476604e-02, 1.87888513e-04, 1.47266265e-04, 1.03749046e-04,\n", + " -2.89949660e-03]),\n", + " array([-9.79341103e-07, 8.73962352e-01, 9.69407300e-01, 7.19996030e-02,\n", + " -7.82612570e-07, 2.65176668e-06, 9.97404661e-01, -1.16137713e-04,\n", + " -3.30314862e-02, 2.74703805e-04, 1.83601011e-04, 1.05771866e-04,\n", + " -7.13199273e-03, 4.75734885e-05, 6.26897538e-01, 3.64324979e-02,\n", + " -1.31659687e-01, -3.59414352e-04, -7.94844325e-05, 1.50643342e-04,\n", + " -1.51471997e-02, 3.27055498e-04, 2.53865500e-04, 1.77387509e-04,\n", + " -3.31632759e-03]),\n", + " array([ 1.05872766e-06, 9.00347281e-01, 9.81580090e-01, 6.52512918e-02,\n", + " -1.72380629e-05, -1.50716642e-06, 9.97868863e-01, -1.05875528e-04,\n", + " -3.42434175e-02, 2.94495819e-04, 1.97989606e-04, 1.15424067e-04,\n", + " -7.41760846e-03, 4.50963728e-05, 5.56068369e-01, 1.68907199e-01,\n", + " -2.70570844e-01, -6.67762139e-04, -1.18373023e-04, 2.05243718e-04,\n", + " -2.42386253e-02, 3.95840284e-04, 2.87771893e-04, 1.93044020e-04,\n", + " -5.71231474e-03]),\n", + " array([ 2.34253161e-06, 9.23745098e-01, 9.91901022e-01, 5.88378581e-02,\n", + " -1.31739447e-05, -1.07696196e-06, 9.98267552e-01, -9.76856588e-05,\n", + " -3.44198964e-02, 2.99309005e-04, 2.02914838e-04, 1.19453449e-04,\n", + " -7.46685116e-03, 2.98207792e-05, 4.89921940e-01, 1.46873687e-01,\n", + " -2.57032999e-01, 1.63230522e-04, 1.10102649e-05, 1.63797376e-04,\n", + " -3.52957826e-03, 9.62637144e-05, 9.85046436e-05, 8.05876404e-05,\n", + " -9.84853827e-04]),\n", + " array([ 3.08263924e-06, 9.44779347e-01, 9.97437028e-01, 5.38384886e-02,\n", + " -8.74459093e-06, -4.94580554e-07, 9.98549657e-01, -8.97321400e-05,\n", + " -3.40984359e-02, 2.97900710e-04, 2.02360882e-04, 1.19434364e-04,\n", + " -7.39050277e-03, 1.60373834e-05, 4.30472030e-01, 6.26914137e-02,\n", + " -2.00293107e-01, 1.78171884e-04, 1.54770251e-05, 1.59070375e-04,\n", + " 6.42921009e-03, -2.81658962e-05, -1.10791237e-05, -3.81697740e-07,\n", + " 1.52696766e-03]),\n", + " array([ 3.42259803e-06, 9.63353642e-01, 1.00113162e+00, 4.90115378e-02,\n", + " -5.61583393e-06, -1.98821594e-07, 9.98798212e-01, -8.12442780e-05,\n", + " -3.39020111e-02, 2.95720280e-04, 2.01025762e-04, 1.18774737e-04,\n", + " -7.34486678e-03, 7.32563051e-06, 3.77112307e-01, 3.53443245e-02,\n", + " -1.93334030e-01, 1.25597635e-04, 6.76863041e-06, 1.69757240e-04,\n", + " 3.92849505e-03, -4.36085892e-05, -2.67024111e-05, -1.31925337e-05,\n", + " 9.12719947e-04]),\n", + " array([ 3.49823660e-06, 9.79599120e-01, 1.00394874e+00, 4.39790030e-02,\n", + " -3.58949019e-06, -1.33583036e-07, 9.99032456e-01, -7.23119448e-05,\n", + " -3.38055486e-02, 2.93750039e-04, 1.99795587e-04, 1.18145542e-04,\n", + " -7.32408038e-03, 1.78360091e-06, 3.28739797e-01, 2.59178130e-02,\n", + " -2.01519546e-01, 8.10971769e-05, -2.33825617e-07, 1.78646664e-04,\n", + " 1.92925099e-03, -3.94048340e-05, -2.46034931e-05, -1.25839039e-05,\n", + " 4.15727887e-04]),\n", + " array([ 3.40402523e-06, 9.93747934e-01, 1.00598175e+00, 3.87956965e-02,\n", + " -2.28131934e-06, -1.96626130e-07, 9.99247164e-01, -6.31902418e-05,\n", + " -3.37417895e-02, 2.92065824e-04, 1.98742911e-04, 1.17605212e-04,\n", + " -7.31126627e-03, -1.80807624e-06, 2.85370909e-01, 1.71178402e-02,\n", + " -2.07510293e-01, 5.21686679e-05, -4.07521977e-06, 1.82434060e-04,\n", + " 1.27518059e-03, -3.36842950e-05, -2.10535245e-05, -1.08065954e-05,\n", + " 2.56282140e-04]),\n", + " array([ 3.20142501e-06, 1.00604948e+00, 1.00720895e+00, 3.36031210e-02,\n", + " -1.42300628e-06, -3.19693110e-07, 9.99435256e-01, -5.41262435e-05,\n", + " -3.36858038e-02, 2.90645771e-04, 1.97848151e-04, 1.17139378e-04,\n", + " -7.30012932e-03, -4.12136159e-06, 2.47163042e-01, 6.67885395e-03,\n", + " -2.07839477e-01, 3.40921747e-05, -5.77563708e-06, 1.81279966e-04,\n", + " 1.11971419e-03, -2.84010680e-05, -1.78951874e-05, -9.31668797e-06,\n", + " 2.22739165e-04]),\n", + " array([ 2.93064572e-06, 1.01674834e+00, 1.00768185e+00, 2.85285416e-02,\n", + " -8.50449470e-07, -4.65134082e-07, 9.99592978e-01, -4.53321161e-05,\n", + " -3.36342126e-02, 2.89475421e-04, 1.97099977e-04, 1.16740455e-04,\n", + " -7.28980591e-03, -5.57718839e-06, 2.14152421e-01, -3.84863880e-03,\n", + " -2.03081414e-01, 2.26380300e-05, -6.29310503e-06, 1.75882548e-04,\n", + " 1.03182359e-03, -2.34070000e-05, -1.49634927e-05, -7.97846989e-06,\n", + " 2.06468112e-04]),\n", + " array([ 2.61854905e-06, 1.02608091e+00, 1.00751683e+00, 2.36786415e-02,\n", + " -4.60857928e-07, -6.13621129e-07, 9.99719622e-01, -3.69880699e-05,\n", + " -3.35884551e-02, 2.88539952e-04, 1.96490145e-04, 1.16405100e-04,\n", + " -7.28065485e-03, -6.45377976e-06, 1.86225550e-01, -1.30370707e-02,\n", + " -1.94062320e-01, 1.53220081e-05, -6.21432786e-06, 1.66880925e-04,\n", + " 9.15151600e-04, -1.87093789e-05, -1.21966387e-05, -6.70709339e-06,\n", + " 1.83021137e-04]),\n", + " array([ 2.28353972e-06, 1.03427356e+00, 1.00686241e+00, 1.91486637e-02,\n", + " -1.85000294e-07, -7.55857651e-07, 9.99816648e-01, -2.92484801e-05,\n", + " -3.35497249e-02, 2.87817843e-04, 1.96007352e-04, 1.16129384e-04,\n", + " -7.27297665e-03, -6.93482700e-06, 1.63142835e-01, -2.00922750e-02,\n", + " -1.81240828e-01, 1.07871308e-05, -5.86327458e-06, 1.54791796e-04,\n", + " 7.74603026e-04, -1.44421630e-05, -9.65586335e-06, -5.51430703e-06,\n", + " 1.53564017e-04]),\n", + " array([ 1.93879667e-06, 1.04153939e+00, 1.00587922e+00, 1.50280305e-02,\n", + " 2.81731693e-08, -8.87932672e-07, 9.99887073e-01, -2.22471594e-05,\n", + " -3.35185109e-02, 2.87282971e-04, 1.95638135e-04, 1.15908909e-04,\n", + " -7.26689476e-03, -7.13659425e-06, 1.44560161e-01, -2.46180958e-02,\n", + " -1.64849514e-01, 8.30017286e-06, -5.41270496e-06, 1.40026413e-04,\n", + " 6.24280794e-04, -1.06974571e-05, -7.38432639e-06, -4.40950668e-06,\n", + " 1.21637880e-04]),\n", + " array([ 1.59465972e-06, 1.04807414e+00, 1.00473035e+00, 1.14023994e-02,\n", + " 2.18942544e-07, -1.00892655e-06, 9.99934991e-01, -1.61014868e-05,\n", + " -3.34948969e-02, 2.86913551e-04, 1.95373852e-04, 1.15743436e-04,\n", + " -7.26243033e-03, -7.12393057e-06, 1.30042358e-01, -2.64235149e-02,\n", + " -1.45037990e-01, 7.42837092e-06, -4.95627881e-06, 1.22913453e-04,\n", + " 4.72279073e-04, -7.38838756e-06, -5.28565907e-06, -3.30945798e-06,\n", + " 8.92886790e-05]),\n", + " array([ 1.26057714e-06, 1.05405172e+00, 1.00357608e+00, 8.35412766e-03,\n", + " 4.11464602e-07, -1.12048206e-06, 9.99965104e-01, -1.09144794e-05,\n", + " -3.34784326e-02, 2.86721141e-04, 1.95235216e-04, 1.15654489e-04,\n", + " -7.25946836e-03, -6.92041828e-06, 1.19072409e-01, -2.54427303e-02,\n", + " -1.21936865e-01, 7.52623028e-06, -4.57522676e-06, 1.03740148e-04,\n", + " 3.29286917e-04, -3.84820971e-06, -2.77272189e-06, -1.77895234e-06,\n", + " 5.92392871e-05]),\n", + " array([ 9.46446101e-07, 1.05961964e+00, 1.00256942e+00, 5.96135847e-03,\n", + " 5.62310016e-07, -1.22988463e-06, 9.99982231e-01, -6.77163140e-06,\n", + " -3.34660685e-02, 2.86863264e-04, 1.95369769e-04, 1.15756561e-04,\n", + " -7.25723079e-03, -6.52362075e-06, 1.11059043e-01, -2.17252394e-02,\n", + " -9.57132426e-02, 5.88952904e-06, -4.46497552e-06, 8.28569593e-05,\n", + " 2.47282034e-04, 2.84246358e-06, 2.69105825e-06, 2.04145632e-06,\n", + " 4.47513756e-05]),\n", + " array([ 6.61078397e-07, 1.06489463e+00, 1.00183915e+00, 4.29122593e-03,\n", + " 3.17853760e-07, -1.36090549e-06, 9.99990793e-01, -3.72616286e-06,\n", + " -3.34391177e-02, 2.88102741e-04, 1.96446749e-04, 1.16543166e-04,\n", + " -7.25095009e-03, -5.96715966e-06, 1.05344375e-01, -1.56862550e-02,\n", + " -6.68061870e-02, -9.89167899e-06, -5.21959614e-06, 6.09093709e-05,\n", + " 5.39015811e-04, 2.47895464e-05, 2.15395894e-05, 1.57320839e-05,\n", + " 1.25613970e-04]),\n", + " array([ 3.97148583e-07, 1.06996230e+00, 1.00096692e+00, 3.35879793e-03,\n", + " -1.90733039e-06, -1.57458853e-06, 9.99994359e-01, -1.77401096e-06,\n", + " -3.32819297e-02, 2.93502329e-04, 2.00917040e-04, 1.19647534e-04,\n", + " -7.21175170e-03, -5.60429905e-06, 1.01217078e-01, -1.82194431e-02,\n", + " -3.72973942e-02, -8.90940409e-05, -8.17695399e-06, 3.90430379e-05,\n", + " 3.14375924e-03, 1.07991755e-04, 8.94058384e-05, 6.20873595e-05,\n", + " 7.83967809e-04])],\n", + " [array([ 8.50629220e+00, 8.24344926e+00, 8.24153176e+00, 8.50789101e+00,\n", + " 3.39024320e-04, -7.59256686e-02, -1.24021299e-03, -3.11669281e-04,\n", + " 2.03330707e-04, -2.72155936e-02]),\n", + " array([ 7.51639327e+00, 7.34560951e+00, 7.34365842e+00, 7.51820719e+00,\n", + " 9.45813400e-05, 3.87918264e-02, -1.79786790e-03, -8.70838746e-04,\n", + " -2.19179295e-04, 8.97001302e-03]),\n", + " array([ 6.71063400e+00, 6.62278159e+00, 6.62089588e+00, 6.71250511e+00,\n", + " 4.32240085e-06, 3.57381977e-02, -1.67577932e-03, -8.37592466e-04,\n", + " -2.38761940e-04, 9.45697523e-03]),\n", + " array([ 6.07872787e+00, 6.06017659e+00, 6.05847166e+00, 6.08049272e+00,\n", + " -5.08394522e-05, 3.14686521e-02, -1.53859040e-03, -7.74428565e-04,\n", + " -2.26421887e-04, 9.26264640e-03]),\n", + " array([ 5.60770007e+00, 5.63920223e+00, 5.63778632e+00, 5.60921816e+00,\n", + " -8.16539960e-05, 3.05046875e-02, -1.41613865e-03, -7.13170422e-04,\n", + " -2.08294451e-04, 9.77008866e-03]),\n", + " array([ 5.28197437e+00, 5.33874609e+00, 5.33771336e+00, 5.28312671e+00,\n", + " -9.21527976e-05, 3.60562712e-02, -1.31703883e-03, -6.64123203e-04,\n", + " -1.93435591e-04, 1.18688828e-02]),\n", + " array([ 5.08467115e+00, 5.13495977e+00, 5.13438645e+00, 5.08535287e+00,\n", + " -8.04041112e-05, 5.02558441e-02, -1.36305712e-03, -7.52861166e-04,\n", + " -2.82934849e-04, 1.60322511e-02]),\n", + " array([ 3.64138469e+00, 3.95629103e+00, 3.93796287e+00, 3.65967730e+00,\n", + " -1.79318590e-05, -1.65892966e-02, -4.14885880e-03, -3.02328710e-03,\n", + " -1.91399430e-03, -3.32166938e-04]),\n", + " array([ 8.96169981e-02, 1.57216282e-02, 1.57166305e-02, 8.96742180e-02,\n", + " -4.38476930e-05, -3.57062077e-02, -3.24813901e-04, -3.13301769e-04,\n", + " -2.40405256e-04, -1.20041834e-02]),\n", + " array([ 9.41940210e-02, -1.87956647e-02, -1.87451505e-02, 9.41990939e-02,\n", + " -4.32722709e-05, -2.42280155e-02, -1.12520455e-04, -1.05350175e-04,\n", + " -7.87683408e-05, -9.14769975e-03]),\n", + " array([ 2.83949072e-01, -2.01004636e-02, -2.00016515e-02, 2.83863468e-01,\n", + " -1.33914969e-05, 2.07161040e-02, -7.64368186e-05, -6.37476624e-05,\n", + " -4.28102699e-05, 1.52832988e-03]),\n", + " array([ 7.94156498e-01, -1.26167881e-03, -1.15940658e-03, 7.94114709e-01,\n", + " -5.02179693e-05, 1.30458157e-01, -9.89968139e-05, -5.88218691e-05,\n", + " -2.47753373e-05, 2.70647418e-02]),\n", + " array([ 1.07159938e+00, 2.53170336e-02, 2.53813285e-02, 1.07162390e+00,\n", + " -7.22354003e-05, 1.79561349e-01, -1.26630932e-04, -6.89635008e-05,\n", + " -2.39909089e-05, 3.80459519e-02]),\n", + " array([ 1.22501386e+00, 5.77896709e-02, 5.77846526e-02, 1.22512611e+00,\n", + " -8.24916069e-05, 1.85711825e-01, -2.28640964e-04, -1.58419050e-04,\n", + " -8.83362824e-05, 3.78855821e-02]),\n", + " array([ 3.08837154e+00, 3.57068596e+00, 3.56285767e+00, 3.09578240e+00,\n", + " 3.07275252e-04, -6.64193712e-02, -2.02346468e-03, -1.35855573e-03,\n", + " -7.75457674e-04, -1.26159217e-02]),\n", + " array([ 3.90597677e+00, 5.03330334e+00, 5.03279989e+00, 3.90650741e+00,\n", + " -1.94760401e-05, -1.77584173e-01, -1.03968519e-03, -5.07948587e-04,\n", + " -1.31958297e-04, -3.61287020e-02]),\n", + " array([ 4.02566419e+00, 5.05153397e+00, 5.05069999e+00, 4.02656118e+00,\n", + " -5.73130269e-05, -1.70243606e-01, -1.04320636e-03, -4.91196333e-04,\n", + " -1.10471434e-04, -3.55729465e-02]),\n", + " array([ 4.12711875e+00, 5.05872564e+00, 5.05767257e+00, 4.12826179e+00,\n", + " -8.42924664e-05, -1.57528066e-01, -1.07919799e-03, -5.13398291e-04,\n", + " -1.22316320e-04, -3.32073230e-02]),\n", + " array([ 4.18810302e+00, 5.05765228e+00, 5.05649437e+00, 4.18937269e+00,\n", + " -1.05236909e-04, -1.48634939e-01, -1.09865879e-03, -5.25826782e-04,\n", + " -1.29188254e-04, -3.14872504e-02]),\n", + " array([ 4.20985957e+00, 5.04991923e+00, 5.04877194e+00, 4.21113404e+00,\n", + " -1.19516143e-04, -1.45287589e-01, -1.09790379e-03, -5.24761404e-04,\n", + " -1.28125557e-04, -3.09381608e-02]),\n", + " array([ 4.18481845e+00, 5.03681501e+00, 5.03579131e+00, 4.18597715e+00,\n", + " -1.26251245e-04, -1.50654306e-01, -1.07696482e-03, -5.10539731e-04,\n", + " -1.19565268e-04, -3.23831307e-02]),\n", + " array([ 4.10546143e+00, 5.02044370e+00, 5.01965041e+00, 4.10638954e+00,\n", + " -1.24994802e-04, -1.67603931e-01, -1.03954965e-03, -4.86991893e-04,\n", + " -1.06620934e-04, -3.65302166e-02]),\n", + " array([ 4.03650698e+00, 5.00509363e+00, 5.00462944e+00, 4.03709642e+00,\n", + " -1.12648692e-04, -1.80517926e-01, -1.02655875e-03, -4.92003581e-04,\n", + " -1.17728549e-04, -3.94752964e-02]),\n", + " array([ 1.99124345e+00, 1.74926245e+00, 1.74250763e+00, 1.99781996e+00,\n", + " 9.12623428e-05, 2.78406142e-02, -1.59373915e-03, -1.13264749e-03,\n", + " -6.95816120e-04, 4.40520030e-03]),\n", + " array([ 9.78055963e-01, 8.51746425e-01, 8.51076914e-01, 9.78922673e-01,\n", + " -1.75613813e-04, 2.02016188e-02, -4.21446997e-04, -2.88908204e-04,\n", + " -1.64554716e-04, 4.09716419e-03]),\n", + " array([ 6.71977992e-01, 9.69863883e-01, 9.68959239e-01, 6.72718094e-01,\n", + " 1.49107357e-04, -4.68754451e-02, -4.05542414e-04, -2.84131485e-04,\n", + " -1.66473383e-04, -9.46825335e-03]),\n", + " array([ 2.62855341e+00, 2.47692879e+00, 2.47066117e+00, 2.63495654e+00,\n", + " -7.19030370e-05, 3.79321271e-02, -1.65991889e-03, -1.13252402e-03,\n", + " -6.60098822e-04, 9.07281854e-03]),\n", + " array([ 5.00452231e+00, 4.03007506e+00, 4.02951149e+00, 5.00495033e+00,\n", + " 1.28973775e-04, 1.74127457e-01, -1.01021267e-03, -4.77795536e-04,\n", + " -1.06903672e-04, 3.74585930e-02]),\n", + " array([ 5.01224110e+00, 4.15751396e+00, 4.15663471e+00, 5.01295458e+00,\n", + " 1.57827724e-04, 1.51175994e-01, -1.01769093e-03, -4.66378082e-04,\n", + " -9.00997996e-05, 3.24638986e-02]),\n", + " array([ 5.01688253e+00, 4.24789462e+00, 4.24682728e+00, 5.01777711e+00,\n", + " 1.63628788e-04, 1.34020009e-01, -1.04663311e-03, -4.83453721e-04,\n", + " -9.86873434e-05, 2.86021439e-02]),\n", + " array([ 5.01713217e+00, 4.28147156e+00, 4.28034196e+00, 5.01809585e+00,\n", + " 1.56376701e-04, 1.29025678e-01, -1.05908408e-03, -4.91563023e-04,\n", + " -1.03306779e-04, 2.76058248e-02]),\n", + " array([ 5.01387049e+00, 4.27720242e+00, 4.27613687e+00, 5.01478635e+00,\n", + " 1.39701607e-04, 1.31535200e-01, -1.05351439e-03, -4.88209772e-04,\n", + " -1.01485666e-04, 2.83516147e-02]),\n", + " array([ 5.00885905e+00, 4.25172172e+00, 4.25084376e+00, 5.00960962e+00,\n", + " 1.15622413e-04, 1.37031535e-01, -1.03465446e-03, -4.77134705e-04,\n", + " -9.56817691e-05, 2.96937037e-02]),\n", + " array([ 5.00378468e+00, 4.25546726e+00, 4.25490704e+00, 5.00425308e+00,\n", + " 7.37617778e-05, 1.32143969e-01, -1.05680513e-03, -5.10835008e-04,\n", + " -1.26401225e-04, 2.82880855e-02]),\n", + " array([ 3.43970297e+00, 3.45086903e+00, 3.44314310e+00, 3.44774450e+00,\n", + " -2.26403050e-04, 8.37883331e-03, -2.12583029e-03, -1.43882241e-03,\n", + " -8.29119710e-04, 2.64146408e-03]),\n", + " array([ 2.84861757e+00, 3.13481974e+00, 3.13244318e+00, 2.85099739e+00,\n", + " -3.83679487e-06, -4.72521163e-02, -1.10507490e-03, -6.78915679e-04,\n", + " -3.30775186e-04, -9.82777982e-03]),\n", + " array([ 3.41477756e+00, 3.46439884e+00, 3.46271461e+00, 3.41643038e+00,\n", + " 2.48976105e-05, -9.80383388e-03, -1.01038554e-03, -5.58772420e-04,\n", + " -2.18935757e-04, -2.23643269e-03]),\n", + " array([ 3.60209615e+00, 3.56481586e+00, 3.56312069e+00, 3.60376926e+00,\n", + " 1.77197912e-05, 6.21243769e-03, -1.02838160e-03, -5.59550290e-04,\n", + " -2.10856484e-04, 1.26302288e-03]),\n", + " array([ 3.60895772e+00, 3.57934837e+00, 3.57757511e+00, 3.61072033e+00,\n", + " 8.37586917e-06, 5.41909218e-03, -1.04165780e-03, -5.68598847e-04,\n", + " -2.16328292e-04, 1.14934657e-03]),\n", + " array([ 3.58735305e+00, 3.58787331e+00, 3.58604473e+00, 3.58917920e+00,\n", + " 1.27190548e-06, 1.70514518e-04, -1.04910695e-03, -5.74725285e-04,\n", + " -2.20833590e-04, 3.11191270e-05]),\n", + " array([ 3.57822239e+00, 3.60714852e+00, 3.60528135e+00, 3.58009288e+00,\n", + " -3.98915749e-06, -4.95573898e-03, -1.05639024e-03, -5.79986478e-04,\n", + " -2.24191753e-04, -1.07941415e-03]),\n", + " array([ 3.58158120e+00, 3.63460011e+00, 3.63270185e+00, 3.58348693e+00,\n", + " -7.99379502e-06, -9.34150579e-03, -1.06477212e-03, -5.85436613e-04,\n", + " -2.27184041e-04, -2.03334609e-03]),\n", + " array([ 3.59157240e+00, 3.66608407e+00, 3.66415820e+00, 3.59350878e+00,\n", + " -1.11058386e-05, -1.32532786e-02, -1.07386940e-03, -5.91117958e-04,\n", + " -2.30086955e-04, -2.88411365e-03]),\n", + " array([ 3.60450031e+00, 3.69914482e+00, 3.69719339e+00, 3.60646456e+00,\n", + " -1.35670633e-05, -1.69121593e-02, -1.08320338e-03, -5.96851758e-04,\n", + " -2.32923039e-04, -3.67933218e-03]),\n", + " array([ 3.61859775e+00, 3.73250279e+00, 3.73052802e+00, 3.62058710e+00,\n", + " -1.55391424e-05, -2.04094112e-02, -1.09227382e-03, -6.02320695e-04,\n", + " -2.35535412e-04, -4.43908588e-03]),\n", + " array([ 3.63295895e+00, 3.76534508e+00, 3.76335398e+00, 3.63496587e+00,\n", + " -1.70512312e-05, -2.37616508e-02, -1.09969955e-03, -6.06420477e-04,\n", + " -2.37166744e-04, -5.16686652e-03]),\n", + " array([ 3.64702412e+00, 3.79673667e+00, 3.79476009e+00, 3.64901685e+00,\n", + " -1.77783224e-05, -2.68870477e-02, -1.09987467e-03, -6.04512356e-04,\n", + " -2.34511043e-04, -5.84306739e-03]),\n", + " array([ 3.65945045e+00, 3.82277855e+00, 3.82095144e+00, 3.66129162e+00,\n", + " -1.64604520e-05, -2.92263763e-02, -1.06912090e-03, -5.77055470e-04,\n", + " -2.13657607e-04, -6.33465167e-03]),\n", + " array([ 3.59901984e+00, 3.75685964e+00, 3.75572955e+00, 3.60015631e+00,\n", + " -1.03565193e-05, -2.73492582e-02, -9.03554345e-04, -4.44869122e-04,\n", + " -1.22535434e-04, -5.82654612e-03])],\n", " True)" ] }, @@ -1201,63 +690,37 @@ "metadata": {}, "outputs": [], "source": [ - "displayTrajectory(robot, ddp.xs, dt)" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [], - "source": [ - "# Control trajectory\n", - "f1 = []\n", - "f2 = [];\n", - "f3 = [];\n", - "f4 = [];\n", - "\n", - "for u in ddp.us:\n", - " f1.append(u[0])\n", - " f2.append(u[1])\n", - " f3.append(u[2])\n", - " f4.append(u[3])\n", - "\n", - "# State trajectory\n", - "Xx = [];\n", - "Xy = [];\n", - "Xz = [];\n", - "Vx = [];\n", - "Vy = [];\n", - "Vz = [];\n", - "\n", - "\n", - "for x in ddp.xs:\n", - " Xx.append(x[0])\n", - " Xy.append(x[1])\n", - " Xz.append(x[2])\n", - " Vx.append(x[13])\n", - " Vy.append(x[14])\n", - " Vz.append(x[15])" + "displayTrajectory(robot, ddp.xs, dt)\n" ] }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 14, "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "Text(0.5,0,'[s]')" + "50" ] }, - "execution_count": 9, + "execution_count": 14, "metadata": {}, "output_type": "execute_result" - }, + } + ], + "source": [ + "np.size(ddp.xs,0)" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "<Figure size 1080x720 with 4 Axes>" ] @@ -1269,19 +732,46 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "<Figure size 432x288 with 1 Axes>" + "<Figure size 1080x720 with 2 Axes>" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" + } + ], + "source": [ + "distanceRotorCOG = 0.1525\n", + "cf = 6.6e-5\n", + "cm = 1e-6\n", + "pltUAM = PlotUAM(ddp.xs, ddp.us, np.size(ddp.us,0), dt, distanceRotorCOG, cf, cm)\n", + "\n", + "fig, axs = pltUAM.plotMotorForces()\n", + "fig,axs = pltUAM.plotActuation()" + ] + }, + { + "cell_type": "code", + "execution_count": 32, + "metadata": {}, + "outputs": [ + { + "ename": "AttributeError", + "evalue": "'list' object has no attribute 'set_title'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m-----------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mAttributeError\u001b[0m Traceback (most recent call last)", + "\u001b[0;32m<ipython-input-32-6afaa0e0f774>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m 3\u001b[0m \u001b[0mfig\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfigure\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 4\u001b[0m \u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplot\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcontrol\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 5\u001b[0;31m \u001b[0maxs\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mset_title\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'Moments'\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m", + "\u001b[0;31mAttributeError\u001b[0m: 'list' object has no attribute 'set_title'" + ] }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "<Figure size 432x288 with 1 Axes>" ] @@ -1293,42 +783,12 @@ } ], "source": [ - "import matplotlib.pyplot as plt\n", - "t = np.arange(0., 1-dt, dt)\n", - "\n", - "fig, axs = plt.subplots(2,2, figsize=(15,10))\n", - "fig.suptitle('Motor forces')\n", - "axs[0, 0].plot(t,f1)\n", - "axs[0, 0].set_title('Motor 1')\n", - "axs[0, 1].plot(t,f2)\n", - "axs[0, 1].set_title('Motor 2')\n", - "axs[1, 0].plot(t,f3)\n", - "axs[1, 0].set_title('Motor 3')\n", - "axs[1, 1].plot(t,f4)\n", - "axs[1, 1].set_title('Motor 4')\n", - "\n", - "plt.figure()\n", - "t = np.append(t, 1)\n", - "plt.plot(t,Xx,t,Xy,t,Xz)\n", - "plt.legend(['x','y','z'])\n", - "plt.title('State - Position')\n", - "plt.ylabel('Position, [m]')\n", - "plt.xlabel('[s]')\n", - "\n", - "plt.figure()\n", - "plt.plot(t,Vx,t,Vy,t,Vz)\n", - "plt.legend(['x','y','z'])\n", - "plt.title('State - Velocity')\n", - "plt.ylabel('Velocity, [m/s]')\n", - "plt.xlabel('[s]')" + "t = np.arange(0, 2*T*dt-dt, dt)\n", + "control = np.vstack(ddp.us)\n", + "fig = plt.figure()\n", + "axs = plt.plot(t, control[:,1])\n", + "axs.set_title('Moments')" ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { @@ -1347,7 +807,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4,