diff --git a/crocoddyl/__init__.py b/crocoddyl/__init__.py
index c5c1d4b9675378f9a0bb98bc813dafd35cfd0817..b92d7b7180e827dd9f96638148624a6b095e66e1 100644
--- a/crocoddyl/__init__.py
+++ b/crocoddyl/__init__.py
@@ -30,7 +30,7 @@ from .impact import (ActionDataImpact, ActionModelImpact, CostModelImpactCoM, Co
 from .integrated_action import (IntegratedActionDataEuler, IntegratedActionDataRK4, IntegratedActionModelEuler,
                                 IntegratedActionModelRK4)
 from .kkt import SolverKKT
-from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs, loadKinton, loadKintonArm, loadBorinotArm
+from .robots import getTalosPathFromRos, loadHyQ, loadTalos, loadTalosArm, loadTalosLegs, loadKinton, loadKintonArm, load2dofPlanar, loadHector
 from .shooting import ShootingProblem
 from .solver import SolverAbstract
 from .state import StateAbstract, StateNumDiff, StatePinocchio, StateVector
diff --git a/crocoddyl/robots.py b/crocoddyl/robots.py
index 6be2250e84b6f0255f6e3f869e6d227fb9f7388b..25a51a77ceca6108152fc7bf6769302132709c60 100644
--- a/crocoddyl/robots.py
+++ b/crocoddyl/robots.py
@@ -142,9 +142,15 @@ def loadKintonArm(modelPath='/opt/openrobots/share/example-robot-data'):
     robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
     return robot
 
-def loadBorinotArm(modelPath='/opt/openrobots/share/example-robot-data'):
-    URDF_FILENAME = "borinot_arm.urdf"
-    URDF_SUBPATH = "/borinot_arm/urdf/" + URDF_FILENAME
+def load2dofPlanar(modelPath='/home/pepms/robotics/other-tools/robot-data'):
+    URDF_FILENAME = "2dof_planar.urdf"
+    URDF_SUBPATH = "/2dof_planar/urdf/" + URDF_FILENAME
     robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], None)
     robot.q0.flat = [np.pi]
     return robot
+
+def loadHector(modelPath='/home/pepms/robotics/other-tools/robot-data'):
+    URDF_FILENAME = "quadrotor_base.urdf"
+    URDF_SUBPATH = "/hector-description/urdf/" + URDF_FILENAME
+    robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
+    return robot
diff --git a/examples/notebooks/2DOFs.ipynb b/examples/notebooks/2DOFs.ipynb
index 9431ea8eff5de6f8a24aff2793fa520a6d81874c..6a5effbaf61606f181e7863aa23b8a73d2b115b3 100644
--- a/examples/notebooks/2DOFs.ipynb
+++ b/examples/notebooks/2DOFs.ipynb
@@ -10,7 +10,7 @@
     "import pinocchio as pin\n",
     "import numpy as np\n",
     "\n",
-    "robot = loadBorinotArm()\n",
+    "robot = load2dofPlanar()\n",
     "robot.initViewer(loadModel=True)\n",
     "\n",
     "q0 = [3.14, 0]\n",
@@ -87,7 +87,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 23,
+   "execution_count": 5,
    "metadata": {
     "scrolled": false
    },
@@ -451,7 +451,7 @@
        " True)"
       ]
      },
-     "execution_count": 23,
+     "execution_count": 5,
      "metadata": {},
      "output_type": "execute_result"
     }
@@ -472,7 +472,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 24,
+   "execution_count": 10,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -481,7 +481,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 19,
+   "execution_count": 7,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -527,7 +527,7 @@
     {
      "data": {
       "text/plain": [
-       "<matplotlib.legend.Legend at 0x7f57076b5390>"
+       "<matplotlib.legend.Legend at 0x7fcd29239310>"
       ]
      },
      "execution_count": 9,
@@ -536,7 +536,7 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
        "<Figure size 1080x720 with 2 Axes>"
       ]
@@ -548,7 +548,7 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
        "<Figure size 1080x720 with 2 Axes>"
       ]
@@ -601,7 +601,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.15+"
   }
  },
  "nbformat": 4,
