diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py
index deace92e157adca34b690211b8b2662ec881eae3..13a00b2b658d1c9366fce147b3efa18e247ea1bd 100644
--- a/crocoddyl/actuation.py
+++ b/crocoddyl/actuation.py
@@ -14,7 +14,7 @@ class ActuationModelDoublePendulum:
     def calc(self, data, x, u):
         S = np.zeros([self.nv,self.nu])
         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):
diff --git a/examples/notebooks/borinot_arm.ipynb b/examples/notebooks/borinot_arm.ipynb
index 401568e46397d79232d854a1a24179cdf7544a01..2159b523293176b99817040f581f8e26148fdf27 100644
--- a/examples/notebooks/borinot_arm.ipynb
+++ b/examples/notebooks/borinot_arm.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 1,
+   "execution_count": 10,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -44,44 +44,58 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 2,
+   "execution_count": 11,
    "metadata": {},
    "outputs": [],
    "source": [
     "import time \n",
-    "dt = 0.05\n",
-    "t = np.arange(0,3,dt)\n",
-    "q0 = np.array([3.14, 0])\n",
+    "dt = 0.01\n",
+    "t = np.arange(0,10,dt)\n",
+    "q0 = np.array([[1,0]]).T\n",
     "\n",
     "q = q0\n",
-    "q_d = np.zeros([2])\n",
-    "q_dd = np.zeros([2])"
+    "q_d = np.zeros([2,1])\n",
+    "q_dd = np.zeros([2,1])"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 3,
+   "execution_count": 12,
    "metadata": {},
-   "outputs": [],
+   "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-12-1be34671a8d7>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m     13\u001b[0m     \u001b[0;31m#pin.forwardKinematics(robot.model, robot.data, q, q_d)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     14\u001b[0m     \u001b[0mrobot\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdisplay\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[0;32m---> 15\u001b[0;31m     \u001b[0mtime\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msleep\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mdt\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m",
+      "\u001b[0;31mKeyboardInterrupt\u001b[0m: "
+     ]
+    }
+   ],
    "source": [
+    "nle = np.zeros([2,1])\n",
     "for i in range(len(t)):\n",
-    "    pin.computeAllTerms(robot.model, robot.data, a2m(q), a2m(q_d))\n",
+    "    pin.computeAllTerms(robot.model, robot.data, q, q_d)\n",
     "    M = robot.data.M\n",
     "    Minv = np.linalg.inv(M)\n",
-    "    r = np.zeros(2)\n",
-    "    tau = np.zeros([2])\n",
-    "    r = tau - m2a(robot.data.nle) \n",
+    "    r = np.zeros([2,1])\n",
+    "    tau = np.zeros([2,1])\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, a2m(q), a2m(q_d))\n",
-    "    robot.display(a2m(q))\n",
-    "    time.sleep(0.01)"
+    "    #pin.forwardKinematics(robot.model, robot.data, q, q_d)\n",
+    "    robot.display(q)\n",
+    "    time.sleep(dt)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 16,
+   "execution_count": 31,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -93,40 +107,20 @@
     "                                    frame=state, \n",
     "                                    ref=state.zero, \n",
     "                                    nu=1,\n",
-    "                                    activation=ActivationModelWeightedQuad(np.array([10,1,10,1]+[0.1]*2))) \n",
+    "                                    activation=ActivationModelWeightedQuad(np.array([1,1,1,1]+[0.1]*2))) \n",
     "\n",
     "runningCostModel = CostModelSum(robot.model, nu=1)\n",
     "terminalCostModel = CostModelSum(robot.model, nu=1)\n",
     "\n",
-    "runningCostModel.addCost(name=\"regx\", weight=1e-6, cost=xRegCost)\n",
-    "runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n",
-    "runningCostModel.addCost(name=\"pend\", weight=1, cost=xPendCost)\n",
-    "terminalCostModel.addCost(name=\"ori2\", weight=50, cost=xPendCost)"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": 14,
-   "metadata": {},
-   "outputs": [
-    {
-     "data": {
-      "text/plain": [
-       "array([1, 1, 1, 1, 1, 1])"
-      ]
-     },
-     "execution_count": 14,
-     "metadata": {},
-     "output_type": "execute_result"
-    }
-   ],
-   "source": [
-    "np.array([1,1,1,1,1,1])"
+    "# runningCostModel.addCost(name=\"regx\", weight=1e-6, cost=xRegCost)\n",
+    "runningCostModel.addCost(name=\"regu\", weight=1e-3, cost=uRegCost)\n",
+    "runningCostModel.addCost(name=\"pend\", weight=0.1, cost=xPendCost)\n",
+    "terminalCostModel.addCost(name=\"ori2\", weight=1e5, cost=xPendCost)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 17,
+   "execution_count": 32,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -137,24 +131,22 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 18,
+   "execution_count": 33,
    "metadata": {},
    "outputs": [],
    "source": [
     "# Defining the time duration for running action models and the terminal one\n",
-    "dt = 5e-2\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 = 60\n",
+    "T = 100\n",
     "x0 = np.array([3.14, 0, 0., 0. ])\n",
     "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 21,
+   "execution_count": 34,
    "metadata": {
     "scrolled": false
    },
@@ -164,261 +156,269 @@
      "output_type": "stream",
      "text": [
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "   0  3.69322e+01  4.00077e-01  -2.42118e+05  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "   1  1.06958e+02  1.09817e+04  -1.53840e+05  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "   2  1.63942e+02  1.20163e+04  -6.61968e+04  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "   3  2.15054e+02  2.44469e+04  -2.73148e+04  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "   4  2.81349e+02  7.90349e+04  -1.02097e+04  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "   5  2.99798e+02  2.11671e+05  -1.16727e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "   6  2.97934e+02  2.62602e+05  -2.79618e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "   7  3.86648e+02  2.79628e+05  -9.03739e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "   8  3.56496e+02  3.05065e+05  2.10063e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "   9  3.34571e+02  3.18361e+05  1.98154e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  10  3.17185e+02  2.94918e+05  1.85317e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  11  3.03955e+02  2.69587e+05  1.70976e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  12  2.97158e+02  2.44718e+05  1.68433e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  13  2.95010e+02  2.23988e+05  1.55772e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  14  2.92127e+02  1.77842e+05  1.34269e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  15  2.90237e+02  1.58263e+05  1.20819e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  16  2.89086e+02  1.40933e+05  1.07796e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  17  2.91530e+02  1.25615e+05  9.83780e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  18  2.93471e+02  1.01389e+05  7.82353e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  19  3.20074e+02  8.45151e+04  5.00839e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  20  3.27004e+02  1.15773e+05  6.12089e+01  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  21  3.37051e+02  1.14404e+05  5.21526e+01  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  22  3.47284e+02  1.16724e+05  4.12767e+01  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  23  3.61630e+02  1.15360e+05  2.05498e+01  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  24  3.69814e+02  1.55834e+05  -1.82432e+01  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  25  3.83622e+02  2.11950e+05  -5.73130e+01  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  26  4.04999e+02  3.78516e+05  -1.27011e+02  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  27  3.04226e+03  8.89445e+05  -2.16174e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  28  2.96260e+03  1.94558e+07  4.74121e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  29  2.89227e+03  3.20377e+07  4.56920e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  30  2.84216e+03  5.46099e+07  4.43829e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  31  2.79386e+03  2.15807e+07  4.04823e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  32  2.66402e+03  7.69171e+07  3.10104e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  33  2.57381e+03  3.82400e+07  1.67203e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  34  2.54173e+03  2.12230e+07  3.15291e+03  1.00000e-09  1.00000e-09   0.0078     0\n",
-      "  35  2.50917e+03  2.28277e+07  2.84282e+03  1.00000e-09  1.00000e-09   0.0078     0\n",
-      "  36  2.42059e+03  1.83943e+07  2.80926e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  37  2.35571e+03  4.53314e+06  2.88468e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  38  2.29450e+03  2.94511e+06  3.01538e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  39  2.23646e+03  2.95397e+06  3.04682e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  40  2.18184e+03  3.20187e+06  2.98093e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  41  2.06283e+03  3.58034e+06  2.76530e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  42  1.96765e+03  3.53539e+06  1.37594e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  43  1.86980e+03  4.01495e+06  1.83770e+02  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  44  1.82959e+03  3.00959e+06  1.84260e+03  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  45  1.67903e+03  2.92441e+06  1.63419e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  46  1.56821e+03  2.94444e+06  1.61861e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  47  1.51188e+03  2.16622e+06  1.62038e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  48  1.47221e+03  1.78256e+06  1.60973e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  49  1.42969e+03  1.73753e+06  1.59498e+03  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  50  1.35578e+03  1.65609e+06  1.48932e+03  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  51  1.23650e+03  1.58521e+06  1.22446e+03  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  52  1.18605e+03  1.13222e+06  9.81387e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  53  1.13860e+03  9.95712e+05  9.37734e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  54  1.09941e+03  8.30033e+05  8.24965e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  55  1.06417e+03  7.39428e+05  7.23574e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  56  1.00827e+03  6.76196e+05  6.49559e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  57  9.60038e+02  5.72434e+05  5.40036e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  58  9.32590e+02  6.01817e+05  4.14413e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  59  9.08566e+02  4.06614e+05  3.24408e+02  1.00000e-09  1.00000e-09   0.5000     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  60  8.94121e+02  4.21678e+05  2.86102e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  61  8.64166e+02  3.40199e+05  2.70807e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  62  8.48218e+02  3.51569e+05  2.89312e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  63  8.31981e+02  3.73936e+05  3.18707e+02  1.00000e-09  1.00000e-09   0.0625     0\n",
-      "  64  8.24092e+02  3.88829e+05  4.01007e+02  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  65  8.17135e+02  5.39409e+05  5.46952e+02  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  66  8.09434e+02  7.14737e+05  5.76387e+02  1.00000e-09  1.00000e-09   0.0156     0\n",
-      "  67  7.98049e+02  8.88812e+05  5.64268e+02  1.00000e-09  1.00000e-09   0.0312     0\n",
-      "  68  7.68908e+02  1.03626e+06  5.11594e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  69  7.34227e+02  4.66997e+05  3.96413e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  70  7.09251e+02  2.53414e+05  2.98731e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  71  6.81394e+02  2.02792e+05  2.37017e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  72  6.56273e+02  2.20441e+05  1.66143e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  73  6.41038e+02  1.70077e+05  1.13641e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  74  6.33920e+02  1.06675e+05  9.28492e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  75  6.29017e+02  4.73885e+04  8.20266e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  76  6.23077e+02  2.47788e+05  8.36601e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  77  6.19159e+02  1.06836e+05  7.27925e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  78  6.14156e+02  4.79003e+04  7.55618e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  79  6.11053e+02  3.49728e+04  6.42295e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  80  6.08647e+02  3.40752e+04  7.15732e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  81  6.04176e+02  2.96021e+04  6.26665e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  82  6.02491e+02  2.55608e+04  5.16847e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  83  5.99168e+02  3.05765e+04  5.52358e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  84  5.96067e+02  2.89171e+04  4.75835e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  85  5.93180e+02  2.77018e+04  4.31490e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  86  5.90499e+02  2.68026e+04  3.94451e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  87  5.87904e+02  2.55754e+04  3.61755e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  88  5.86719e+02  2.37913e+04  3.28942e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  89  5.83564e+02  2.77219e+04  3.32681e+01  1.00000e-09  1.00000e-09   0.2500     0\n"
-     ]
-    },
-    {
-     "name": "stdout",
-     "output_type": "stream",
-     "text": [
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  90  5.79916e+02  2.62083e+04  2.93626e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  91  5.76686e+02  2.13074e+04  2.46840e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  92  5.75554e+02  1.69815e+04  2.22984e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  93  5.73421e+02  1.80388e+04  2.96336e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  94  5.71645e+02  1.27997e+04  1.82280e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  95  5.70015e+02  1.20544e+04  2.08043e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  96  5.68817e+02  9.56750e+03  1.52030e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  97  5.67363e+02  1.04158e+04  1.87783e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "  98  5.66095e+02  9.08136e+03  1.50942e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "  99  5.64302e+02  8.77571e+03  1.74565e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 100  5.62333e+02  1.01427e+04  2.34368e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 101  5.60839e+02  5.87835e+03  1.44288e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 102  5.59963e+02  1.07652e+04  2.58961e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 103  5.58818e+02  6.10980e+03  1.55720e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 104  5.57771e+02  3.25974e+03  8.12973e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 105  5.56969e+02  4.08881e+03  1.02860e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 106  5.56174e+02  2.57280e+03  5.99404e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 107  5.55899e+02  3.36096e+03  7.84363e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 108  5.55424e+02  8.66043e+03  1.87587e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 109  5.54496e+02  5.92336e+03  1.23806e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "   0  1.23424e+03  2.76233e+02  -3.48552e+04  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   1  1.01544e+03  1.00134e+05  2.35628e+03  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   2  9.16455e+02  1.83154e+05  1.89208e+03  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "   3  7.57330e+02  1.87571e+05  1.52565e+03  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   4  6.44777e+02  1.44015e+05  1.35155e+03  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   5  5.27047e+02  8.60324e+04  9.96662e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "   6  4.50095e+02  6.75230e+04  7.74202e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "   7  4.00431e+02  1.80157e+05  5.83294e+02  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "   8  3.83728e+02  4.99068e+05  4.44340e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "   9  3.10166e+02  8.60093e+05  3.81490e+02  1.00000e-09  1.00000e-09   0.2500     0\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 110  5.53788e+02  4.65201e+03  7.88604e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 111  5.53271e+02  5.51584e+03  1.13144e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 112  5.51919e+02  8.99521e+03  2.15248e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 113  5.51089e+02  4.69214e+03  1.22457e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 114  5.50523e+02  1.12072e+04  2.69121e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 115  5.49556e+02  6.12199e+03  1.48897e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 116  5.48741e+02  2.77994e+03  6.09736e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 117  5.48164e+02  3.52929e+03  8.29119e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 118  5.47633e+02  1.90495e+03  3.97957e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 119  5.47228e+02  2.50094e+03  5.74839e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "  10  2.98238e+02  5.01465e+05  2.13508e+02  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "  11  2.67004e+02  1.16825e+05  1.54060e+02  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "  12  2.58810e+02  4.98327e+04  7.75288e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "  13  2.50463e+02  3.07653e+04  4.44410e+01  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "  14  2.46747e+02  1.64912e+04  2.51054e+01  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "  15  2.44532e+02  3.94136e+03  1.75514e+01  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "  16  2.43116e+02  8.81016e+02  1.15983e+01  1.00000e-09  1.00000e-09   0.2500     0\n",
+      "  17  2.42845e+02  4.92143e+02  2.14890e+00  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  18  2.42541e+02  2.45726e+00  2.55458e+00  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  19  2.42494e+02  1.15928e+00  1.89974e-01  1.00000e-09  1.00000e-09   0.5000     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 120  5.46850e+02  1.49792e+03  2.83630e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 121  5.46718e+02  2.09436e+03  4.44970e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 122  5.46270e+02  6.08477e+03  1.28130e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 123  5.45740e+02  3.87948e+03  7.25354e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 124  5.45208e+02  3.01168e+03  4.00495e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 125  5.44863e+02  3.96339e+03  6.98522e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 126  5.44035e+02  7.22921e+03  1.64124e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 127  5.43624e+02  3.62263e+03  9.02543e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 128  5.43171e+02  9.29248e+03  2.22470e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 129  5.42506e+02  4.97860e+03  1.16623e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "  20  2.42480e+02  3.14052e-01  1.46928e-01  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  21  2.42457e+02  1.62771e-01  1.84970e-01  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  22  2.42449e+02  4.32427e-02  1.98314e-02  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  23  2.42444e+02  3.37429e-02  3.91730e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  24  2.42443e+02  9.02640e-03  3.33728e-03  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  25  2.42442e+02  6.84183e-03  1.15422e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  26  2.42442e+02  1.12123e-03  6.88194e-04  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  27  2.42442e+02  8.95574e-04  6.93182e-04  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  28  2.42442e+02  2.30554e-04  9.29979e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  29  2.42442e+02  2.11601e-04  1.14409e-04  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",
-      " 130  5.42037e+02  2.14840e+03  4.18279e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 131  5.41651e+02  2.96496e+03  6.61381e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 132  5.41373e+02  1.46496e+03  2.68288e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 133  5.41112e+02  2.04903e+03  4.59226e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 134  5.40949e+02  1.03497e+03  1.81702e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 135  5.40761e+02  1.53258e+03  3.45276e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 136  5.40663e+02  7.75189e+02  1.30613e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 137  5.40516e+02  1.22861e+03  2.75293e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 138  5.40451e+02  6.28609e+02  1.00461e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 139  5.40329e+02  1.05500e+03  2.30815e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
+      "  30  2.42442e+02  4.89311e-05  2.93286e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  31  2.42442e+02  3.42716e-05  2.29562e-05  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  32  2.42442e+02  1.57349e-05  9.48651e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  33  2.42442e+02  6.43347e-06  5.05435e-06  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  34  2.42442e+02  1.46074e-06  5.50036e-06  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  35  2.42442e+02  4.69193e-06  7.76582e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  36  2.42442e+02  7.06717e-07  7.90346e-07  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  37  2.42442e+02  1.20611e-06  2.45075e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  38  2.42442e+02  1.12149e-07  1.63510e-07  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  39  2.42442e+02  1.64253e-07  1.58347e-07  1.00000e-09  1.00000e-09   0.5000     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 140  5.40276e+02  5.65302e+02  8.36913e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 141  5.40165e+02  9.80151e+02  2.03334e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 142  5.40103e+02  5.82776e+02  7.73748e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 143  5.39987e+02  1.01551e+03  1.90695e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 144  5.39888e+02  7.20574e+02  8.35814e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 145  5.39812e+02  1.24345e+03  1.99141e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 146  5.39495e+02  3.55859e+03  6.60769e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 147  5.39274e+02  2.52704e+03  3.76222e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 148  5.38735e+02  5.86814e+03  1.12954e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 149  5.38452e+02  3.32883e+03  6.47367e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 150  5.37977e+02  7.16389e+03  1.69660e+01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 151  5.37451e+02  3.66210e+03  8.80655e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 152  5.37077e+02  1.55251e+03  3.32318e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 153  5.36772e+02  2.26651e+03  5.39779e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 154  5.36578e+02  1.03661e+03  2.09859e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 155  5.36376e+02  1.61962e+03  3.85476e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 156  5.36281e+02  7.41355e+02  1.42010e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 157  5.36137e+02  1.24529e+03  2.97774e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 158  5.36096e+02  5.53504e+02  1.02242e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 159  5.35986e+02  1.00686e+03  2.42855e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 160  5.35935e+02  4.28672e+02  7.78496e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 161  5.35887e+02  2.96620e+02  4.39498e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 162  5.35848e+02  4.05258e+02  8.23160e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 163  5.35833e+02  2.34852e+02  3.89308e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 164  5.35796e+02  4.62685e+02  1.02659e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 165  5.35772e+02  2.28785e+02  4.28415e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 166  5.35757e+02  1.34619e+02  1.89806e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 167  5.35737e+02  2.04990e+02  4.20938e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 168  5.35731e+02  1.10469e+02  1.63303e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 169  5.35711e+02  1.97158e+02  4.30760e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 170  5.35702e+02  9.75119e+01  1.51440e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 171  5.35693e+02  6.90480e+01  8.13791e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 172  5.35684e+02  9.76316e+01  1.68727e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 173  5.35679e+02  6.24982e+01  8.00210e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 174  5.35670e+02  1.06579e+02  2.02417e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 175  5.35667e+02  6.17581e+01  8.68814e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 176  5.35657e+02  1.24280e+02  2.54752e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 177  5.35651e+02  6.57412e+01  1.01696e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 178  5.35646e+02  4.68822e+01  5.02552e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 179  5.35639e+02  6.79594e+01  1.11637e-01  1.00000e-09  1.00000e-09   0.1250     0\n"
+      "  40  2.42442e+02  3.73652e-08  2.06493e-07  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  41  2.42442e+02  4.28284e-08  2.80121e-08  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  42  2.42442e+02  1.00840e-08  6.36661e-08  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  43  2.42442e+02  8.00865e-09  5.50736e-09  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  44  2.42442e+02  3.29178e-09  2.03204e-08  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  45  2.42442e+02  1.54964e-09  1.17986e-09  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  46  2.42442e+02  3.59963e-10  1.22462e-09  1.00000e-09  1.00000e-09   0.5000     1\n"
      ]
     },
     {
-     "name": "stdout",
-     "output_type": "stream",
-     "text": [
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 180  5.35635e+02  4.69500e+01  5.18769e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 181  5.35628e+02  7.27644e+01  1.24725e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 182  5.35624e+02  4.89416e+01  5.54115e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 183  5.35617e+02  8.00134e+01  1.40884e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 184  5.35613e+02  5.29710e+01  6.08276e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 185  5.35604e+02  9.00227e+01  1.60363e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 186  5.35600e+02  5.95614e+01  6.84421e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 187  5.35590e+02  1.03630e+02  1.83770e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 188  5.35585e+02  6.98350e+01  7.90273e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 189  5.35574e+02  1.22536e+02  2.12322e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 190  5.35566e+02  8.60258e+01  9.41792e-02  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 191  5.35552e+02  1.50191e+02  2.48511e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 192  5.35540e+02  1.12718e+02  1.17257e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 193  5.35521e+02  1.93996e+02  2.97831e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 194  5.35501e+02  1.59965e+02  1.55842e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 195  5.35488e+02  2.71126e+02  3.73549e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 196  5.35430e+02  6.75075e+02  1.21961e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 197  5.35388e+02  4.87055e+02  6.12627e-01  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 198  5.35282e+02  1.17158e+03  1.92026e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 199  5.35156e+02  9.72225e+02  1.12517e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 200  5.34945e+02  2.14756e+03  3.24721e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 201  5.34652e+02  1.81303e+03  2.16978e+00  1.00000e-09  1.00000e-09   0.2500     0\n",
-      " 202  5.34309e+02  3.06248e+03  5.28960e+00  1.00000e-09  1.00000e-09   0.1250     0\n",
-      " 203  5.33943e+02  1.97489e+03  3.30196e+00  1.00000e-09  1.00000e-09   0.2500     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-21-87701ea220e3>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m      9\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     10\u001b[0m \u001b[0;31m#ddp.solve(init_xs=xs0,init_us=us0,maxiter=600)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 11\u001b[0;31m \u001b[0mddp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0msolve\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mmaxiter\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0;36m600\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     12\u001b[0m \u001b[0;31m# Solving it with the DDP algorithm\u001b[0m\u001b[0;34m\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     13\u001b[0m \u001b[0;31m#ddp.solve()\u001b[0m\u001b[0;34m\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;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[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[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[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[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[0m\n",
-      "\u001b[0;32m/home/jmarti/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[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[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[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[0m\n",
-      "\u001b[0;32m/home/jmarti/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[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[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[0m\n",
-      "\u001b[0;32m/home/jmarti/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[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[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[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[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[0m\n",
-      "\u001b[0;32m/home/jmarti/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[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[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[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[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[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/flying.pyc\u001b[0m in \u001b[0;36mcalc\u001b[0;34m(self, data, x, u)\u001b[0m\n\u001b[1;32m     29\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     30\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 31\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     32\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     33\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;31mKeyboardInterrupt\u001b[0m: "
-     ]
+     "data": {
+      "text/plain": [
+       "([array([3.14, 0.  , 0.  , 0.  ]),\n",
+       "  array([  2.48619666,   1.26799443, -65.38033368, 126.79944273]),\n",
+       "  array([  2.27233527,   1.66634287, -21.3861392 ,  39.83484469]),\n",
+       "  array([  2.08671921,   2.00420597, -18.56160577,  33.78630934]),\n",
+       "  array([  1.92029401,   2.29883584, -16.64252052,  29.46298714]),\n",
+       "  array([  1.76708298,   2.56217061, -15.32110304,  26.33347696]),\n",
+       "  array([  1.62087626,   2.80764516, -14.62067198,  24.54745521]),\n",
+       "  array([  1.47442262,   3.05190744, -14.64536354,  24.426228  ]),\n",
+       "  array([  1.3206873 ,   3.3127518 , -15.37353206,  26.08443616]),\n",
+       "  array([  1.15679491,   3.60189934, -16.38923966,  28.91475425]),\n",
+       "  array([  0.98681691,   3.91567307, -16.99779944,  31.37737266]),\n",
+       "  array([  0.8222342 ,   4.23005108, -16.45827131,  31.43780118]),\n",
+       "  array([  0.67743907,   4.512543  , -14.47951315,  28.24919166]),\n",
+       "  array([  0.55775724,   4.74885966, -11.96818306,  23.6316665 ]),\n",
+       "  array([ 0.46044418,  4.94217678, -9.73130511, 19.33171132]),\n",
+       "  array([ 0.38132951,  5.09963603, -7.91146721, 15.74592539]),\n",
+       "  array([ 0.31700816,  5.22741721, -6.43213563, 12.77811782]),\n",
+       "  array([ 0.26495191,  5.33021033, -5.20562451, 10.27931183]),\n",
+       "  array([ 0.22328402,  5.41153018, -4.16678937,  8.13198512]),\n",
+       "  array([ 0.19058156,  5.47405017, -3.27024603,  6.25199907]),\n",
+       "  array([ 0.16573847,  5.51984669, -2.48430842,  4.57965232]),\n",
+       "  array([ 0.14787347,  5.55056769, -1.78650051,  3.07210007]),\n",
+       "  array([ 0.13626712,  5.56754917, -1.16063439,  1.6981475 ]),\n",
+       "  array([ 0.13031776,  5.57189713, -0.59493625,  0.43479628]),\n",
+       "  array([ 0.12950948,  5.5645465 , -0.08082791, -0.73506344]),\n",
+       "  array([ 0.13338828,  5.54630427,  0.38787941, -1.82422295]),\n",
+       "  array([ 0.14154351,  5.51788187,  0.81552384, -2.84223995]),\n",
+       "  array([ 0.15359301,  5.47991993,  1.20495001, -3.79619408]),\n",
+       "  array([ 0.16917038,  5.43300783,  1.55773643, -4.69121021]),\n",
+       "  array([ 0.18791362,  5.3776997 ,  1.87432437, -5.53081268]),\n",
+       "  array([ 0.2094543 ,  5.31452817,  2.15406767, -6.31715317]),\n",
+       "  array([ 0.23340645,  5.24401673,  2.39521552, -7.05114372]),\n",
+       "  array([ 0.25935481,  5.16669154,  2.59483529, -7.73251927]),\n",
+       "  array([ 0.28684161,  5.08309302,  2.74868042, -8.35985194]),\n",
+       "  array([ 0.31535168,  4.99378763,  2.85100728, -8.93053877]),\n",
+       "  array([ 0.34429516,  4.89937974,  2.89434774, -9.44078908]),\n",
+       "  array([ 0.37298767,  4.80052328,  2.86925074, -9.88564568]),\n",
+       "  array([  0.40062788,   4.69793239,   2.76402104, -10.25908903]),\n",
+       "  array([  0.42627298,   4.59238943,   2.56450994, -10.55429653]),\n",
+       "  array([  0.44881356,   4.48474782,   2.25405786, -10.76416062]),\n",
+       "  array([  0.4669511 ,   4.37592578,   1.81375431, -10.8822036 ]),\n",
+       "  array([  0.47918373,   4.26688532,   1.22326316, -10.90404692]),\n",
+       "  array([  0.48380905,   4.15858974,   0.46253126, -10.82955752]),\n",
+       "  array([  0.47895596,   4.05193333,  -0.48530869, -10.66564152]),\n",
+       "  array([  0.46265879,   3.94764005,  -1.62971677, -10.42932786]),\n",
+       "  array([  0.43298363,   3.84613699,  -2.96751635, -10.15030539]),\n",
+       "  array([ 0.38820829,  3.74742059, -4.47753381, -9.87164059]),\n",
+       "  array([ 0.32704593,  3.65094748, -6.11623543, -9.64731022]),\n",
+       "  array([ 0.24889778,  3.55559236, -7.81481544, -9.53551214]),\n",
+       "  array([ 0.15413288,  3.45972109, -9.47649012, -9.58712743]),\n",
+       "  array([  0.04442051,   3.36142721, -10.97123702,  -9.82938799]),\n",
+       "  array([ -0.07684779,   3.25893985, -12.12683011, -10.24873572]),\n",
+       "  array([ -0.20409242,   3.15105239, -12.72446325, -10.78874646]),\n",
+       "  array([ -0.32935488,   3.03716811, -12.52624565, -11.38842731]),\n",
+       "  array([ -0.44302394,   2.91668725, -11.36690624, -12.04808621]),\n",
+       "  array([ -0.53585356,   2.78840694,  -9.28296186, -12.82803116]),\n",
+       "  array([ -0.60158443,   2.65110357,  -6.5730864 , -13.73033725]),\n",
+       "  array([ -0.63867581,   2.50490585,  -3.70913805, -14.61977208]),\n",
+       "  array([ -0.649929  ,   2.35162609,  -1.12531903, -15.32797604]),\n",
+       "  array([ -0.6404033 ,   2.19378574,   0.95257018, -15.78403461]),\n",
+       "  array([ -0.61535563,   2.03367953,   2.50476695, -16.01062116]),\n",
+       "  array([ -0.57919984,   1.87305655,   3.61557841, -16.06229811]),\n",
+       "  array([ -0.53529573,   1.71316015,   4.3904115 , -15.98964024]),\n",
+       "  array([ -0.4860958 ,   1.55485681,   4.91999301, -15.83033304]),\n",
+       "  array([ -0.43336784,   1.39875256,   5.27279519, -15.61042508]),\n",
+       "  array([ -0.37838985,   1.24527835,   5.497799  , -15.34742148]),\n",
+       "  array([ -0.32209654,   1.09474944,   5.62933109, -15.05289053]),\n",
+       "  array([ -0.26518355,   0.94740662,   5.69129979, -14.73428241]),\n",
+       "  array([ -0.20818024,   0.80344536,   5.70033087, -14.39612592]),\n",
+       "  array([ -0.15150075,   0.66303732,   5.66794882, -14.04080398]),\n",
+       "  array([ -0.09548014,   0.52634674,   5.60206079, -13.6690585 ]),\n",
+       "  array([ -0.04040051,   0.39354349,   5.50796275, -13.280325  ]),\n",
+       "  array([  0.01348976,   0.26481387,   5.38902696, -12.87296179]),\n",
+       "  array([  0.06596155,   0.14036971,   5.24717921, -12.44441568]),\n",
+       "  array([  0.11679393,   0.02045618,   5.0832384 , -11.99135266]),\n",
+       "  array([  0.1657656 ,  -0.09464155,   4.89716713, -11.5097734 ]),\n",
+       "  array([  0.21264827,  -0.20459284,   4.68826635, -10.9951288 ]),\n",
+       "  array([  0.25720164,  -0.30901731,   4.45533688, -10.44244771]),\n",
+       "  array([ 0.29916987, -0.40748218,  4.19682378, -9.84648637]),\n",
+       "  array([ 0.33827941, -0.49950124,  3.91095412, -9.20190627]),\n",
+       "  array([ 0.37423816, -0.58453607,  3.59587438, -8.50348301]),\n",
+       "  array([ 0.40673605, -0.66199949,  3.24978878, -7.74634234]),\n",
+       "  array([ 0.43544699, -0.73126161,  2.87109477, -6.9262114 ]),\n",
+       "  array([ 0.46003206, -0.79165823,  2.4585061 , -6.03966205]),\n",
+       "  array([ 0.48014354, -0.84250136,  2.01114832, -5.08431284]),\n",
+       "  array([ 0.49542962, -0.88309083,  1.52860777, -4.05894731]),\n",
+       "  array([ 0.50553876, -0.91272588,  1.01091462, -2.96350469]),\n",
+       "  array([ 0.51012322, -0.93071496,  0.45844592, -1.79890859]),\n",
+       "  array([ 0.50884069, -0.93638219, -0.1282528 , -0.5667232 ]),\n",
+       "  array([ 0.5013536 , -0.92906885, -0.74870954,  0.73133428]),\n",
+       "  array([ 0.4873257 , -0.90812938, -1.40278952,  2.09394747]),\n",
+       "  array([ 0.46641654, -0.87292243, -2.0909165 ,  3.52069487]),\n",
+       "  array([ 0.43827479, -0.82279917, -2.81417441,  5.01232632]),\n",
+       "  array([ 0.40253262, -0.75709248, -3.57421775,  6.57066829]),\n",
+       "  array([ 0.35880311, -0.67511189, -4.37295064,  8.19805922]),\n",
+       "  array([ 0.30668317, -0.5761486 , -5.21199381,  9.89632919]),\n",
+       "  array([ 0.24576279, -0.45949368, -6.092038  , 11.66549182]),\n",
+       "  array([ 0.17564019, -0.32446896, -7.01226048, 13.50247231]),\n",
+       "  array([ 0.09593987, -0.17046602, -7.97003148, 15.40029402]),\n",
+       "  array([ 6.34277069e-03,  2.98770771e-03, -8.95971012e+00,  1.73453725e+01]),\n",
+       "  array([ 0.0062454 ,  0.00293778, -0.00973713, -0.00499246])],\n",
+       " [array([6.07107415]),\n",
+       "  array([-1.31650454]),\n",
+       "  array([0.20206686]),\n",
+       "  array([-0.0502019]),\n",
+       "  array([-0.13594596]),\n",
+       "  array([0.04472378]),\n",
+       "  array([0.49202064]),\n",
+       "  array([1.05474675]),\n",
+       "  array([1.3555997]),\n",
+       "  array([0.9563586]),\n",
+       "  array([-0.21013415]),\n",
+       "  array([-1.35371291]),\n",
+       "  array([-1.52400693]),\n",
+       "  array([-1.12038681]),\n",
+       "  array([-0.72144898]),\n",
+       "  array([-0.44896606]),\n",
+       "  array([-0.27655936]),\n",
+       "  array([-0.16865182]),\n",
+       "  array([-0.10069346]),\n",
+       "  array([-0.05736096]),\n",
+       "  array([-0.02924155]),\n",
+       "  array([-0.01054491]),\n",
+       "  array([0.00229442]),\n",
+       "  array([0.01145778]),\n",
+       "  array([0.01825514]),\n",
+       "  array([0.02344595]),\n",
+       "  array([0.02744708]),\n",
+       "  array([0.03047342]),\n",
+       "  array([0.03263823]),\n",
+       "  array([0.03402872]),\n",
+       "  array([0.0347657]),\n",
+       "  array([0.03505156]),\n",
+       "  array([0.03520717]),\n",
+       "  array([0.03569538]),\n",
+       "  array([0.03712557]),\n",
+       "  array([0.04023047]),\n",
+       "  array([0.04580306]),\n",
+       "  array([0.0545782]),\n",
+       "  array([0.06704224]),\n",
+       "  array([0.08315722]),\n",
+       "  array([0.10200048]),\n",
+       "  array([0.12135638]),\n",
+       "  array([0.13736368]),\n",
+       "  array([0.14441786]),\n",
+       "  array([0.13560827]),\n",
+       "  array([0.10394854]),\n",
+       "  array([0.04447101]),\n",
+       "  array([-0.04300388]),\n",
+       "  array([-0.15074387]),\n",
+       "  array([-0.26020939]),\n",
+       "  array([-0.3417824]),\n",
+       "  array([-0.36392366]),\n",
+       "  array([-0.31819504]),\n",
+       "  array([-0.24227991]),\n",
+       "  array([-0.19392605]),\n",
+       "  array([-0.18414966]),\n",
+       "  array([-0.1708393]),\n",
+       "  array([-0.12899889]),\n",
+       "  array([-0.07430104]),\n",
+       "  array([-0.0258893]),\n",
+       "  array([0.01012836]),\n",
+       "  array([0.03438033]),\n",
+       "  array([0.0489035]),\n",
+       "  array([0.05572796]),\n",
+       "  array([0.05671712]),\n",
+       "  array([0.05357122]),\n",
+       "  array([0.04781701]),\n",
+       "  array([0.04079085]),\n",
+       "  array([0.03363014]),\n",
+       "  array([0.02727701]),\n",
+       "  array([0.02249228]),\n",
+       "  array([0.01987579]),\n",
+       "  array([0.01988898]),\n",
+       "  array([0.02287569]),\n",
+       "  array([0.0290783]),\n",
+       "  array([0.03864711]),\n",
+       "  array([0.05164162]),\n",
+       "  array([0.06802364]),\n",
+       "  array([0.08764312]),\n",
+       "  array([0.11021875]),\n",
+       "  array([0.13531686]),\n",
+       "  array([0.16233327]),\n",
+       "  array([0.19048376]),\n",
+       "  array([0.21880892]),\n",
+       "  array([0.24619821]),\n",
+       "  array([0.27143505]),\n",
+       "  array([0.2932604]),\n",
+       "  array([0.31044747]),\n",
+       "  array([0.32187601]),\n",
+       "  array([0.32659479]),\n",
+       "  array([0.323867]),\n",
+       "  array([0.31320708]),\n",
+       "  array([0.29443694]),\n",
+       "  array([0.26780869]),\n",
+       "  array([0.2342473]),\n",
+       "  array([0.19574492]),\n",
+       "  array([0.15587445]),\n",
+       "  array([0.1202847]),\n",
+       "  array([0.09678264]),\n",
+       "  array([-0.83008598])],\n",
+       " True)"
+      ]
+     },
+     "execution_count": 34,
+     "metadata": {},
+     "output_type": "execute_result"
     }
    ],
    "source": [
@@ -427,19 +427,17 @@
     "ddp.callback = [CallbackDDPVerbose()]\n",
     "ddp.callback.append(CallbackDDPLogger())\n",
     "\n",
-    "us0 = np.zeros([60,1])\n",
+    "us0 = np.zeros([T,1])\n",
     "us0 = us0 + 4\n",
-    "xs0 = [problem.initialState]*len(ddp.models())\n",
+    "xs0 = [problem.initialState+0.1]*len(ddp.models())\n",
     "\n",
-    "#ddp.solve(init_xs=xs0,init_us=us0,maxiter=600)\n",
-    "ddp.solve(maxiter=600)\n",
-    "# Solving it with the DDP algorithm\n",
-    "#ddp.solve()"
+    "#ddp.solve(init_xs=xs0,init_us=us0,maxiter=100)\n",
+    "ddp.solve(maxiter=150)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 20,
+   "execution_count": 36,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -448,24 +446,73 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 12,
+   "execution_count": 49,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "import time \n",
+    "dt = 0.01\n",
+    "t = np.arange(0,1,dt)\n",
+    "q0 = np.array([[3.14,0]]).T\n",
+    "\n",
+    "q = q0\n",
+    "q_d = np.zeros([2,1])\n",
+    "q_dd = np.zeros([2,1])"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 50,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "robot.display(q)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 51,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "nle = np.zeros([2,1])\n",
+    "for i in range(len(t)):\n",
+    "    pin.computeAllTerms(robot.model, robot.data, q, q_d)\n",
+    "    M = robot.data.M\n",
+    "    Minv = np.linalg.inv(M)\n",
+    "    r = np.zeros([2,1])\n",
+    "    tau = np.zeros([2,1])\n",
+    "    tau[1,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": 37,
    "metadata": {},
    "outputs": [
     {
      "data": {
       "text/plain": [
-       "<matplotlib.legend.Legend at 0x7fa10020a710>"
+       "<matplotlib.legend.Legend at 0x7f5c45cd9b90>"
       ]
      },
-     "execution_count": 12,
+     "execution_count": 37,
      "metadata": {},
      "output_type": "execute_result"
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7fa1402ab910>"
+       "<matplotlib.figure.Figure at 0x7f5c75ef6dd0>"
       ]
      },
      "metadata": {
@@ -475,9 +522,9 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7fa10029ec90>"
+       "<matplotlib.figure.Figure at 0x7f5c75e957d0>"
       ]
      },
      "metadata": {