diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py
index d2bba9a95d4ddafa44d7c74b9e1e528b5c2d0299..67672107820123c7f8cf2e9f1c3e063830dede76 100644
--- a/crocoddyl/actuation.py
+++ b/crocoddyl/actuation.py
@@ -13,12 +13,12 @@ class ActuationModelDoublePendulum:
         self.actLink = actLink
 
     def calc(self, data, x, u):
-        S = np.zeros([self.nv,self.nu])
+        S = np.zeros([self.nv, self.nu])
         if self.actLink == 1:
             S[0] = 1
         else:
             S[1] = 1
-        data.a[:] = np.dot(S,u)
+        data.a[:] = np.dot(S, u)
         return data.a
 
     def calcDiff(self, data, x, u, recalc=True):
@@ -29,6 +29,7 @@ class ActuationModelDoublePendulum:
     def createData(self, pinocchioData):
         return ActuationDataDoublePendulum(self, pinocchioData)
 
+
 class ActuationDataDoublePendulum:
     def __init__(self, model, pinocchioData):
         self.pinocchio = pinocchioData
@@ -38,9 +39,9 @@ class ActuationDataDoublePendulum:
         self.Ax = self.A[:, :ndx]
         self.Au = self.A[:, ndx:]
         if model.actLink == 1:
-            self.Au[0,0] = 1
+            self.Au[0, 0] = 1
         else:
-            self.Au[1,0] = 1
+            self.Au[1, 0] = 1
 
 
 class ActuationModelUAM:
@@ -63,12 +64,11 @@ class ActuationModelUAM:
         self.cf = coefF
 
     def calc(self, data, x, u):
-        # data.a[2:] = u
         d, cf, cm = self.d, self.cf, self.cf
-        S = np.array(np.zeros([self.nv,self.nu]))
-        S[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
+        S = np.array(np.zeros([self.nv, self.nu]))
+        S[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
         np.fill_diagonal(S[6:, 4:], 1)
-        data.a = np.dot(S,u)
+        data.a = np.dot(S, u)
         return data.a
 
     def calcDiff(self, data, x, u, recalc=True):
@@ -79,6 +79,7 @@ class ActuationModelUAM:
     def createData(self, pinocchioData):
         return ActuationDataUAM(self, pinocchioData)
 
+
 class ActuationDataUAM:
     def __init__(self, model, pinocchioData):
         self.pinocchio = pinocchioData
@@ -88,9 +89,9 @@ class ActuationDataUAM:
         self.A = np.zeros([nv, ndx + nu])  # result of calcDiff
         self.Ax = self.A[:, :ndx]
         self.Au = self.A[:, ndx:]
-        self.Au[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
+        self.Au[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
         np.fill_diagonal(self.Au[6:, 4:], 1)
-        #np.fill_diagonal(self.Au[2:, :], 1)
+        # np.fill_diagonal(self.Au[2:, :], 1)
 # This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment
 # [      0,      0,     0,     0]
 # [      0,      0,     0,     0]
@@ -105,6 +106,7 @@ class ActuationModelFreeFloating:
     This model transforms an actuation u into a joint torque tau.
     We implement here the simplest model: tau = S.T*u, where S is constant.
     '''
+
     def __init__(self, pinocchioModel):
         self.pinocchio = pinocchioModel
         if (pinocchioModel.joints[1].shortname() != 'JointModelFreeFlyer'):
diff --git a/crocoddyl/cost.py b/crocoddyl/cost.py
index b2cc49845c2d803f62a30bcaa7109283e35b2048..08bbd7b6f796555e219499ffd3263b9189ef7b55 100644
--- a/crocoddyl/cost.py
+++ b/crocoddyl/cost.py
@@ -15,6 +15,7 @@ class CostModelPinocchio:
     can be retrieved from Pinocchio data, through the calc and calcDiff
     functions, respectively.
     """
+
     def __init__(self, pinocchioModel, ncost, withResiduals=True, nu=None):
         self.ncost = ncost
         self.nq = pinocchioModel.nq
@@ -40,6 +41,7 @@ class CostDataPinocchio:
 
     It stores the data corresponting to the CostModelPinocchio class.
     """
+
     def __init__(self, model, pinocchioData):
         ncost, nv, ndx, nu = model.ncost, model.nv, model.ndx, model.nu
         self.pinocchio = pinocchioData
@@ -70,6 +72,7 @@ class CostDataPinocchio:
 class CostModelNumDiff(CostModelPinocchio):
     """ Abstract cost model that uses NumDiff for derivative computation.
     """
+
     def __init__(self, costModel, State, withGaussApprox=False, reevals=[]):
         '''
         reevals is a list of lambdas of (pinocchiomodel,pinocchiodata,x,u) to be
diff --git a/crocoddyl/differential_action.py b/crocoddyl/differential_action.py
index acf64d09b37a90599fd13f0acd3cc98f5f5aa88e..fceda169826f91d736559cae3e8bd860cc0d41e6 100644
--- a/crocoddyl/differential_action.py
+++ b/crocoddyl/differential_action.py
@@ -4,6 +4,7 @@ import pinocchio
 from .state import StatePinocchio, StateVector
 from .utils import EPS, a2m, m2a, randomOrthonormalMatrix
 
+
 class DifferentialActionModelAbstract:
     """ Abstract class for the differential action model.
 
@@ -13,6 +14,7 @@ class DifferentialActionModelAbstract:
     the dynamics, cost functions and their derivatives. These computations are
     mainly carry on inside calc() and calcDiff(), respectively.
     """
+
     def __init__(self, nq, nv, nu):
         self.nq = nq
         self.nv = nv
diff --git a/examples/notebooks/2DOFs.ipynb b/examples/notebooks/2DOFs.ipynb
index 9431ea8eff5de6f8a24aff2793fa520a6d81874c..0b50f6fd1aaa0906cb86cb847a7c28a77db7fae4 100644
--- a/examples/notebooks/2DOFs.ipynb
+++ b/examples/notebooks/2DOFs.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 1,
+   "execution_count": 16,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -36,7 +36,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 2,
+   "execution_count": 17,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -61,7 +61,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 3,
+   "execution_count": 18,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -72,7 +72,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 4,
+   "execution_count": 19,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -87,9 +87,9 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 23,
+   "execution_count": 20,
    "metadata": {
-    "scrolled": false
+    "scrolled": true
    },
    "outputs": [
     {
@@ -451,7 +451,7 @@
        " True)"
       ]
      },
-     "execution_count": 23,
+     "execution_count": 20,
      "metadata": {},
      "output_type": "execute_result"
     }
@@ -463,16 +463,14 @@
     "ddp.callback.append(CallbackDDPLogger())\n",
     "\n",
     "us0 = np.zeros([T,1])\n",
-    "#us0 = ddp.us\n",
     "xs0 = [problem.initialState+0.1]*len(ddp.models())\n",
     "\n",
-    "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n",
-    "#ddp.solve(maxiter=150)"
+    "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 24,
+   "execution_count": 21,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -601,7 +599,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.12"
   }
  },
  "nbformat": 4,
diff --git a/examples/notebooks/acrobot.ipynb b/examples/notebooks/acrobot.ipynb
index b6eb826049d4f4b95f9c96a05450124d793549ef..d00dc24cbb54c9dd5fccebe6ff91495687c816d8 100644
--- a/examples/notebooks/acrobot.ipynb
+++ b/examples/notebooks/acrobot.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 22,
+   "execution_count": 1,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -36,7 +36,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 23,
+   "execution_count": 2,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -61,18 +61,18 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 24,
+   "execution_count": 3,
    "metadata": {},
    "outputs": [],
    "source": [
     "actModel = ActuationModelDoublePendulum(robot.model, actLink=2)\n",
-    "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n",
-    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))"
+    "runningModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, runningCostModel))\n",
+    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, terminalCostModel))"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 25,
+   "execution_count": 4,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -87,7 +87,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 26,
+   "execution_count": 5,
    "metadata": {
     "scrolled": true
    },
@@ -440,7 +440,7 @@
        " True)"
       ]
      },
-     "execution_count": 26,
+     "execution_count": 5,
      "metadata": {},
      "output_type": "execute_result"
     }
@@ -452,16 +452,14 @@
     "ddp.callback.append(CallbackDDPLogger())\n",
     "\n",
     "us0 = np.zeros([T,1])\n",
-    "#us0 = ddp.us\n",
     "xs0 = [problem.initialState+0.1]*len(ddp.models())\n",
     "\n",
-    "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n",
-    "#ddp.solve(maxiter=150)"
+    "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 27,
+   "execution_count": 6,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -469,8 +467,10 @@
    ]
   },
   {
-   "cell_type": "markdown",
+   "cell_type": "code",
+   "execution_count": 13,
    "metadata": {},
+   "outputs": [],
    "source": [
     "import time \n",
     "dt = 0.01\n",
@@ -483,8 +483,10 @@
    ]
   },
   {
-   "cell_type": "markdown",
+   "cell_type": "code",
+   "execution_count": 14,
    "metadata": {},
+   "outputs": [],
    "source": [
     "nle = np.zeros([2,1])\n",
     "for i in range(len(t)):\n",
@@ -593,7 +595,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.12"
   }
  },
  "nbformat": 4,
diff --git a/examples/notebooks/kinton_flying_base.ipynb b/examples/notebooks/kinton_flying_base.ipynb
index ce686bdafb8a3e44c36a45a8a2ac07b3b93b4187..b8b09caf788fb19160f180991bc3a092f9e95204 100644
--- a/examples/notebooks/kinton_flying_base.ipynb
+++ b/examples/notebooks/kinton_flying_base.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 6,
+   "execution_count": 26,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -14,7 +14,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 7,
+   "execution_count": 27,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -30,24 +30,24 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 8,
+   "execution_count": 28,
    "metadata": {},
    "outputs": [],
    "source": [
     "# DEFINE TARGET POSITION\n",
-    "target_pos  = np.array([0,0,1])\n",
+    "target_pos  = np.array([1,0,1])\n",
     "target_quat = pin.Quaternion(1, 0, 0, 0)\n",
     "target_quat.normalize()\n",
     "\n",
     "# Plot goal frame\n",
-    "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)\n",
+    "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 2)\n",
     "robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])\n",
     "robot.viewer.gui.refresh()"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 9,
+   "execution_count": 29,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -99,51 +99,38 @@
     "                                                                np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))\n",
     "\n",
     "# Then let's add the running and terminal cost functions\n",
-    "runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n",
+    "runningCostModel.addCost(name=\"pos\", weight=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",
+    "terminalCostModel.addCost(name=\"pos\", weight=1e3, cost=goalTrackingCost)\n",
     "\n",
     "# DIFFERENTIAL ACTION MODEL\n",
-    "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n",
-    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))"
+    "runningModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, runningCostModel))\n",
+    "terminalModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, terminalCostModel))"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 10,
+   "execution_count": 30,
    "metadata": {
     "scrolled": true
    },