diff --git a/examples/notebooks/acrobot.ipynb b/examples/notebooks/acrobot.ipynb
index b6eb826049d4f4b95f9c96a05450124d793549ef..16a8fc8d1ee32106e05d5e23f5f154acdcf3e5f7 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": [
@@ -10,7 +10,7 @@
     "import pinocchio as pin\n",
     "import numpy as np\n",
     "\n",
-    "robot = loadBorinotArm()\n",
+    "robot = load2dofPlanar()\n",
     "robot.initViewer(loadModel=True)\n",
     "\n",
     "q0 = [3.14, 0]\n",
@@ -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": 6,
    "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": 7,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -87,7 +87,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 26,
+   "execution_count": 8,
    "metadata": {
     "scrolled": true
    },
@@ -440,7 +440,7 @@
        " True)"
       ]
      },
-     "execution_count": 26,
+     "execution_count": 8,
      "metadata": {},
      "output_type": "execute_result"
     }
@@ -461,7 +461,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 27,
+   "execution_count": 9,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -593,7 +593,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.15+"
   }
  },
  "nbformat": 4,
diff --git a/examples/notebooks/kinton_flying_mission.ipynb b/examples/notebooks/kinton_flying_mission.ipynb
index 6eb8f24c7ebafee8ec0c08569d55f69b1f78caa3..28c9b638526a3848ba98ee33bb09d3b5b6ef817c 100644
--- a/examples/notebooks/kinton_flying_mission.ipynb
+++ b/examples/notebooks/kinton_flying_mission.ipynb
@@ -19,7 +19,7 @@
    "outputs": [],
    "source": [
     "# LOAD ROBOT\n",
-    "robot = loadKinton()\n",
+    "robot = loadHector()\n",
     "robot.initViewer(loadModel=True)\n",
     "robot.display(robot.q0)\n",
     "\n",
@@ -30,7 +30,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 3,
+   "execution_count": 12,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -88,7 +88,7 @@
     "    terminalCostModel.addCost(name=\"pos\", weight=10, cost=goalTrackingCost)\n",
     "\n",
     "    # DIFFERENTIAL ACTION MODEL\n",
-    "    dmodel = DifferentialActionModelUAM(rmodel, actModel, runningCostModel)\n",
+    "    dmodel = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n",
     "    model = IntegratedActionModelEuler(dmodel)\n",
     "    model.timeStep =  integrationStep  \n",
     "    return model   "
@@ -96,7 +96,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 4,
+   "execution_count": 13,
    "metadata": {
     "scrolled": true
    },
@@ -130,537 +130,29 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 5,
+   "execution_count": 16,
    "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  5.67251e-01  4.20441e-02  8.76805e+00  1.00000e-09  1.00000e-09   1.0000     1\n",
-      "   1  5.55684e-01  3.58469e-04  2.99271e-01  1.00000e-09  1.00000e-09   0.0625     1\n",
-      "   2  5.31309e-01  3.20341e-04  2.39454e-01  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "   3  4.97230e-01  2.51906e-04  1.73594e-01  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "   4  4.68044e-01  1.74315e-04  1.00853e-01  1.00000e-09  1.00000e-09   1.0000     1\n",
-      "   5  4.65799e-01  6.36329e-05  5.31715e-02  1.00000e-09  1.00000e-09   0.5000     1\n",
-      "   6  4.51048e-01  5.56021e-05  4.73253e-02  1.00000e-09  1.00000e-09   0.5000     1\n",
-      "   7  4.44854e-01  2.33241e-05  1.81715e-02  1.00000e-09  1.00000e-09   0.5000     1\n",
-      "   8  4.44295e-01  1.05396e-05  6.67558e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "   9  4.42921e-01  7.87399e-06  4.86690e-03  1.00000e-09  1.00000e-09   1.0000     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  10  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"
+     "ename": "ValueError",
+     "evalue": "operands could not be broadcast together with shapes (10,) (4,) ",
+     "output_type": "error",
+     "traceback": [
+      "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
+      "\u001b[0;31mValueError\u001b[0m                                Traceback (most recent call last)",
+      "\u001b[0;32m<ipython-input-16-57dd4f295efb>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m     16\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     17\u001b[0m \u001b[0;31m# Solving it with the DDP algorithm\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 18\u001b[0;31m \u001b[0mddp\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[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
+      "\u001b[0;32m/home/pepms/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    143\u001b[0m                 \u001b[0;32mtry\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    144\u001b[0m                     \u001b[0;31m# t = time.time()\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 145\u001b[0;31m                     \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcomputeDirection\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mrecalc\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mrecalc\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    146\u001b[0m                     \u001b[0;31m# print \"TIME, Solving: Compute direction. Iteration \" + str(i) + \": \" + str(time.time()-t)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    147\u001b[0m                 \u001b[0;32mexcept\u001b[0m \u001b[0mArithmeticError\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/fddp.pyc\u001b[0m in \u001b[0;36mcomputeDirection\u001b[0;34m(self, recalc)\u001b[0m\n\u001b[1;32m     71\u001b[0m         \"\"\"\n\u001b[1;32m     72\u001b[0m         \u001b[0;32mif\u001b[0m \u001b[0mrecalc\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\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[0mcalc\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[0m\u001b[1;32m     74\u001b[0m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mbackwardPass\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     75\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mnan\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[0mproblem\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mT\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0;36m1\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mk\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mVx\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/fddp.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m     52\u001b[0m         \"\"\" Compute the tangent (LQR) model.\n\u001b[1;32m     53\u001b[0m         \"\"\"\n\u001b[0;32m---> 54\u001b[0;31m         \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[0mproblem\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalcDiff\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mxs\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mus\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     55\u001b[0m         \u001b[0;32mif\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0misFeasible\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     56\u001b[0m             \u001b[0;31m# Gap store the state defect from the guess to feasible (rollout) trajectory, i.e.\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/shooting.pyc\u001b[0m in \u001b[0;36mcalcDiff\u001b[0;34m(self, xs, us)\u001b[0m\n\u001b[1;32m     31\u001b[0m         \u001b[0;32massert\u001b[0m \u001b[0;34m(\u001b[0m\u001b[0mlen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mus\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;34m==\u001b[0m \u001b[0mself\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[1;32m     32\u001b[0m         \u001b[0;32mfor\u001b[0m \u001b[0mm\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;32min\u001b[0m \u001b[0mzip\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mrunningModels\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mrunningDatas\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mxs\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m-\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mus\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---> 33\u001b[0;31m             \u001b[0mm\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[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     34\u001b[0m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mterminalModel\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcalcDiff\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mterminalData\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mxs\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m-\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     35\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0msum\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0md\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0md\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mrunningDatas\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mterminalData\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/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/integrated_action.pyc\u001b[0m in \u001b[0;36mcalcDiff\u001b[0;34m(self, data, x, u, recalc)\u001b[0m\n\u001b[1;32m     38\u001b[0m         \u001b[0mnv\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[0mnv\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[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     39\u001b[0m         \u001b[0;32mif\u001b[0m \u001b[0mrecalc\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 40\u001b[0;31m             \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[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     41\u001b[0m         \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdifferential\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[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[0mrecalc\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     42\u001b[0m         \u001b[0mdxnext_dx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdxnext_ddx\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mState\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mJintegrate\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdx\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/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[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[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[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[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[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/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    353\u001b[0m         \u001b[0mpinocchio\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mforwardKinematics\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[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    354\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[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 355\u001b[0;31m         \u001b[0mdata\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[0mcosts\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[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[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m    356\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[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    357\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/cost.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, x, u)\u001b[0m\n\u001b[1;32m    173\u001b[0m         \u001b[0mnr\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[1;32m    174\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[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 175\u001b[0;31m             \u001b[0mdata\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[0mweight\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\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[0mx\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mu\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    176\u001b[0m             \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwithResiduals\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    177\u001b[0m                 \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mresiduals\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mnr\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0mnr\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0mm\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mncost\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msqrt\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[0;34m*\u001b[0m \u001b[0md\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mresiduals\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/cost.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, x, u)\u001b[0m\n\u001b[1;32m    552\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[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    553\u001b[0m         \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mresiduals\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m]\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mu\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mref\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0mNone\u001b[0m \u001b[0;32melse\u001b[0m \u001b[0mu\u001b[0m \u001b[0;34m-\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mref\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 554\u001b[0;31m         \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0msum\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mactivation\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[0mactivation\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mresiduals\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[0m\u001b[1;32m    555\u001b[0m         \u001b[0;32mreturn\u001b[0m \u001b[0mdata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mcost\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    556\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
+      "\u001b[0;32m/home/pepms/robotics/toolboxes/crocoddyl/crocoddyl/activation.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, r)\u001b[0m\n\u001b[1;32m    122\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m    123\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[0mr\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--> 124\u001b[0;31m         \u001b[0;32mreturn\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mweights\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0mr\u001b[0m\u001b[0;34m**\u001b[0m\u001b[0;36m2\u001b[0m \u001b[0;34m/\u001b[0m \u001b[0;36m2\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;34m\u001b[0m\u001b[0m\n\u001b[1;32m    126\u001b[0m     \u001b[0;32mdef\u001b[0m \u001b[0mcalcDiff\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[0mr\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mrecalc\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0mTrue\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;31mValueError\u001b[0m: operands could not be broadcast together with shapes (10,) (4,) "
      ]
-    },
-    {
-     "data": {
-      "text/plain": [
-       "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.,\n",
-       "         0., 0., 0., 0., 0., 0., 0., 0.]),\n",
-       "  array([ 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)"
-      ]
-     },
-     "execution_count": 5,
-     "metadata": {},
-     "output_type": "execute_result"
     }
    ],
    "source": [
@@ -670,7 +162,7 @@
     "#        T *=2\n",
     "    models += [uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')]*T\n",
     "\n",
-    "q0 = rmodel.referenceConfigurations[\"initial_pose\"]\n",
+    "q0 = robot.q0\n",
     "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n",
     "\n",
     "problem = ShootingProblem(x0, models[:-1], models[-1])\n",
@@ -686,7 +178,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 6,
+   "execution_count": null,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -695,54 +187,38 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 14,
+   "execution_count": 17,
    "metadata": {},
    "outputs": [
     {
      "data": {
       "text/plain": [
-       "50"
+       "6"
       ]
      },
-     "execution_count": 14,
+     "execution_count": 17,
      "metadata": {},
      "output_type": "execute_result"
     }
    ],
+   "source": [
+    "robot.nv"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
    "source": [
     "np.size(ddp.xs,0)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 17,
+   "execution_count": null,
    "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"
-    },
-    {
-     "data": {
-      "image/png": "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\n",
-      "text/plain": [
-       "<Figure size 1080x720 with 2 Axes>"
-      ]
-     },
-     "metadata": {
-      "needs_background": "light"
-     },
-     "output_type": "display_data"
-    }
-   ],
+   "outputs": [],
    "source": [
     "distanceRotorCOG = 0.1525\n",
     "cf = 6.6e-5\n",
@@ -755,33 +231,9 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 32,
+   "execution_count": null,
    "metadata": {},
-   "outputs": [
-    {
-     "ename": "AttributeError",
-     "evalue": "'list' object has no attribute 'set_title'",
-     "output_type": "error",
-     "traceback": [
-      "\u001b[0;31m-----------------------------------------------------------------------\u001b[0m",
-      "\u001b[0;31mAttributeError\u001b[0m                        Traceback (most recent call last)",
-      "\u001b[0;32m<ipython-input-32-6afaa0e0f774>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m      3\u001b[0m \u001b[0mfig\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfigure\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m      4\u001b[0m \u001b[0maxs\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mplt\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mplot\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mcontrol\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 5\u001b[0;31m \u001b[0maxs\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mset_title\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'Moments'\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
-      "\u001b[0;31mAttributeError\u001b[0m: 'list' object has no attribute 'set_title'"
-     ]
-    },
-    {
-     "data": {
-      "image/png": "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\n",
-      "text/plain": [
-       "<Figure size 432x288 with 1 Axes>"
-      ]
-     },
-     "metadata": {
-      "needs_background": "light"
-     },
-     "output_type": "display_data"
-    }
-   ],
+   "outputs": [],
    "source": [
     "t = np.arange(0, 2*T*dt-dt, dt)\n",
     "control = np.vstack(ddp.us)\n",
@@ -807,7 +259,7 @@
    "name": "python",
    "nbconvert_exporter": "python",
    "pygments_lexer": "ipython2",
-   "version": "2.7.16"
+   "version": "2.7.15+"
   }
  },
  "nbformat": 4,