-   "outputs": [
-    {
-     "ename": "KeyboardInterrupt",
-     "evalue": "",
-     "output_type": "error",
-     "traceback": [
-      "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
-      "\u001b[0;31mKeyboardInterrupt\u001b[0m                         Traceback (most recent call last)",
-      "\u001b[0;32m<ipython-input-10-b175ebf9a54b>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m     23\u001b[0m     \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mquasiStatic\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0md\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mrmodel\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdefaultState\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     24\u001b[0m     \u001b[0;32mif\u001b[0m \u001b[0misinstance\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mm\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mIntegratedActionModelEuler\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32melse\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mzeros\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;36m0\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 25\u001b[0;31m     for m, d in zip(fddp.problem.runningModels, fddp.problem.runningDatas)]\n\u001b[0m\u001b[1;32m     26\u001b[0m \u001b[0mxs0\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mproblem\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0minitialState\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0mlen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mfddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmodels\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     27\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/flying.pyc\u001b[0m in \u001b[0;36mquasiStatic\u001b[0;34m(self, data, x)\u001b[0m\n\u001b[1;32m     71\u001b[0m         \u001b[0;32melse\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     72\u001b[0m             \u001b[0mx\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mnq\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[0m\n\u001b[0;32m---> 73\u001b[0;31m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalcDiff\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\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[0mnu\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     74\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdot\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mlinalg\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinv\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mactuation\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mAu\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m-\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mr\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0mnu\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     75\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/flying.pyc\u001b[0m in \u001b[0;36mcalcDiff\u001b[0;34m(self, data, x, u, recalc)\u001b[0m\n\u001b[1;32m     62\u001b[0m         \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcomputeJointJacobians\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mq\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     63\u001b[0m         \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mupdateFramePlacements\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 64\u001b[0;31m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcosts\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalcDiff\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcosts\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mrecalc\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mFalse\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     65\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mxout\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     66\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/cost.pyc\u001b[0m in \u001b[0;36mcalcDiff\u001b[0;34m(self, data, x, u, recalc)\u001b[0m\n\u001b[1;32m    186\u001b[0m         \u001b[0mnr\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;36m0\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    187\u001b[0m         \u001b[0;32mfor\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0md\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mzip\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcosts\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mvalues\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcosts\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mvalues\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 188\u001b[0;31m             \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalcDiff\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0md\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mrecalc\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mFalse\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    189\u001b[0m             \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mLx\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m+=\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mweight\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0md\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mLx\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    190\u001b[0m             \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mLu\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m+=\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mweight\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0md\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mLu\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/cost.pyc\u001b[0m in \u001b[0;36mcalcDiff\u001b[0;34m(self, data, x, u, recalc)\u001b[0m\n\u001b[1;32m    383\u001b[0m             \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalc\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    384\u001b[0m         \u001b[0mnq\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mnq\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 385\u001b[0;31m         \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mupdateFramePlacements\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    386\u001b[0m         J = np.dot(\n\u001b[1;32m    387\u001b[0m             \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mJlog6\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mrMf\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;31mKeyboardInterrupt\u001b[0m: "
-     ]
-    }
-   ],
+   "outputs": [],
    "source": [
     "# DEFINING THE SHOOTING PROBLEM & SOLVING\n",
     "\n",
     "# Defining the time duration for running action models and the terminal one\n",
-    "dt = 1e-3\n",
+    "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 = 1000\n",
+    "T = 100\n",
     "q0 = rmodel.referenceConfigurations[\"initial_pose\"].copy()\n",
+    "q0[:3] = np.array([[0,0,1]]).T\n",
+    "robot.display(q0)\n",
+    "\n",
     "v0 = pin.utils.zero(rmodel.nv)\n",
     "x0 = m2a(np.concatenate([q0, v0]))\n",
     "rmodel.defaultState = x0.copy()\n",
@@ -153,22 +140,102 @@
     "# Creating the DDP solver for this OC problem, defining a logger\n",
     "fddp = SolverFDDP(problem)\n",
     "fddp.callback = [CallbackDDPVerbose()]\n",
-    "fddp.callback.append(CallbackDDPLogger())\n",
-    "\n",
+    "fddp.callback.append(CallbackDDPLogger())"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 31,
+   "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  6.29590e+02  7.96224e-02  2.15609e+03  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   1  6.30852e+02  4.80967e-02  1.26791e+03  1.00000e-08  1.00000e-08   0.0020     0\n",
+      "   2  6.01761e+02  4.82739e-02  1.23187e+03  1.00000e-08  1.00000e-08   0.0625     0\n",
+      "   3  4.40427e+03  1.06561e-01  4.42949e+05  1.00000e-07  1.00000e-07   0.0020     0\n",
+      "   4  5.56204e+02  9.78431e-02  4.88230e+04  1.00000e-06  1.00000e-06   0.0020     0\n",
+      "   5  5.32187e+02  5.97649e-02  1.43019e+03  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "   6  4.97507e+02  1.60327e-01  1.61203e+03  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "   7  4.74778e+02  8.38901e-02  1.91458e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "   8  3.25696e+02  5.72554e-02  9.34297e+02  1.00000e-06  1.00000e-06   0.2500     0\n",
+      "   9  2.67737e+02  2.86730e-01  5.26083e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "  10  2.37987e+02  4.96799e-02  5.86572e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  11  2.02788e+02  4.53041e-02  4.86577e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  12  1.85384e+02  4.77690e-02  4.46737e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  13  1.66182e+02  6.62648e-02  4.01742e+03  1.00000e-06  1.00000e-06   0.0078     0\n",
+      "  14  1.58441e+02  9.52512e-02  1.05481e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  15  1.13844e+02  1.18378e-01  3.06773e+02  1.00000e-06  1.00000e-06   0.2500     0\n",
+      "  16  1.05150e+02  1.25007e-01  2.20486e+03  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "  17  9.90704e+01  5.23780e-02  2.70045e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  18  8.94492e+01  2.02392e-01  2.07226e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  19  6.47362e+01  1.76034e-01  1.65536e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "  20  6.28304e+01  2.51709e-02  1.40523e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  21  4.98590e+01  4.79961e-02  1.35959e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  22  4.52306e+01  1.66295e-02  1.09988e+02  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  23  4.34704e+01  6.83555e-03  2.38636e+02  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "  24  4.14151e+01  1.23934e-02  2.46175e+02  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "  25  3.88052e+01  7.79518e-03  3.04807e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  26  2.99692e+01  7.69465e-03  6.41478e+01  1.00000e-06  1.00000e-06   0.2500     0\n",
+      "  27  2.50620e+01  5.60275e-03  7.16136e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  28  2.36294e+01  7.39141e-03  4.36020e+01  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  29  2.29907e+01  6.96437e-03  1.30013e+02  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "  30  2.15019e+01  6.50978e-03  1.74040e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  31  1.86834e+01  5.57690e-03  2.94871e+01  1.00000e-06  1.00000e-06   0.2500     0\n",
+      "  32  1.51607e+01  3.23914e-03  4.99516e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  33  1.47822e+01  2.51836e-03  2.25850e+01  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  34  1.40048e+01  2.43399e-03  9.80769e+01  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  35  1.30786e+01  2.37065e-03  1.44113e+01  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  36  1.23943e+01  3.02734e-03  8.72063e+01  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  37  1.18446e+01  2.82385e-03  1.13099e+01  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  38  1.12258e+01  3.53432e-03  8.45098e+01  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  39  1.09829e+01  3.60843e-03  9.22512e+00  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "  40  1.03321e+01  4.10735e-03  9.02560e+01  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  41  1.01096e+01  4.04217e-03  7.82867e+00  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  42  1.00090e+01  3.91499e-03  2.43686e+01  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "  43  9.72547e+00  3.74271e-03  3.48707e+01  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  44  9.56641e+00  3.48811e-03  5.60029e+00  1.00000e-06  1.00000e-06   0.2500     0\n",
+      "  45  8.43643e+00  8.91384e-04  1.63381e+02  1.00000e-06  1.00000e-06   0.0156     0\n"
+     ]
+    },
+    {
+     "ename": "KeyboardInterrupt",
+     "evalue": "",
+     "output_type": "error",
+     "traceback": [
+      "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
+      "\u001b[0;31mKeyboardInterrupt\u001b[0m                         Traceback (most recent call last)",
+      "\u001b[0;32m<ipython-input-31-5296d495a382>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m      5\u001b[0m \u001b[0mxs0\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mproblem\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0minitialState\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0mlen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mfddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmodels\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m      6\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 7\u001b[0;31m \u001b[0mfddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msolve\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
+      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/fddp.pyc\u001b[0m in \u001b[0;36msolve\u001b[0;34m(self, maxiter, init_xs, init_us, isFeasible, regInit)\u001b[0m\n\u001b[1;32m    157\u001b[0m             \u001b[0;32mfor\u001b[0m \u001b[0ma\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0malphas\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    158\u001b[0m                 \u001b[0;32mtry\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 159\u001b[0;31m                     \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdV\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mtryStep\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0ma\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    160\u001b[0m                 \u001b[0;32mexcept\u001b[0m \u001b[0mArithmeticError\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    161\u001b[0m                     \u001b[0;32mcontinue\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/fddp.pyc\u001b[0m in \u001b[0;36mtryStep\u001b[0;34m(self, stepLength)\u001b[0m\n\u001b[1;32m    122\u001b[0m         \u001b[0;34m:\u001b[0m\u001b[0mparam\u001b[0m \u001b[0mstepLength\u001b[0m\u001b[0;34m:\u001b[0m \u001b[0mstep\u001b[0m \u001b[0mlength\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    123\u001b[0m         \"\"\"\n\u001b[0;32m--> 124\u001b[0;31m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mforwardPass\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mstepLength\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    125\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m \u001b[0;34m-\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost_try\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    126\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/jmarti/robotics/toolboxes/crocoddyl/crocoddyl/fddp.pyc\u001b[0m in \u001b[0;36mforwardPass\u001b[0;34m(self, stepLength, warning)\u001b[0m\n\u001b[1;32m    326\u001b[0m             \u001b[0;32mwith\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwarnings\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcatch_warnings\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    327\u001b[0m                 \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwarnings\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msimplefilter\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mwarning\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 328\u001b[0;31m                 \u001b[0mxnext\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcost\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalc\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0md\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mxtry\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mutry\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    329\u001b[0m             \u001b[0mctry\u001b[0m \u001b[0;34m+=\u001b[0m \u001b[0mcost\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    330\u001b[0m             \u001b[0mraiseIfNan\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mctry\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcost\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mArithmeticError\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'forward error'\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/integrated_action.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, x, u)\u001b[0m\n\u001b[1;32m     23\u001b[0m     \u001b[0;32mdef\u001b[0m \u001b[0mcalc\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mNone\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     24\u001b[0m         \u001b[0mnq\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdt\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mnq\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mtimeStep\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 25\u001b[0;31m         \u001b[0macc\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcost\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalc\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     26\u001b[0m         \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwithCostResiduals\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     27\u001b[0m             \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcostResiduals\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcostResiduals\u001b[0m\u001b[0;34m[\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/differential_action.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, x, u)\u001b[0m\n\u001b[1;32m    346\u001b[0m         \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mtauq\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mactuation\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalc\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mactuation\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    347\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 348\u001b[0;31m         \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcomputeAllTerms\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mq\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mv\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    349\u001b[0m         \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    350\u001b[0m         \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mMinv\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mlinalg\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0minv\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mM\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/jmarti/.local/lib/python2.7/site-packages/numpy/linalg/linalg.pyc\u001b[0m in \u001b[0;36minv\u001b[0;34m(a)\u001b[0m\n\u001b[1;32m    549\u001b[0m     \u001b[0msignature\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m'D->D'\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0misComplexType\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32melse\u001b[0m \u001b[0;34m'd->d'\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    550\u001b[0m     \u001b[0mextobj\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mget_linalg_error_extobj\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0m_raise_linalgerror_singular\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 551\u001b[0;31m     \u001b[0mainv\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0m_umath_linalg\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0minv\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0ma\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0msignature\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0msignature\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mextobj\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mextobj\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    552\u001b[0m     \u001b[0;32mreturn\u001b[0m \u001b[0mwrap\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mainv\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mastype\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mresult_t\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcopy\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mFalse\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    553\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;31mKeyboardInterrupt\u001b[0m: "
+     ]
+    }
+   ],
+   "source": [
     "us0 = [\n",
     "    m.differential.quasiStatic(d.differential, rmodel.defaultState)\n",
     "    if isinstance(m, IntegratedActionModelEuler) else np.zeros(0)\n",
     "    for m, d in zip(fddp.problem.runningModels, fddp.problem.runningDatas)]\n",
     "xs0 = [problem.initialState]*len(fddp.models())\n",
     "\n",
-    "# Solving it with the DDP algorithm\n",
-    "#fddp.solve(init_xs=xs0, init_us=us0)\n",
     "fddp.solve()"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": null,
+   "execution_count": 19,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -177,38 +244,39 @@
   },
   {
    "cell_type": "code",
-   "execution_count": null,
+   "execution_count": 23,
    "metadata": {},
-   "outputs": [],
+   "outputs": [
+    {
+     "name": "stdout",
+     "output_type": "stream",
+     "text": [
+      "[[0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]\n",
+      " [0.]]\n"
+     ]
+    }
+   ],
    "source": [
-    "# Control trajectory\n",
-    "f1 = []\n",
-    "f2 = [];\n",
-    "f3 = [];\n",
-    "f4 = [];\n",
-    "\n",
-    "for u in fddp.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",
+    "import time \n",
+    "dt = 0.01\n",
+    "t = np.arange(0,1,dt)\n",
+    "q0 = rmodel.referenceConfigurations[\"initial_pose\"].copy()\n",
+    "q0[:3] = np.array([[0,0,1]]).T\n",
     "\n",
-    "for x in fddp.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])"
+    "q = q0\n",
+    "q_d = np.zeros([rmodel.nv,1])\n",
+    "q_dd = np.zeros([rmodel.nv,1])\n",
+    "print q_d"
    ]
   },
   {
@@ -217,42 +285,23 @@
    "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]')"
+    "nle = np.zeros([2,1])\n",
+    "for i in range(len(t)):\n",
+    "    pin.computeAllTerms(rmodel, robot.data, q, q_d)\n",
+    "    M = robot.data.M\n",
+    "    Minv = np.linalg.inv(M)\n",
+    "    r = np.zeros([,1])\n",
+    "    tau = np.zeros([2,1])\n",
+    "    tau[0,0] = ddp.us[i]\n",
+    "    nle[:,0] = m2a(robot.data.nle)    \n",
+    "    r[:] = tau - nle\n",
+    "    q_dd = np.dot(Minv, r)\n",
+    "    q = q + q_d*dt + q_dd*dt**2\n",
+    "    q_d = q_d + q_dd*dt\n",
+    "    #pin.forwardKinematics(robot.model, robot.data, q, q_d)\n",
+    "    robot.display(q)\n",
+    "    time.sleep(dt)"
    ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": []
   }
  ],
  "metadata": {
diff --git a/examples/notebooks/kinton_flying_mission.ipynb b/examples/notebooks/kinton_flying_mission.ipynb
index 6eb8f24c7ebafee8ec0c08569d55f69b1f78caa3..d9ddf79b0464d95c2601a83732543d4283066103 100644
--- a/examples/notebooks/kinton_flying_mission.ipynb
+++ b/examples/notebooks/kinton_flying_mission.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 1,
+   "execution_count": 26,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -14,7 +14,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 2,
+   "execution_count": 27,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -30,7 +30,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 3,
+   "execution_count": 28,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -81,22 +81,26 @@
     "                                                                    np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))\n",
     "\n",
     "    # Then let's add the running and terminal cost functions\n",
-    "    runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n",
-    "    runningCostModel.addCost(name=\"regx\", weight=1e-4, cost=xRegCost)\n",
+    "    runningCostModel.addCost(name=\"pos\", weight=1, cost=goalTrackingCost)\n",
+    "    runningCostModel.addCost(name=\"regx\", weight=1e-6, 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=10, cost=goalTrackingCost)\n",
+    "    # runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n",
+    "    terminalCostModel.addCost(name=\"pos\", weight=1e3, cost=goalTrackingCost)\n",
     "\n",
     "    # DIFFERENTIAL ACTION MODEL\n",
-    "    dmodel = DifferentialActionModelUAM(rmodel, actModel, runningCostModel)\n",
-    "    model = IntegratedActionModelEuler(dmodel)\n",
-    "    model.timeStep =  integrationStep  \n",
-    "    return model   "
+    "    runningDmodel  = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n",
+    "    terminalDmodel = DifferentialActionModelActuated(rmodel, actModel, terminalCostModel)\n",
+    "    runningModel  = IntegratedActionModelEuler(runningDmodel)\n",
+    "    terminalModel = IntegratedActionModelEuler(terminalDmodel) \n",
+    "    runningModel.timeStep =  integrationStep\n",
+    "    terminalModel.timeStep =  integrationStep\n",
+    "    \n",
+    "    return runningModel, terminalModel   "
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 4,
+   "execution_count": 29,
    "metadata": {
     "scrolled": true
    },
@@ -130,34 +134,47 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 5,
-   "metadata": {},
+   "execution_count": 30,
+   "metadata": {
+    "scrolled": true
+   },
    "outputs": [
     {
      "name": "stdout",
      "output_type": "stream",
      "text": [
+      "49\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\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",
+      "   0  1.53271e+03  2.92603e+01  3.16146e+03  1.00000e-09  1.00000e-09   0.0078     0\n",
+      "   1  1.06352e+35  1.99241e+02  3.16513e+03  1.00000e-08  1.00000e-08   0.0020     0\n",
+      "   2  1.90957e+46  1.92461e+02  5.67382e+15  1.00000e-07  1.00000e-07   0.0020     0\n",
+      "   3  1.66200e+03  1.92118e+02  3.20631e+03  1.00000e-06  1.00000e-06   0.0020     0\n",
+      "   4  1.52483e+03  1.92791e+02  3.16110e+03  1.00000e-06  1.00000e-06   0.0039     0\n",
+      "   5  1.51849e+03  2.25174e+02  3.14188e+03  1.00000e-06  1.00000e-06   0.0078     0\n",
+      "   6  1.49611e+03  3.65879e+02  3.12458e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "   7  1.16189e+03  5.36795e+02  3.06635e+03  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "   8  1.00372e+03  3.90854e+02  2.38571e+03  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "   9  8.89988e+02  2.59809e+02  2.06477e+03  1.00000e-06  1.00000e-06   0.0625     0\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\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"
+      "  10  8.81025e+02  4.04586e+02  1.86234e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  11  7.75472e+02  4.67297e+02  1.80866e+03  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  12  6.40714e+02  4.44887e+02  1.58914e+03  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  13  6.13847e+02  5.08329e+02  1.33260e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  14  5.91209e+02  5.80590e+02  1.26666e+03  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  15  4.91776e+02  8.13277e+02  1.23898e+03  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  16  4.84035e+02  2.14353e+02  1.01910e+03  1.00000e-06  1.00000e-06   0.0078     0\n",
+      "  17  4.32433e+02  2.17571e+02  9.99922e+02  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  18  4.03857e+02  2.06101e+02  8.94278e+02  1.00000e-06  1.00000e-06   0.0312     0\n",
+      "  19  3.78044e+02  1.74267e+02  8.32883e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
+      "  20  3.77158e+02  9.96151e+02  7.95167e+02  1.00000e-06  1.00000e-06   0.0039     0\n",
+      "  21  3.75501e+02  9.94156e+02  7.84670e+02  1.00000e-06  1.00000e-06   0.0039     0\n",
+      "  22  3.71323e+02  9.68994e+02  7.75764e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  23  3.22253e+02  8.03569e+02  7.60195e+02  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  24  2.03545e+02  5.30764e+02  6.59037e+02  1.00000e-06  1.00000e-06   0.1250     0\n",
+      "  25  1.96419e+02  1.39872e+02  4.52954e+02  1.00000e-06  1.00000e-06   0.0156     0\n",
+      "  26  1.82267e+02  1.45859e+02  4.03301e+02  1.00000e-06  1.00000e-06   0.0625     0\n",
+      "  27  2.51878e+10  1.05273e+02  -9.43772e+03  1.00000e-06  1.00000e-06   0.1250     0\n"
      ]
     },
     {
@@ -165,500 +182,467 @@
       "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([ 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)"
+       "  array([-7.23779655e-05, -3.79136022e-05,  6.14093268e-01,  6.17069921e-05,\n",
+       "         -1.16951328e-04,  1.20337610e-05,  9.99999991e-01, -3.67408013e-03,\n",
+       "         -3.67331650e-04,  9.18454401e-04, -6.98548401e-04, -2.33562910e-04,\n",
+       "         -1.76531563e-02,  4.74962429e-06,  8.02420743e-06,  1.22818655e+01,\n",
+       "          2.46827969e-03, -4.67805314e-03,  4.81350443e-04, -7.34816026e-02,\n",
+       "         -7.34663300e-03,  1.83690880e-02, -1.39709680e-02, -4.67125820e-03,\n",
+       "         -3.53063126e-01]),\n",
+       "  array([ 1.49596078e-04,  1.95925337e-04,  7.40222876e-01, -1.28831957e-03,\n",
+       "          7.50453184e-04,  1.26375429e-05,  9.99998888e-01, -2.46045590e-03,\n",
+       "          3.81603710e-03,  7.93244808e-03,  7.66156117e-03,  1.21316669e-02,\n",
+       "         -1.52022946e-02,  2.72330375e-03,  1.39850170e-03,  2.52259951e+00,\n",
+       "         -5.40006622e-02,  3.46968413e-02,  2.83263172e-05,  2.42724846e-02,\n",
+       "          8.36673750e-02,  1.40279874e-01,  1.67202191e-01,  2.47304596e-01,\n",
+       "          4.90172341e-02]),\n",
+       "  array([ 9.43827113e-05, -1.63910604e-06,  7.30901461e-01,  5.58196079e-03,\n",
+       "          1.17499840e-04, -6.12490110e-06,  9.99984414e-01, -7.36419390e-04,\n",
+       "          2.92207752e-02,  1.68274899e-02,  1.84056475e-02,  2.60389460e-02,\n",
+       "         -1.00207907e-02, -8.56245824e-04, -3.81566739e-03, -1.86409824e-01,\n",
+       "          2.74812586e-01, -2.53203781e-02, -5.76879083e-04,  3.44807302e-02,\n",
+       "          5.08094761e-01,  1.77900836e-01,  2.14881728e-01,  2.78145582e-01,\n",
+       "          1.03630077e-01]),\n",
+       "  array([ 4.32893270e-05, -4.98936505e-04,  7.22010848e-01,  8.01656701e-03,\n",
+       "         -1.67188689e-04, -8.45092233e-06,  9.99967853e-01,  4.99976213e-04,\n",
+       "          4.84983878e-02,  2.87003211e-02,  3.09344778e-02,  4.05343493e-02,\n",
+       "         -7.42000149e-03, -9.91750640e-04, -1.20312641e-02, -1.77660432e-01,\n",
+       "          9.73866071e-02, -1.13872201e-02, -1.80360325e-05,  2.47279120e-02,\n",
+       "          3.85552253e-01,  2.37456624e-01,  2.50576606e-01,  2.89908067e-01,\n",
+       "          5.20157850e-02]),\n",
+       "  array([-2.03284300e-05, -1.53377290e-03,  7.21531454e-01,  7.89429121e-03,\n",
+       "         -2.33493746e-04, -7.69766739e-06,  9.99968812e-01,  2.08430383e-03,\n",
+       "          6.51862806e-02,  4.23177821e-02,  4.47377330e-02,  5.58372859e-02,\n",
+       "         -5.71544089e-03, -1.26676212e-03, -2.08633318e-02, -9.25686724e-03,\n",
+       "         -4.89115520e-03, -2.65191040e-03,  5.22088358e-05,  3.16865523e-02,\n",
+       "          3.33757855e-01,  2.72349220e-01,  2.76065103e-01,  3.06058732e-01,\n",
+       "          3.40912119e-02]),\n",
+       "  array([-9.65091836e-05, -2.97155730e-03,  7.21963192e-01,  8.05204724e-03,\n",
+       "         -4.06505655e-04, -6.76413805e-06,  9.99967499e-01,  4.10245456e-03,\n",
+       "          8.42223237e-02,  5.66765362e-02,  5.92587009e-02,  7.17206020e-02,\n",
+       "         -3.48712680e-03, -1.49395631e-03, -2.85928625e-02,  9.09318316e-03,\n",
+       "          6.31052140e-03, -6.91992951e-03,  9.04984596e-05,  4.03630146e-02,\n",
+       "          3.80720862e-01,  2.87175083e-01,  2.90419359e-01,  3.17666321e-01,\n",
+       "          4.45662819e-02]),\n",
+       "  array([-1.92360720e-04, -4.79706888e-03,  7.21886932e-01,  8.43169771e-03,\n",
+       "         -6.14046660e-04, -5.00976046e-06,  9.99964264e-01,  6.51998369e-03,\n",
+       "          1.04870663e-01,  7.14646182e-02,  7.41718651e-02,  8.79057839e-02,\n",
+       "         -7.16755764e-04, -1.88957533e-03, -3.64786896e-02, -9.21233812e-04,\n",
+       "          1.51866524e-02, -8.30075548e-03,  1.30843948e-04,  4.83505827e-02,\n",
+       "          4.12966789e-01,  2.95761640e-01,  2.98263283e-01,  3.23703638e-01,\n",
+       "          5.54074207e-02]),\n",
+       "  array([-3.18219173e-04, -7.03417341e-03,  7.21732209e-01,  8.67875016e-03,\n",
+       "         -8.06841081e-04, -2.60083597e-06,  9.99962013e-01,  9.35510469e-03,\n",
+       "          1.26140057e-01,  8.64417153e-02,  8.92445077e-02,  1.04213021e-01,\n",
+       "          2.32433637e-03, -2.49441458e-03, -4.47548132e-02, -2.32488934e-03,\n",
+       "          9.88260167e-03, -7.71069470e-03,  1.55308390e-04,  5.67024199e-02,\n",
+       "          4.25387873e-01,  2.99541942e-01,  3.01452853e-01,  3.26144746e-01,\n",
+       "          6.08218427e-02]),\n",
+       "  array([-4.83727709e-04, -9.69694345e-03,  7.21627985e-01,  8.73267387e-03,\n",
+       "         -9.82107789e-04,  2.15894174e-07,  9.99961387e-01,  1.26786439e-02,\n",
+       "          1.47803439e-01,  1.01413320e-01,  1.04311959e-01,  1.20532335e-01,\n",
+       "          5.50558217e-03, -3.28906215e-03, -5.32762293e-02, -1.15103222e-03,\n",
+       "          2.15719316e-03, -7.00943882e-03,  1.71768386e-04,  6.64707839e-02,\n",
+       "          4.33267636e-01,  2.99432089e-01,  3.01349031e-01,  3.26386277e-01,\n",
+       "          6.36249159e-02]),\n",
+       "  array([-6.97455872e-04, -1.27876383e-02,  7.21554844e-01,  8.58555224e-03,\n",
+       "         -1.14067415e-03,  3.36021246e-06,  9.99962493e-01,  1.65675835e-02,\n",
+       "          1.69813042e-01,  1.16245317e-01,  1.19264544e-01,  1.36790008e-01,\n",
+       "          8.80453405e-03, -4.25514348e-03, -6.18499120e-02, -3.83050024e-04,\n",
+       "         -5.88490221e-03, -6.34126674e-03,  1.86935773e-04,  7.77787928e-02,\n",
+       "          4.40192073e-01,  2.96639948e-01,  2.99051689e-01,  3.25153463e-01,\n",
+       "          6.59790376e-02]),\n",
+       "  array([-9.67176738e-04, -1.62989368e-02,  7.21516171e-01,  8.20776546e-03,\n",
+       "         -1.27955820e-03,  6.58979752e-06,  9.99965497e-01,  2.11304308e-02,\n",
+       "          1.92151371e-01,  1.30836756e-01,  1.34021388e-01,  1.52930917e-01,\n",
+       "          1.22260390e-02, -5.37662660e-03, -7.02803683e-02,  4.19005366e-04,\n",
+       "         -1.51118079e-02, -5.55385678e-03,  1.94111274e-04,  9.12569464e-02,\n",
+       "          4.46766567e-01,  2.91828770e-01,  2.95136882e-01,  3.22818177e-01,\n",
+       "          6.84300988e-02]),\n",
+       "  array([-1.29973199e-03, -2.02124338e-02,  7.21533697e-01,  7.56317229e-03,\n",
+       "         -1.39291543e-03,  9.59817271e-06,  9.99970429e-01,  2.64863072e-02,\n",
+       "          2.14874049e-01,  1.45105626e-01,  1.48515981e-01,  1.68910522e-01,\n",
+       "          1.57989640e-02, -6.63432144e-03, -7.83422628e-02,  1.60262709e-03,\n",
+       "         -2.57843338e-02, -4.53272278e-03,  1.90537728e-04,  1.07117526e-01,\n",
+       "          4.54453565e-01,  2.85377411e-01,  2.89891862e-01,  3.19592094e-01,\n",
+       "          7.14584998e-02]),\n",
+       "  array([-1.70072829e-03, -2.44966063e-02,  7.21634956e-01,  6.61329357e-03,\n",
+       "         -1.47415924e-03,  1.21046972e-05,  9.99977045e-01,  3.27388167e-02,\n",
+       "          2.38138102e-01,  1.58979630e-01,  1.62687303e-01,  1.84688218e-01,\n",
+       "          1.95848666e-02, -8.00313954e-03, -8.57752312e-02,  3.26264507e-03,\n",
+       "         -3.79959242e-02, -3.24816516e-03,  1.77757968e-04,  1.25050191e-01,\n",
+       "          4.65281072e-01,  2.77480067e-01,  2.83426441e-01,  3.15553937e-01,\n",
+       "          7.57180530e-02]),\n",
+       "  array([-2.17418561e-03, -2.91047299e-02,  7.21842386e-01,  5.32153952e-03,\n",
+       "         -1.51730608e-03,  1.37068709e-05,  9.99984689e-01,  3.99716283e-02,\n",
+       "          2.62253978e-01,  1.72389741e-01,  1.76474095e-01,  2.00222269e-01,\n",
+       "          2.36931854e-02, -9.45155219e-03, -9.22820111e-02,  5.27661260e-03,\n",
+       "         -5.16709391e-02, -1.72433441e-03,  1.51665573e-04,  1.44656232e-01,\n",
+       "          4.82317504e-01,  2.68202237e-01,  2.75735843e-01,  3.10681002e-01,\n",
+       "          8.21663753e-02]),\n",
+       "  array([-2.72222464e-03, -3.39730695e-02,  7.22170978e-01,  3.65889458e-03,\n",
+       "         -1.51624949e-03,  1.40834833e-05,  9.99992157e-01,  4.81779293e-02,\n",
+       "          2.87772146e-01,  1.85273079e-01,  1.89817621e-01,  2.15472177e-01,\n",
+       "          2.83232613e-02, -1.09423217e-02, -9.75299765e-02,  7.47933044e-03,\n",
+       "         -6.65063760e-02,  4.37078789e-05,  1.15744966e-04,  1.64126020e-01,\n",
+       "          5.10363376e-01,  2.57666750e-01,  2.66870521e-01,  3.04998165e-01,\n",
+       "          9.26015190e-02]),\n",
+       "  array([-3.34488775e-03, -3.90196283e-02,  7.22682334e-01,  1.57780103e-03,\n",
+       "         -1.46029450e-03,  1.50546019e-05,  9.99997689e-01,  5.71733845e-02,\n",
+       "          3.15556526e-01,  1.97557364e-01,  2.02654102e-01,  2.30392268e-01,\n",
+       "          3.37514224e-02, -1.24325502e-02, -1.01159398e-01,  1.07927486e-02,\n",
+       "         -8.32438686e-02,  2.23983341e-03,  1.56870383e-04,  1.79909104e-01,\n",
+       "          5.55687597e-01,  2.45685695e-01,  2.56729621e-01,  2.98401828e-01,\n",
+       "          1.08563220e-01]),\n",
+       "  array([-4.03967814e-03, -4.41408310e-02,  7.23506644e-01, -1.04674947e-03,\n",
+       "         -1.33776359e-03,  1.46495674e-05,  9.99998557e-01,  6.75699531e-02,\n",
+       "          3.46843608e-01,  2.09079940e-01,  2.14808142e-01,  2.44825988e-01,\n",
+       "          4.01998164e-02, -1.38692957e-02, -1.02772574e-01,  1.65797434e-02,\n",
+       "         -1.04981903e-01,  4.90283646e-03,  1.29369773e-04,  2.07931373e-01,\n",
+       "          6.25741635e-01,  2.30451537e-01,  2.43080797e-01,  2.88674390e-01,\n",
+       "          1.28967881e-01]),\n",
+       "  array([-4.79973907e-03, -4.92081019e-02,  7.24306598e-01, -4.15383256e-03,\n",
+       "         -1.15512611e-03, -4.08403853e-06,  9.99990706e-01,  8.01971650e-02,\n",
+       "          3.83790871e-01,  2.20017534e-01,  2.26264343e-01,  2.58708437e-01,\n",
+       "          4.88024339e-02, -1.51879193e-02, -1.01850699e-01,  1.55101202e-02,\n",
+       "         -1.24284569e-01,  7.30768534e-03, -5.75430750e-04,  2.52544237e-01,\n",
+       "          7.38945253e-01,  2.18751866e-01,  2.29124023e-01,  2.77648976e-01,\n",
+       "          1.72052350e-01]),\n",
+       "  array([-5.61345395e-03, -5.40899308e-02,  7.23609600e-01, -6.79595899e-03,\n",
+       "         -1.03540795e-03,  2.51360962e-06,  9.99976371e-01,  8.70885015e-02,\n",
+       "          4.31271994e-01,  2.31476487e-01,  2.38397271e-01,  2.73218956e-01,\n",
+       "          6.25309589e-02, -1.63221198e-02, -9.78384155e-02, -1.49722259e-02,\n",
+       "         -1.05686295e-01,  4.78649756e-03,  4.05872743e-04,  1.37826731e-01,\n",
+       "          9.49622469e-01,  2.29179069e-01,  2.42658563e-01,  2.90210391e-01,\n",
+       "          2.74570500e-01]),\n",
+       "  array([-6.47990254e-03, -5.86379142e-02,  7.23103406e-01, -8.66507350e-03,\n",
+       "         -1.30524465e-03,  1.93013862e-05,  9.99961605e-01,  9.08772419e-02,\n",
+       "          4.96970173e-01,  2.41321485e-01,  2.50221454e-01,  2.87664435e-01,\n",
+       "          7.59263731e-02, -1.73194583e-02, -9.10469319e-02, -1.14882130e-02,\n",
+       "         -7.47662037e-02, -1.07982067e-02,  6.75556957e-04,  7.57748079e-02,\n",
+       "          1.31396358e+00,  1.96899958e-01,  2.36483650e-01,  2.88909570e-01,\n",
+       "          2.67908284e-01]),\n",
+       "  array([-7.44916692e-03, -6.23826834e-02,  7.41831647e-01, -1.08973049e-02,\n",
+       "         -8.70143816e-04, -7.13726000e-06,  9.99940244e-01,  9.85784591e-02,\n",
+       "          5.84894504e-01,  2.48340301e-01,  2.59988184e-01,  3.00054039e-01,\n",
+       "          9.09964369e-02, -1.86323380e-02, -8.25124924e-02,  3.73069925e-01,\n",
+       "         -8.92943518e-02,  1.74131520e-02, -7.90137885e-04,  1.54024343e-01,\n",
+       "          1.75848661e+00,  1.40376312e-01,  1.95334603e-01,  2.47792084e-01,\n",
+       "          3.01401276e-01]),\n",
+       "  array([-8.60242134e-03, -6.64700290e-02,  7.98305864e-01,  1.60369141e-02,\n",
+       "         -1.91467333e-03, -3.72298826e-04,  9.99869498e-01,  1.01967720e-01,\n",
+       "          7.58906550e-01,  2.50200168e-01,  2.74917626e-01,  3.14619108e-01,\n",
+       "          1.32286892e-01, -1.97448885e-02, -7.22877287e-02,  1.13011926e+00,\n",
+       "          1.07739162e+00, -4.16193265e-02, -1.60003159e-02,  6.77852178e-02,\n",
+       "          3.48024093e+00,  3.71973507e-02,  2.98588840e-01,  2.91301380e-01,\n",
+       "          8.25809098e-01]),\n",
+       "  array([-1.30938616e-02, -9.86537232e-02,  5.43766269e-01, -1.38742011e-01,\n",
+       "          1.59262532e-02, -5.68736857e-04,  9.90200326e-01,  1.87858736e-01,\n",
+       "          6.25546403e-01,  2.83792613e-01,  2.70597447e-01,  3.32362274e-01,\n",
+       "          1.20336879e-01, -1.99542385e-02, -3.46133441e-02, -5.15189653e+00,\n",
+       "         -6.20966764e+00,  7.13271661e-01, -7.62196270e-03,  1.71782033e+00,\n",
+       "         -2.66720295e+00,  6.71848899e-01, -8.64035829e-02,  3.54863317e-01,\n",
+       "         -2.39000251e-01]),\n",
+       "  array([-6.68153435e-03,  1.18653609e-02,  7.24433267e-01,  5.02250202e-05,\n",
+       "         -2.70264251e-02,  2.49664612e-03,  9.99631600e-01, -3.24026160e-02,\n",
+       "          1.11624718e+00,  2.47328758e-01,  3.85577706e-01,  5.09662780e-01,\n",
+       "          1.30386246e-01,  1.81544219e-01,  1.71215298e+00,  3.89808682e+00,\n",
+       "          5.56834444e+00, -1.72724202e+00, -2.84282901e-02, -4.40522705e+00,\n",
+       "          9.81401563e+00, -7.29277105e-01,  2.29960517e+00,  3.54601012e+00,\n",
+       "          2.00987335e-01]),\n",
+       "  array([ 2.33715640e-02,  1.56117262e-01,  7.85245377e-01, -6.91593298e-02,\n",
+       "          9.67134179e-02, -7.22811716e-03,  9.92880283e-01,  6.33505686e-02,\n",
+       "          8.50264919e-01,  5.08225201e-01,  4.53250477e-01,  6.97647345e-01,\n",
+       "         -2.70134962e-01,  4.82499592e-01,  2.78892400e+00,  1.45779533e+00,\n",
+       "         -2.77487207e+00,  4.96412221e+00, -3.14664394e-01,  1.91506369e+00,\n",
+       "         -5.31964531e+00,  5.21792886e+00,  1.35345543e+00,  3.75969130e+00,\n",
+       "         -8.01042416e+00]),\n",
+       "  array([ 2.49318233e-02,  2.84274889e-01,  7.06063913e-01,  9.06406792e-03,\n",
+       "          9.18018684e-03, -2.94379824e-03,  9.99912447e-01,  4.61390064e-02,\n",
+       "          9.50100284e-01,  3.91362497e-01,  4.08941393e-01,  7.12914490e-01,\n",
+       "         -1.36987794e-01,  1.79232081e-01,  2.66814682e+00, -1.41833702e+00,\n",
+       "          3.14210206e+00, -3.50092498e+00,  2.33184775e-01, -3.44231244e-01,\n",
+       "          1.99670731e+00, -2.33725408e+00, -8.86181689e-01,  3.05342903e-01,\n",
+       "          2.66294335e+00]),\n",
+       "  array([ 2.65350955e-02,  4.16042148e-01,  8.21679842e-01, -9.10360725e-02,\n",
+       "          1.68904585e-02,  2.44330540e-03,  9.95701349e-01,  9.18071187e-02,\n",
+       "          6.46339174e-01,  4.86762449e-01,  3.98497201e-01,  7.09937883e-01,\n",
+       "         -2.82350007e-01, -3.28570666e-02,  2.42723875e+00,  2.52535842e+00,\n",
+       "         -4.01178736e+00,  3.00603890e-01,  1.75713090e-01,  9.13362246e-01,\n",
+       "         -6.07522222e+00,  1.90799904e+00, -2.08883828e-01, -5.95321481e-02,\n",
+       "         -2.90724425e+00]),\n",
+       "  array([ 2.04810440e-02,  5.05592210e-01,  7.04188274e-01, -2.33418299e-03,\n",
+       "          2.28748601e-02, -2.77204953e-03,  9.99731768e-01,  1.62194163e-01,\n",
+       "          7.40281271e-01,  5.37150395e-01,  4.09619051e-01,  7.28651657e-01,\n",
+       "         -1.96581119e-01, -3.26386412e-02,  2.01747322e+00, -2.17787330e+00,\n",
+       "          3.55632041e+00,  2.46272717e-01, -1.26558537e-01,  1.40774089e+00,\n",
+       "          1.87884195e+00,  1.00775893e+00,  2.22436999e-01,  3.74275491e-01,\n",
+       "          1.71537776e+00]),\n",
+       "  array([ 0.02199907,  0.59322613,  0.80071136, -0.05785012, -0.00608   ,\n",
+       "          0.00537088,  0.99829232,  0.10023439,  0.5369081 ,  0.5612649 ,\n",
+       "          0.4482701 ,  0.7647164 , -0.13613273,  0.00512148,  1.62660804,\n",
+       "          2.03428992, -2.22589648, -1.16425669,  0.2721511 , -1.2391955 ,\n",
+       "         -4.06746348,  0.48229003,  0.77302096,  0.72129476,  1.20896784]),\n",
+       "  array([ 0.03038133,  0.66139349,  0.65228701,  0.02823784, -0.00915887,\n",
+       "          0.00586246,  0.99954208,  0.08423737,  0.62572463,  0.67278887,\n",
+       "          0.49391044,  0.82276809, -0.15114221,  0.13902467,  1.46257328,\n",
+       "         -2.93242729,  3.44424981, -0.14244892, -0.00871082, -0.31994036,\n",
+       "          1.77633062,  2.23047938,  0.91280675,  1.16103388, -0.3001897 ]),\n",
+       "  array([ 0.03104884,  0.70837485,  0.77943271, -0.0311782 , -0.02351715,\n",
+       "          0.00565369,  0.99922115,  0.20280087,  0.44220075,  0.55904835,\n",
+       "          0.52624305,  0.85270528, -0.1773796 ,  0.10909218,  0.92388191,\n",
+       "          2.54545158, -2.38011645, -0.56083816,  0.02973188,  2.37127001,\n",
+       "         -3.67047766, -2.2748104 ,  0.64665235,  0.59874383, -0.52474767]),\n",
+       "  array([ 0.04294832,  0.74195723,  0.64102389,  0.03924969, -0.00752711,\n",
+       "          0.0064029 ,  0.99918057,  0.24607385,  0.52664093,  0.71209244,\n",
+       "          0.55284623,  0.8863739 , -0.10137405,  0.15751559,  0.65695636,\n",
+       "         -2.78186116,  2.82164504,  0.62274525, -0.01636894,  0.86545959,\n",
+       "          1.68880365,  3.06088195,  0.53206353,  0.67337243,  1.52011083]),\n",
+       "  array([ 0.0604343 ,  0.74723392,  0.77536892,  0.00742035,  0.04867119,\n",
+       "          0.00982831,  0.99873893,  0.17730904,  0.39904992,  0.90816418,\n",
+       "          0.65698385,  0.9678782 , -0.02899225,  0.23417637,  0.22214813,\n",
+       "          2.6933921 , -1.25688869,  2.26106371,  0.05841058, -1.37529617,\n",
+       "         -2.55182012,  3.92143467,  2.0827523 ,  1.630086  ,  1.44763617]),\n",
+       "  array([ 6.35304552e-02,  7.50382539e-01,  6.76706780e-01,  9.31922280e-04,\n",
+       "         -9.70440478e-02,  7.37567468e-03,  9.95252322e-01,  4.30963615e-01,\n",
+       "          4.36171520e-01,  4.46691389e-01,  5.98173796e-01,  9.30298818e-01,\n",
+       "          2.46372724e-02, -1.31544447e-02,  4.51996896e-02, -1.98047188e+00,\n",
+       "         -3.11792637e-01, -5.83336518e+00, -6.62276920e-02,  5.07309147e+00,\n",
+       "          7.42431966e-01, -9.22945576e+00, -1.17620098e+00, -7.51587681e-01,\n",
+       "          1.07259036e+00]),\n",
+       "  array([ 2.45333075e-02,  7.47839261e-01,  7.95990552e-01,  4.57444022e-02,\n",
+       "          5.37194486e-02,  5.89211388e-03,  9.97490328e-01,  2.78703892e-01,\n",
+       "          4.88974157e-01,  1.04584798e+00,  6.81617363e-01,  9.97706184e-01,\n",
+       "          1.23493370e-01, -6.98428979e-01,  7.87577532e-02,  2.42794583e+00,\n",
+       "          1.83018024e+00,  6.02217701e+00, -2.40284129e-01, -3.04519445e+00,\n",
+       "          1.05605275e+00,  1.19831318e+01,  1.66887133e+00,  1.34814733e+00,\n",
+       "          1.97712196e+00]),\n",
+       "  array([-6.47188841e-02,  7.70055039e-01,  6.33560677e-01,  1.60417960e-02,\n",
+       "          6.89049703e-02,  1.52043372e-03,  9.97493085e-01,  5.48159183e-01,\n",
+       "          6.98209888e-01,  9.03063171e-01,  8.30281048e-01,  1.12168095e+00,\n",
+       "          3.90855437e-01, -1.37187506e+00,  2.44033840e-01, -3.46449494e+00,\n",
+       "         -1.17237596e+00,  6.05005910e-01, -2.66089608e-01,  5.38910582e+00,\n",
+       "          4.18471461e+00, -2.85569611e+00,  2.97327371e+00,  2.47949527e+00,\n",
+       "          5.34724134e+00]),\n",
+       "  array([-1.21769787e-01,  8.00812386e-01,  9.05839287e-01, -5.09393885e-02,\n",
+       "         -5.66350737e-02, -5.74146647e-03,  9.97078073e-01,  4.04115285e-01,\n",
+       "          5.46243740e-01,  7.10210026e-01,  5.68569190e-01,  8.95668558e-01,\n",
+       "         -9.48278543e-02, -1.19753932e+00,  4.11289374e-01,  5.46860074e+00,\n",
+       "         -2.66892004e+00, -5.02546942e+00, -3.95118222e-01, -2.88087795e+00,\n",
+       "         -3.03932296e+00, -3.85706291e+00, -5.23423718e+00, -4.52024780e+00,\n",
+       "         -9.71366583e+00]),\n",
+       "  array([-0.1386908 ,  0.79853223,  0.62135308,  0.0952355 ,  0.13675888,\n",
+       "         -0.01021301,  0.98596293,  0.66535168,  0.6981524 ,  1.158194  ,\n",
+       "          0.94959568,  1.14969628,  0.09686113,  0.09943141, -0.28393278,\n",
+       "         -5.74447958,  5.80987671,  7.80746613, -0.11915413,  5.22472782,\n",
+       "          3.03817315,  8.95967954,  7.62052973,  5.08055438,  3.83377976]),\n",
+       "  array([-0.02206957,  0.69817907,  0.57339773, -0.00872902, -0.01865602,\n",
+       "         -0.007195  ,  0.99976197,  0.67790905,  0.72313127,  0.9120379 ,\n",
+       "          0.76987574,  1.06989721,  0.11712226,  2.49145663, -2.05296647,\n",
+       "         -0.49996659, -4.13002422, -6.27259596,  0.14885394,  0.25114746,\n",
+       "          0.49957754, -4.92312212, -3.59439862, -1.5959813 ,  0.40522262]),\n",
+       "  array([ 9.68990484e-02,  5.91540114e-01,  7.90314478e-01,  4.68755896e-02,\n",
+       "          3.84948486e-02,  4.36069066e-03,  9.98149192e-01,  6.20696144e-01,\n",
+       "          6.11393703e-01,  1.25488469e+00,  9.44884763e-01,  1.15774835e+00,\n",
+       "         -1.45151998e-01,  2.29182206e+00, -1.95331091e+00,  4.46789501e+00,\n",
+       "          2.21766808e+00,  2.29874376e+00,  4.40590887e-01, -1.14425810e+00,\n",
+       "         -2.23475143e+00,  6.85693589e+00,  3.50018035e+00,  1.75702268e+00,\n",
+       "         -5.24548527e+00]),\n",
+       "  array([ 1.97362626e-01,  5.08393765e-01,  7.74759123e-01, -3.34278320e-01,\n",
+       "         -3.91721334e-01,  1.64306118e-02,  8.57054512e-01,  4.12489147e-01,\n",
+       "          6.00889962e-01,  2.30595799e-01,  3.35731970e-01,  7.72926664e-01,\n",
+       "          5.31431177e-01,  1.79413327e+00, -1.57275423e+00, -1.55933659e+00,\n",
+       "         -1.59924039e+01, -1.79303839e+01,  7.71912890e-01, -4.16413994e+00,\n",
+       "         -2.10074820e-01, -2.04857779e+01, -1.21830559e+01, -7.69643363e+00,\n",
+       "          1.35316635e+01]),\n",
+       "  array([ 1.69223915e-01,  5.25595635e-01,  8.89926421e-01,  1.44514675e-01,\n",
+       "          1.58902589e-01,  1.82525899e-02,  9.76489794e-01,  3.59117673e-01,\n",
+       "          1.47484707e+00,  1.39309715e+00,  1.11357490e+00,  1.17802970e+00,\n",
+       "          9.45127804e-01, -2.93285434e-02, -6.96963527e-02,  2.66401260e+00,\n",
+       "          2.02859428e+01,  2.24990063e+01, -1.71651569e-01, -1.06742948e+00,\n",
+       "          1.74791422e+01,  2.32500270e+01,  1.55568585e+01,  8.10206077e+00,\n",
+       "          8.27393254e+00]),\n",
+       "  array([-1.10384135e-02,  6.56370496e-01,  8.60872030e-01,  5.45824335e-02,\n",
+       "          2.45618732e-01,  3.36600331e-02,  9.67243092e-01,  1.47430915e+00,\n",
+       "          3.33818092e+00,  2.12690074e+00,  7.40243584e-01,  1.26717285e+00,\n",
+       "          9.01221233e-01, -2.85221805e+00,  2.46492498e+00, -2.44888974e+00,\n",
+       "         -3.50319096e+00,  3.61018441e+00, -4.65566118e-01,  2.23038296e+01,\n",
+       "          3.72666770e+01,  1.46760718e+01, -7.46662626e+00,  1.78286293e+00,\n",
+       "         -8.78131423e-01]),\n",
+       "  array([ -0.03416916,   0.76218246,   1.00651423,   0.21603177,\n",
+       "           0.50763602,  -0.03832942,   0.83316673,   0.45797655,\n",
+       "           4.02091595,   1.03609473,   1.00538763,   1.56332796,\n",
+       "           1.27069799,  -2.24274985,   2.77857885,   1.12302608,\n",
+       "           7.75212514,  11.30304132,  -1.62259914, -20.32665214,\n",
+       "          13.65470057, -21.81612028,   5.30288097,   5.92310229,\n",
+       "           7.38953516]),\n",
+       "  array([ 8.81486371e-02,  8.57021449e-01,  1.21288803e+00, -1.12476840e-02,\n",
+       "          6.49233883e-01,  1.64672032e-01,  7.42463452e-01,  2.53080481e+00,\n",
+       "          4.63153437e+00, -1.41255520e-01, -2.44119437e-01,  5.95007103e-01,\n",
+       "          1.60702303e+00, -2.67455760e+00,  2.85802575e+00,  3.41932331e+00,\n",
+       "         -1.13601094e+01,  8.13133389e+00,  8.04002920e-01,  4.14565654e+01,\n",
+       "          1.22123683e+01, -2.35470049e+01, -2.49901414e+01, -1.93664172e+01,\n",
+       "          6.72650078e+00]),\n",
+       "  array([-7.17194884e-02,  5.20237926e-01,  1.25437883e+00, -6.72139895e-01,\n",
+       "          5.64608717e-02,  5.80535200e-01,  4.56091014e-01, -8.12901895e+00,\n",
+       "          6.30184634e+00,  1.29233896e+01, -1.29923248e+00,  1.46264807e-01,\n",
+       "          4.85297534e-02, -3.45928761e+00,  8.98712413e-01, -7.88098328e+00,\n",
+       "         -4.20658619e+01, -7.32595614e+00, -3.89744342e+00, -2.13196475e+02,\n",
+       "          3.34062395e+01,  2.61292903e+02, -2.11022610e+01, -8.97484592e+00,\n",
+       "         -3.11698655e+01]),\n",
+       "  array([-4.37081365e-01,  2.46307907e-01,  1.56633672e+00, -9.14522136e-01,\n",
+       "         -1.36126871e-01,  3.80906465e-01, -5.38534022e-03,  1.53913761e+01,\n",
+       "          1.15223598e+02, -2.77542803e+01,  9.18312582e-01,  4.58295254e+00,\n",
+       "          3.00079799e+01, -5.97437634e+00,  1.71861717e+01, -1.76744803e+01,\n",
+       "          3.26177195e+02, -1.33352186e+02, -2.11024126e+01,  4.70407902e+02,\n",
+       "          2.17843503e+03, -8.13553398e+02,  4.43509013e+01,  8.87337547e+01,\n",
+       "          5.99189002e+02]),\n",
+       "  array([-4.35371796e-01,  1.10911703e+01, -1.79580439e-01, -9.37654046e-01,\n",
+       "         -1.45784841e-01,  3.14920824e-01, -1.94047456e-02,  2.22968190e+03,\n",
+       "         -9.46737862e+02, -9.31663314e+02, -1.76932787e+01, -1.24874662e+02,\n",
+       "         -2.94722413e+02, -1.27180158e+02, -2.82650462e+02, -2.05081941e+02,\n",
+       "          5.98049971e+03, -1.58724163e+04, -2.80309772e+00,  4.42858104e+04,\n",
+       "         -2.12392292e+04, -1.80781807e+04, -3.72231826e+02, -2.58915230e+03,\n",
+       "         -6.49460785e+03]),\n",
+       "  array([-3.69749946e+03, -4.21224671e+03,  3.37653300e+03, -2.55544535e-01,\n",
+       "          2.13712875e-01,  6.12718656e-01,  7.16658668e-01,  1.18706856e+06,\n",
+       "          1.05506874e+06,  1.04206260e+06, -9.84266766e+03,  2.70417473e+04,\n",
+       "         -2.86883233e+05, -1.88546674e+05, -9.24092119e+04,  1.96541350e+05,\n",
+       "         -3.10404276e+07,  1.46610806e+07, -2.34128526e+03,  2.36967776e+07,\n",
+       "          2.11203095e+07,  2.08598852e+07, -1.96499488e+05,  5.43332439e+05,\n",
+       "         -5.73177021e+06])],\n",
+       " [array([ 9.51382675e+01,  9.54447914e+01,  9.54790488e+01,  9.51947537e+01,\n",
+       "         -9.04087045e-02, -8.84112238e-02, -2.02035681e-02, -1.20778235e-02,\n",
+       "         -4.34182071e-03, -8.05589246e-02]),\n",
+       "  array([-70.02387102, -71.8002623 , -70.99504382, -70.94952921,\n",
+       "           0.12012801,   0.23984258,   0.30772162,   0.28173833,\n",
+       "           0.22189178,   0.1219746 ]),\n",
+       "  array([-1.76561574e+01, -1.78621603e+01, -1.72759244e+01, -1.82541104e+01,\n",
+       "          1.12744958e-02,  1.10414216e-01,  1.28879560e-01,  1.06813479e-01,\n",
+       "          7.58065148e-02,  3.35766173e-02]),\n",
+       "  array([ 3.09026632e+00,  2.37496114e+00,  2.54852531e+00,  2.93585923e+00,\n",
+       "         -1.87565727e-02,  4.52621346e-02,  6.28590682e-02,  5.43316938e-02,\n",
+       "          3.85745614e-02,  7.13061457e-04]),\n",
+       "  array([ 4.19340244e+00,  3.68910430e+00,  3.80336101e+00,  4.07984146e+00,\n",
+       "         -6.40195666e-04,  4.81811994e-02,  4.22909028e-02,  3.77546744e-02,\n",
+       "          2.79892550e-02,  7.28559217e-03]),\n",
+       "  array([2.91449575e+00, 2.70600933e+00, 2.80948507e+00, 2.81035718e+00,\n",
+       "         6.88757575e-04, 3.96269089e-02, 2.77842184e-02, 2.45593323e-02,\n",
+       "         1.83693452e-02, 1.03028543e-02]),\n",
+       "  array([ 2.65456196e+00,  2.53706658e+00,  2.58551936e+00,  2.60690439e+00,\n",
+       "         -7.67696430e-04,  2.72729387e-02,  1.36390140e-02,  1.22883659e-02,\n",
+       "          9.28130028e-03,  7.53823406e-03]),\n",
+       "  array([ 2.70428460e+00,  2.61693719e+00,  2.62521299e+00,  2.69668238e+00,\n",
+       "         -6.56211675e-04,  2.05273712e-02,  3.33611954e-03,  3.42613114e-03,\n",
+       "          2.78779018e-03,  4.99839541e-03]),\n",
+       "  array([ 2.71150582e+00,  2.64948989e+00,  2.63452665e+00,  2.72541110e+00,\n",
+       "          1.06991521e-03,  1.80037676e-02, -3.34092826e-03, -2.34588135e-03,\n",
+       "         -1.42189771e-03,  3.92059494e-03]),\n",
+       "  array([ 2.70092164,  2.65523011,  2.62409891,  2.72890056,  0.00316335,\n",
+       "          0.01749026, -0.00799196, -0.00634549, -0.00433209,  0.0036786 ]),\n",
+       "  array([ 2.69889425,  2.65967933,  2.61445941,  2.73793847,  0.0061813 ,\n",
+       "          0.01862653, -0.01185529, -0.00962346, -0.00670212,  0.00394113]),\n",
+       "  array([ 2.70359304,  2.66306216,  2.60462961,  2.75243451,  0.00958927,\n",
+       "          0.02166236, -0.01535564, -0.01256128, -0.00881241,  0.00470615]),\n",
+       "  array([ 2.71312441,  2.6631759 ,  2.59202445,  2.77151283,  0.01275492,\n",
+       "          0.02703063, -0.01866334, -0.01532816, -0.0107955 ,  0.00601335]),\n",
+       "  array([ 2.72681016,  2.65740231,  2.57340468,  2.79517435,  0.01561617,\n",
+       "          0.0356512 , -0.02192322, -0.0180609 , -0.01275717,  0.0080341 ]),\n",
+       "  array([ 2.74617067,  2.64269936,  2.54625021,  2.82611765,  0.01647814,\n",
+       "          0.04918333, -0.02475173, -0.0204549 , -0.01448275,  0.0110011 ]),\n",
+       "  array([ 2.78240428,  2.62306785,  2.51264515,  2.87970175,  0.01315496,\n",
+       "          0.0700661 , -0.02713535, -0.02253289, -0.01600121,  0.01495021]),\n",
+       "  array([ 2.84666323,  2.60645762,  2.45673792,  2.96590026,  0.03046495,\n",
+       "          0.10131193, -0.0371604 , -0.03094774, -0.02210579,  0.02215801]),\n",
+       "  array([ 2.87006372,  2.49322228,  2.32522926,  2.9840577 ,  0.05350967,\n",
+       "          0.14704859, -0.04094036, -0.03395718, -0.02428181,  0.03570137]),\n",
+       "  array([ 2.74105192,  2.07584353,  2.14420516,  2.82640147, -0.15302927,\n",
+       "          0.21798463,  0.05284388,  0.04364449,  0.0316475 ,  0.03636098]),\n",
+       "  array([ 3.11784238e+00,  2.24340069e+00,  2.12870941e+00,  3.31818044e+00,\n",
+       "         -8.54610444e-02,  3.39997516e-01, -3.10399144e-03, -2.79623637e-03,\n",
+       "         -1.35463319e-03,  3.95367551e-02]),\n",
+       "  array([ 6.08373131,  5.12630941,  4.46754765,  6.62196579,  0.11950794,\n",
+       "          0.47742159, -0.14244726, -0.11724362, -0.08401462,  0.08168448]),\n",
+       "  array([ 8.00024898,  8.75274428,  8.56249374,  8.22343395, -0.04359842,\n",
+       "          0.64906559, -0.01481111,  0.01040867,  0.01465522,  0.17768602]),\n",
+       "  array([-35.2821004 , -53.40481728, -56.0564881 , -34.2376544 ,\n",
+       "           1.61353041,   1.04025586,  -0.60337177,  -0.50674173,\n",
+       "          -0.33152462,   0.11826687]),\n",
+       "  array([63.46457546, 74.00404397, 91.26618784, 54.71895839, -8.53180324,\n",
+       "          0.54604778,  5.26793635,  4.67794644,  3.6079323 , -0.62450635]),\n",
+       "  array([-27.1435977 ,   5.22710757, -24.19076202,  -2.05782652,\n",
+       "           4.13332421,  -7.53932407,  -2.46854517,  -1.9875779 ,\n",
+       "          -1.31675771,  -2.64179762]),\n",
+       "  array([ -6.90671985, -35.9055569 ,  -1.1384089 , -47.89154557,\n",
+       "           6.5985733 ,   0.92346971,  -3.03486627,  -2.93858154,\n",
+       "          -2.39389461,   3.88533061]),\n",
+       "  array([33.48716997, 37.2068011 , 21.85151941, 50.68398882, -1.88115105,\n",
+       "         -1.03797381,  1.00483246,  0.81618428,  0.49128764, -1.68391803]),\n",
+       "  array([-43.24487739, -28.72246877, -28.80882483, -45.39320135,\n",
+       "           2.02376196,   0.47290045,  -0.75531558,  -0.44740929,\n",
+       "          -0.22447397,   1.16752352]),\n",
+       "  array([47.44298821, 24.78813167, 36.492302  , 39.85430075, -3.83754988,\n",
+       "         -0.36780023,  2.93230743,  2.33236301,  1.62090633, -0.29626034]),\n",
+       "  array([-4.44966390e+01, -2.77057730e+01, -3.28177643e+01, -3.97095746e+01,\n",
+       "          1.29058582e-01,  3.74451723e-01, -1.28331573e-01, -3.95096188e-02,\n",
+       "          2.30169942e-02, -3.60643915e-01]),\n",
+       "  array([51.02355601, 43.63758782, 34.4775619 , 54.41720489,  5.79351319,\n",
+       "          0.31818708, -4.71765285, -3.66363949, -2.55867512,  0.5522248 ]),\n",
+       "  array([-4.14198733e+01, -3.69973750e+01, -2.96756171e+01, -4.52376537e+01,\n",
+       "         -3.53639904e+00,  6.03583001e-02,  3.80899111e+00,  2.87045975e+00,\n",
+       "          1.95701611e+00, -2.43533330e-02]),\n",
+       "  array([48.63865467, 38.62723337, 39.96464533, 51.24482843, -3.89125375,\n",
+       "          0.16865277,  2.50716522,  2.23004862,  1.64012621, -0.46628211]),\n",
+       "  array([-30.70420479, -28.17209415, -33.33826386, -39.41010705,\n",
+       "          13.7852292 ,   0.27563473, -10.37473856,  -8.59912157,\n",
+       "          -6.16918538,   1.13033844]),\n",
+       "  array([ 25.79912978,  36.69414433,  36.35355778,  44.36706492,\n",
+       "         -18.34863943,  -0.99884329,  13.55450802,  10.9094032 ,\n",
+       "           7.69295302,  -2.29256795]),\n",
+       "  array([-34.71590512, -38.25919313, -44.32949341, -43.42852479,\n",
+       "          14.76521495,  -0.25089212,  -9.65183011,  -7.01626167,\n",
+       "          -4.638893  ,   1.69274078]),\n",
+       "  array([68.78433243, 69.08128127, 87.9543492 , 55.05822546, -5.23668897,\n",
+       "         -5.75081351, -1.25204253, -2.82099197, -2.75360048, -1.8116989 ]),\n",
+       "  array([-99.4385295 , -71.11364114, -89.08080045, -78.95751368,\n",
+       "          -2.32221153,   1.51264908,   8.84583986,   9.66312642,\n",
+       "           7.91412602,   1.84610654]),\n",
+       "  array([66.13578285, 17.77527654, 47.08565701, 33.3059726 ,  3.70692322,\n",
+       "         -1.61311281, -7.38892511, -7.99908013, -6.36877604, -0.10170829]),\n",
+       "  array([ 29.22649742,  62.81680152,  56.96115153,  47.83337564,\n",
+       "         -12.54839643,  -3.0214439 ,   9.77199128,   8.82084224,\n",
+       "           6.44673972,  -0.94036539]),\n",
+       "  array([ -2.20770687, -81.94987581, -47.76968533, -53.83106259,\n",
+       "          17.67502553,  -0.53647182, -16.55947807, -15.84421387,\n",
+       "         -11.9863268 ,   2.82099635]),\n",
+       "  array([-41.46281037, 138.31059332,  61.3675991 ,  57.59836954,\n",
+       "         -22.7756343 ,  -4.21646748,  22.77929971,  23.24640231,\n",
+       "          18.16251809,  -4.45760471]),\n",
+       "  array([ 39.20879523, -98.38811346, -22.57967597, -65.74906803,\n",
+       "          28.94920848,  -6.79002307, -23.60341769, -22.60462754,\n",
+       "         -16.9997745 ,   2.67045546]),\n",
+       "  array([ -0.37968177,  44.99598476, 138.83368551, -64.4105193 ,\n",
+       "         -30.61311926, -31.45707746,  14.72314159,  13.61230793,\n",
+       "           9.94716573,   0.71093857]),\n",
+       "  array([143.72037329, -56.41343967,  73.6923721 , -19.53644702,\n",
+       "          34.84195902, -13.53782953, -11.65902186, -15.70930379,\n",
+       "         -13.69984726,   6.64954999]),\n",
+       "  array([  18.04122303, -224.30150689,   44.87054542, -197.66543894,\n",
+       "          -56.7367418 ,  -13.45278651,   46.04162915,   36.81108562,\n",
+       "           26.80569562,   -1.57731813]),\n",
+       "  array([-237.05073142,  227.77493498,  -83.883216  , -303.00727897,\n",
+       "          365.61572264,  -72.39286906, -266.50599807, -192.62330823,\n",
+       "         -131.30849181,   11.20277466]),\n",
+       "  array([ -473.19830439,   489.28812697,  1984.10239617,  -166.26820898,\n",
+       "         -1789.64683411, -1093.96483919,   181.99874164,   129.08781274,\n",
+       "           132.5698816 ,   -23.56955846]),\n",
+       "  array([-24632.75402335,  52176.68286695, -14864.79565776,   2705.73754142,\n",
+       "          39500.25555513,   1264.78674662, -58865.81190584, -60436.49857178,\n",
+       "         -43190.57961228,   2850.58693808])],\n",
+       " False)"
       ]
      },
-     "execution_count": 5,
+     "execution_count": 30,
      "metadata": {},
      "output_type": "execute_result"
     }
@@ -666,9 +650,8 @@
    "source": [
     "models = []\n",
     "for i in range(0,len(target_pos)):\n",
-    "#    if (i==1):\n",
-    "#        T *=2\n",
-    "    models += [uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')]*T\n",
+    "    runningModel, terminalModel = uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')\n",
+    "    models += [runningModel]*(T-1) + [terminalModel]\n",
     "\n",
     "q0 = rmodel.referenceConfigurations[\"initial_pose\"]\n",
     "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n",
@@ -680,13 +663,16 @@
     "ddp.callback = [CallbackDDPVerbose()]\n",
     "ddp.callback.append(CallbackDDPLogger())\n",
     "\n",
-    "# Solving it with the DDP algorithm\n",
-    "ddp.solve()"
+    "us0 = np.zeros([problem.T, 10])\n",
+    "xs0 = [problem.initialState+0.1]*len(ddp.models())\n",
+    "\n",
+    "# ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n",
+    "ddp.solve(maxiter=150)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 6,
+   "execution_count": 31,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -719,22 +705,21 @@
    "metadata": {},
    "outputs": [
     {
-     "data": {
-      "image/png": "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\n",
-      "text/plain": [
-       "<Figure size 1080x720 with 4 Axes>"
-      ]
-     },
-     "metadata": {
-      "needs_background": "light"
-     },
-     "output_type": "display_data"
+     "ename": "AttributeError",
+     "evalue": "PlotUAM instance has no attribute 'plotActuation'",
+     "output_type": "error",
+     "traceback": [
+      "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
+      "\u001b[0;31mAttributeError\u001b[0m                            Traceback (most recent call last)",
+      "\u001b[0;32m<ipython-input-17-7e2e2bd56186>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m      5\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m      6\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----> 7\u001b[0;31m \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[0mplotActuation\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
+      "\u001b[0;31mAttributeError\u001b[0m: PlotUAM instance has no attribute 'plotActuation'"
+     ]
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<Figure size 1080x720 with 2 Axes>"
+       "<matplotlib.figure.Figure at 0x7fd9fb7fa550>"
       ]
      },
      "metadata": {
@@ -807,7 +792,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.12"
   }
  },
  "nbformat": 4,