diff --git a/crocoddyl/__init__.py b/crocoddyl/__init__.py index 5661caec976610a3c604af69081cc44639e7111f..c5c1d4b9675378f9a0bb98bc813dafd35cfd0817 100644 --- a/crocoddyl/__init__.py +++ b/crocoddyl/__init__.py @@ -19,12 +19,12 @@ from .cost import (CostDataCoM, CostDataControl, CostDataForce, CostDataFramePla from .ddp import SolverDDP from .diagnostic import displayTrajectory, plotDDPConvergence, plotOCSolution from .differential_action import (DifferentialActionDataAbstract, DifferentialActionDataFullyActuated, - DifferentialActionDataLQR, DifferentialActionDataNumDiff, + DifferentialActionDataLQR, DifferentialActionDataNumDiff, DifferentialActionDataActuated, DifferentialActionModelAbstract, DifferentialActionModelFullyActuated, - DifferentialActionModelLQR, DifferentialActionModelNumDiff) + DifferentialActionModelLQR, DifferentialActionModelNumDiff, DifferentialActionModelActuated) from .fddp import SolverFDDP from .floating_contact import DifferentialActionDataFloatingInContact, DifferentialActionModelFloatingInContact -from .flying import DifferentialActionModelUAM, DifferentialActionDataUAM +# from .flying import DifferentialActionModelUAM, DifferentialActionDataUAM from .impact import (ActionDataImpact, ActionModelImpact, CostModelImpactCoM, CostModelImpactWholeBody, ImpulseData6D, ImpulseDataPinocchio, ImpulseModel3D, ImpulseModel6D, ImpulseModelMultiple, ImpulseModelPinocchio) from .integrated_action import (IntegratedActionDataEuler, IntegratedActionDataRK4, IntegratedActionModelEuler, diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py index 13a00b2b658d1c9366fce147b3efa18e247ea1bd..d2bba9a95d4ddafa44d7c74b9e1e528b5c2d0299 100644 --- a/crocoddyl/actuation.py +++ b/crocoddyl/actuation.py @@ -3,17 +3,21 @@ import warnings import numpy as np class ActuationModelDoublePendulum: - def __init__(self, pinocchioModel): + def __init__(self, pinocchioModel,actLink): self.pinocchio = pinocchioModel self.nq = pinocchioModel.nq self.nv = pinocchioModel.nv self.nx = self.nq + self.nv self.ndx = self.nv * 2 self.nu = 1 + self.actLink = actLink def calc(self, data, x, u): S = np.zeros([self.nv,self.nu]) - S[1] = 1 + if self.actLink == 1: + S[0] = 1 + else: + S[1] = 1 data.a[:] = np.dot(S,u) return data.a @@ -33,7 +37,11 @@ class ActuationDataDoublePendulum: self.A = np.zeros([nv, ndx + nu]) # result of calcDiff self.Ax = self.A[:, :ndx] self.Au = self.A[:, ndx:] - self.Au[1,0] = 1 + if model.actLink == 1: + self.Au[0,0] = 1 + else: + self.Au[1,0] = 1 + class ActuationModelUAM: ''' diff --git a/crocoddyl/differential_action.py b/crocoddyl/differential_action.py index fa83b485ef158c98694f588b9f83bde47aa02bad..acf64d09b37a90599fd13f0acd3cc98f5f5aa88e 100644 --- a/crocoddyl/differential_action.py +++ b/crocoddyl/differential_action.py @@ -2,8 +2,7 @@ import numpy as np import pinocchio from .state import StatePinocchio, StateVector -from .utils import EPS, a2m, randomOrthonormalMatrix - +from .utils import EPS, a2m, m2a, randomOrthonormalMatrix class DifferentialActionModelAbstract: """ Abstract class for the differential action model. @@ -321,3 +320,82 @@ class DifferentialActionDataNumDiff: self.Lxx = self.L[:ndx, :ndx] self.Lxu = self.L[:ndx, ndx:] self.Luu = self.L[ndx:, ndx:] + +class DifferentialActionModelActuated(DifferentialActionModelAbstract): + def __init__(self, pinocchioModel, actuationModel, costModel): + DifferentialActionModelAbstract.__init__(self, pinocchioModel.nq, pinocchioModel.nv, actuationModel.nu) + self.DifferentialActionDataType = DifferentialActionDataActuated + self.pinocchio = pinocchioModel + self.State = StatePinocchio(self.pinocchio) + self.actuation = actuationModel + self.costs = costModel + + @property + def ncost(self): + return self.costs.ncost + + def calc(self, data, x, u=None): + if u is None: + u = self.unone + nq, nv = self.nq, self.nv + q = a2m(x[:nq]) + v = a2m(x[-nv:]) + + data.tauq[:] = self.actuation.calc(data.actuation, x, u) + + pinocchio.computeAllTerms(self.pinocchio, data.pinocchio, q, v) + data.M = data.pinocchio.M + data.Minv = np.linalg.inv(data.M) + data.r = data.tauq - m2a(data.pinocchio.nle) + data.xout[:] = np.dot(data.Minv, data.r) + + # --- Cost + pinocchio.forwardKinematics(self.pinocchio, data.pinocchio, q, v) + pinocchio.updateFramePlacements(self.pinocchio, data.pinocchio) + data.cost = self.costs.calc(data.costs, x, u) + return data.xout, data.cost + + def calcDiff(self, data, x, u=None, recalc=True): + if u is None: + u = self.unone + if recalc: + xout, cost = self.calc(data, x, u) + nq, nv = self.nq, self.nv + q = a2m(x[:nq]) + v = a2m(x[-nv:]) + a = a2m(data.xout) + + dtau_dx = data.actuation.Ax + dtau_du = data.actuation.Au + + pinocchio.computeRNEADerivatives(self.pinocchio, data.pinocchio, q, v, a) + data.Fx[:, :nv] = -np.dot(data.Minv, data.pinocchio.dtau_dq) + data.Fx[:, nv:] = -np.dot(data.Minv, data.pinocchio.dtau_dv) + data.Fx += np.dot(data.Minv, dtau_dx) + data.Fu[:, :] = np.dot(data.Minv, dtau_du) + # Cost + pinocchio.computeJointJacobians(self.pinocchio, data.pinocchio, q) + pinocchio.updateFramePlacements(self.pinocchio, data.pinocchio) + self.costs.calcDiff(data.costs, x, u, recalc=False) + return data.xout, data.cost + + def quasiStatic(self, data, x): + nu, nq, nv = self.nu, self.nq, self.nv + if len(x) == nq: + x = np.concatenate([x, np.zeros(nv)]) + else: + x[nq:] = 0 + self.calcDiff(data, x, np.zeros(nu)) + return np.dot(np.linalg.pinv(data.actuation.Au), -data.r)[:nu] + +class DifferentialActionDataActuated(DifferentialActionDataAbstract): + def __init__(self, model): + self.pinocchio = model.pinocchio.createData() + self.actuation = model.actuation.createData(self.pinocchio) + costData = model.costs.createData(self.pinocchio) + DifferentialActionDataAbstract.__init__(self, model, costData) + + nv = model.nv + self.tauq = np.zeros(nv) + self.xout = np.zeros(nv) + self.r = np.zeros(nv) diff --git a/examples/notebooks/2DOFs.ipynb b/examples/notebooks/2DOFs.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..9431ea8eff5de6f8a24aff2793fa520a6d81874c --- /dev/null +++ b/examples/notebooks/2DOFs.ipynb @@ -0,0 +1,609 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl import *\n", + "import pinocchio as pin\n", + "import numpy as np\n", + "\n", + "robot = loadBorinotArm()\n", + "robot.initViewer(loadModel=True)\n", + "\n", + "q0 = [3.14, 0]\n", + "robot.q0.flat = q0\n", + "robot.framesForwardKinematics(robot.q0)\n", + "robot.display(robot.q0)\n", + "\n", + "IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)\n", + "IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)\n", + "Mlink1 = robot.data.oMf[IDX_LINK1]\n", + "Mlink2 = robot.data.oMf[IDX_LINK2]\n", + "\n", + "target_pos = np.array([0,0,0.3])\n", + "target_quat = pin.Quaternion(1, 0, 0, 0)\n", + "target_quat.normalize()\n", + "\n", + "Mref = pin.SE3()\n", + "Mref.translation = target_pos.reshape(3,1)\n", + "Mref.rotation = target_quat.matrix()\n", + "\n", + "robot.viewer.gui.refresh()" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "state = StatePinocchio(robot.model)\n", + "\n", + "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)\n", + "uRegCost = CostModelControl(robot.model, nu = 1)\n", + "xPendCost = CostModelDoublePendulum(robot.model, \n", + " frame=state, \n", + " ref=state.zero, \n", + " nu=1,\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-3, cost=uRegCost)\n", + "runningCostModel.addCost(name=\"pend\", weight=1, cost=xPendCost)\n", + "terminalCostModel.addCost(name=\"ori2\", weight=1e5, cost=xPendCost)" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "actModel = ActuationModelDoublePendulum(robot.model, actLink = 1)\n", + "runningModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, runningCostModel))\n", + "terminalModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, terminalCostModel))" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "# Defining the time duration for running action models and the terminal one\n", + "dt = 1e-2\n", + "runningModel.timeStep = dt\n", + "\n", + "T = 100\n", + "x0 = np.array([3.14, 0, 0., 0. ])\n", + "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 0 2.00251e+05 2.49231e+09 -2.00919e+04 1.00000e+03 1.00000e+03 0.5000 0\n", + " 1 2.00219e+05 6.36115e+08 -5.07140e+03 1.00000e+03 1.00000e+03 0.5000 0\n", + " 2 2.00207e+05 1.61402e+08 -1.25930e+03 1.00000e+03 1.00000e+03 0.5000 0\n", + " 3 2.00202e+05 4.15162e+07 -3.08384e+02 1.00000e+03 1.00000e+03 0.5000 0\n", + " 4 2.00200e+05 1.10519e+07 -7.35331e+01 1.00000e+03 1.00000e+03 0.5000 0\n", + " 5 2.00200e+05 3.15617e+06 -1.63488e+01 1.00000e+03 1.00000e+03 0.5000 0\n", + " 6 2.00199e+05 1.03152e+06 -2.80766e+00 1.00000e+03 1.00000e+03 0.5000 0\n", + " 7 2.00199e+05 4.24028e+05 1.43417e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 8 2.00198e+05 1.23707e+05 7.82398e-01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 9 2.00197e+05 1.44061e+05 9.11869e-01 1.00000e+02 1.00000e+02 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 10 2.00196e+05 1.75495e+05 1.11113e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 11 2.00194e+05 2.20187e+05 1.39435e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 12 2.00192e+05 2.81390e+05 1.78217e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 13 2.00190e+05 3.63597e+05 2.30309e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 14 2.00187e+05 4.72875e+05 2.99561e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 15 2.00183e+05 6.17300e+05 3.91099e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 16 2.00177e+05 8.07554e+05 5.11708e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 17 2.00170e+05 1.05770e+06 6.70327e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 18 2.00160e+05 1.38620e+06 8.78711e+00 1.00000e+02 1.00000e+02 1.0000 1\n", + " 19 2.00148e+05 1.81727e+06 1.15229e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 20 2.00132e+05 2.38258e+06 1.51129e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 21 2.00111e+05 3.12354e+06 1.98223e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 22 2.00083e+05 4.09415e+06 2.59981e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 23 2.00046e+05 5.36473e+06 3.40939e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 24 1.99998e+05 7.02658e+06 4.47026e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 25 1.99935e+05 9.19784e+06 5.85970e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 26 1.99853e+05 1.20307e+07 7.67828e+01 1.00000e+02 1.00000e+02 1.0000 1\n", + " 27 1.99745e+05 1.57200e+07 1.00566e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 28 1.99604e+05 2.05133e+07 1.31634e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 29 1.99420e+05 2.67219e+07 1.72161e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 30 1.99178e+05 3.47316e+07 2.24929e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 31 1.98864e+05 4.50114e+07 2.93468e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 32 1.98455e+05 5.81166e+07 3.82212e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 33 1.97923e+05 7.46804e+07 4.96646e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 34 1.97235e+05 9.53860e+07 6.43430e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 35 1.96347e+05 1.20909e+08 8.30429e+02 1.00000e+02 1.00000e+02 1.0000 1\n", + " 36 1.95208e+05 1.51819e+08 1.06660e+03 1.00000e+02 1.00000e+02 1.0000 1\n", + " 37 1.93756e+05 1.88436e+08 1.36160e+03 1.00000e+02 1.00000e+02 1.0000 1\n", + " 38 1.91919e+05 2.30651e+08 1.72507e+03 1.00000e+02 1.00000e+02 1.0000 1\n", + " 39 1.89618e+05 2.77749e+08 2.16542e+03 1.00000e+02 1.00000e+02 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 40 1.52107e+05 1.19024e+10 7.99311e+05 1.00000e+02 1.00000e+02 0.0312 1\n", + " 41 1.04287e+05 2.47125e+09 9.87329e+04 1.00000e+01 1.00000e+01 1.0000 1\n", + " 42 6.84717e+04 5.83726e+09 1.92524e+05 1.00000e+01 1.00000e+01 0.2500 1\n", + " 43 5.54649e+04 6.51313e+09 1.22500e+05 1.00000e+01 1.00000e+01 0.5000 1\n", + " 44 2.16775e+04 5.33861e+10 1.01503e+05 1.00000e+01 1.00000e+01 0.5000 1\n", + " 45 6.00681e+03 1.37814e+10 3.79650e+04 1.00000e+00 1.00000e+00 1.0000 1\n", + " 46 2.19039e+03 1.66324e+06 1.07710e+04 1.00000e+00 1.00000e+00 0.5000 1\n", + " 47 5.48511e+02 7.68537e+05 3.28492e+03 1.00000e-01 1.00000e-01 1.0000 1\n", + " 48 4.66669e+02 5.26506e+04 2.00445e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 49 4.26123e+02 1.19294e+04 9.27419e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 4.02336e+02 8.75391e+03 5.26777e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + " 51 3.95506e+02 6.51720e+03 3.41902e+01 1.00000e-01 1.00000e-01 0.2500 1\n", + " 52 3.90174e+02 3.77447e+03 3.02021e+01 1.00000e-01 1.00000e-01 0.2500 1\n", + " 53 3.84577e+02 2.19823e+03 2.71642e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + " 54 3.75302e+02 5.68460e+02 2.75948e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + " 55 3.68301e+02 2.13517e+02 1.92654e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + " 56 3.65215e+02 1.11803e+02 1.30171e+01 1.00000e-02 1.00000e-02 1.0000 1\n", + " 57 3.61628e+02 1.36622e+02 2.03598e+01 1.00000e-02 1.00000e-02 0.2500 1\n", + " 58 3.59448e+02 1.24390e+02 1.60325e+01 1.00000e-03 1.00000e-03 1.0000 1\n", + " 59 3.56167e+02 2.19222e+02 2.09220e+01 1.00000e-03 1.00000e-03 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 60 3.51001e+02 9.11162e+02 1.73022e+01 1.00000e-03 1.00000e-03 0.5000 1\n", + " 61 3.46090e+02 2.28356e+02 9.54641e+00 1.00000e-04 1.00000e-04 1.0000 1\n", + " 62 3.43280e+02 2.71194e+01 4.10627e+00 1.00000e-05 1.00000e-05 1.0000 1\n", + " 63 3.41468e+02 7.65346e+01 2.03785e+00 1.00000e-06 1.00000e-06 1.0000 1\n", + " 64 3.39961e+02 6.75324e+01 1.53178e+00 1.00000e-07 1.00000e-07 1.0000 1\n", + " 65 3.38531e+02 1.08191e+01 1.42259e+00 1.00000e-08 1.00000e-08 1.0000 1\n", + " 66 3.37121e+02 9.26116e+00 1.38538e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 67 3.35688e+02 9.42177e+00 1.39556e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 68 3.34205e+02 9.40791e+00 1.43652e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 69 3.32659e+02 9.67683e+00 1.49385e+00 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", + " 70 3.31050e+02 9.94176e+00 1.55426e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 71 3.29398e+02 1.00794e+01 1.60111e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 72 3.27739e+02 9.96503e+00 1.61612e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 73 3.26128e+02 9.50706e+00 1.58267e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 74 3.24627e+02 8.67890e+00 1.49097e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 75 3.23291e+02 7.54031e+00 1.34281e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 76 3.22161e+02 6.22333e+00 1.15245e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 77 3.21249e+02 4.88773e+00 9.42434e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 78 3.20545e+02 3.66962e+00 7.36308e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 79 3.20023e+02 2.65008e+00 5.52115e-01 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", + " 80 3.19649e+02 1.85335e+00 3.99546e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 81 3.19389e+02 1.26320e+00 2.80640e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 82 3.19212e+02 8.43751e-01 1.92351e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 83 3.19094e+02 5.54803e-01 1.29252e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 84 3.19016e+02 3.60420e-01 8.54864e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 85 3.18965e+02 2.31964e-01 5.58319e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 86 3.18932e+02 1.48221e-01 3.61020e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 87 3.18911e+02 9.41830e-02 2.31609e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 88 3.18898e+02 5.95885e-02 1.47664e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 89 3.18890e+02 3.75740e-02 9.36834e-03 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 90 3.18884e+02 2.36308e-02 5.92065e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 91 3.18881e+02 1.48311e-02 3.73036e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 92 3.18879e+02 9.29344e-03 2.34470e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 93 3.18877e+02 5.81606e-03 1.47096e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 94 3.18877e+02 3.63627e-03 9.21431e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 95 3.18876e+02 2.27165e-03 5.76518e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 96 3.18876e+02 1.41829e-03 3.60379e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 97 3.18876e+02 8.85065e-04 2.25106e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 98 3.18876e+02 5.52110e-04 1.40528e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 99 3.18875e+02 3.44304e-04 8.76879e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 100 3.18875e+02 2.14665e-04 5.46966e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 101 3.18875e+02 1.33812e-04 3.41081e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 102 3.18875e+02 8.34004e-05 2.12646e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 103 3.18875e+02 5.19741e-05 1.32550e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 104 3.18875e+02 3.23871e-05 8.26115e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 105 3.18875e+02 2.01800e-05 5.14819e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 106 3.18875e+02 1.25733e-05 3.20797e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 107 3.18875e+02 7.83347e-06 1.99883e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 108 3.18875e+02 4.88032e-06 1.24537e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 109 3.18875e+02 3.04036e-06 7.75895e-07 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", + " 110 3.18875e+02 1.89408e-06 4.83384e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 111 3.18875e+02 1.17993e-06 3.01141e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 112 3.18875e+02 7.35050e-07 1.87602e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 113 3.18875e+02 4.57895e-07 1.16869e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 114 3.18875e+02 2.85244e-07 7.28040e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 115 3.18875e+02 1.77689e-07 4.53530e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 116 3.18875e+02 1.10689e-07 2.82523e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 117 3.18875e+02 6.89515e-08 1.75994e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 118 3.18875e+02 4.29523e-08 1.09633e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 119 3.18875e+02 2.67560e-08 6.82939e-09 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", + " 120 3.18875e+02 1.66672e-08 4.25423e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 121 3.18875e+02 1.03824e-08 2.65008e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 122 3.18875e+02 6.46749e-09 1.65081e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 123 3.18875e+02 4.02873e-09 1.02833e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 124 3.18875e+02 2.50961e-09 6.40576e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 125 3.18875e+02 1.56329e-09 3.99031e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 126 3.18875e+02 9.73817e-10 2.48566e-10 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "data": { + "text/plain": [ + "([array([3.14, 0. , 0. , 0. ]),\n", + " array([ 3.17269079, -0.05672873, 3.26907942, -5.6728731 ]),\n", + " array([ 3.20808333, -0.11791405, 3.53925368, -6.11853221]),\n", + " array([ 3.24602991, -0.18303993, 3.79465829, -6.51258806]),\n", + " array([ 3.28631146, -0.25143034, 4.02815487, -6.83904043]),\n", + " array([ 3.32863628, -0.32225426, 4.23248143, -7.08239242]),\n", + " array([ 3.37265336, -0.39456111, 4.40170846, -7.23068519]),\n", + " array([ 3.41797962, -0.46734364, 4.53262634, -7.27825265]),\n", + " array([ 3.46423776, -0.53961941, 4.62581357, -7.22757736]),\n", + " array([ 3.51109735, -0.6105138 , 4.68595932, -7.08943814]),\n", + " array([ 3.55831017, -0.67932569, 4.72128149, -6.8811892 ]),\n", + " array([ 3.60573282, -0.74556377, 4.74226543, -6.62380789]),\n", + " array([ 3.65333474, -0.80895137, 4.76019217, -6.33875985]),\n", + " array([ 3.70119372, -0.86940691, 4.78589762, -6.04555448]),\n", + " array([ 3.74948362, -0.92701044, 4.82898998, -5.76035323]),\n", + " array([ 3.79845891, -0.98196575, 4.89752875, -5.49553029]),\n", + " array([ 3.84843933, -1.03456439, 4.99804218, -5.25986456]),\n", + " array([ 3.89979668, -1.08515473, 5.13573525, -5.0590335 ]),\n", + " array([ 3.95294438, -1.13411643, 5.31476949, -4.89617035]),\n", + " array([ 4.00832974, -1.18183989, 5.53853623, -4.77234634]),\n", + " array([ 4.06642848, -1.228709 , 5.80987453, -4.68691048]),\n", + " array([ 4.12774046, -1.27508556, 6.13119769, -4.63765658]),\n", + " array([ 4.19278536, -1.32129356, 6.50448952, -4.62080012]),\n", + " array([ 4.26209653, -1.36760105, 6.93111689, -4.63074879]),\n", + " array([ 4.33621036, -1.41419757, 7.4113833 , -4.65965185]),\n", + " array([ 4.41564764, -1.46116489, 7.94372822, -4.69673219]),\n", + " array([ 4.50088242, -1.5084395 , 8.52347822, -4.72746088]),\n", + " array([ 4.5922936 , -1.55576706, 9.14111733, -4.73275575]),\n", + " array([ 4.69009581, -1.60265295, 9.78022093, -4.68858863]),\n", + " array([ 4.79425117, -1.64831927, 10.4155366 , -4.56663234]),\n", + " array([ 4.90437268, -1.69168637, 11.01215056, -4.33671047]),\n", + " array([ 5.01964264, -1.73140172, 11.5269963 , -3.97153451]),\n", + " array([ 5.13877937, -1.76593439, 11.91367256, -3.45326678]),\n", + " array([ 5.26008215, -1.7937347 , 12.13027836, -2.78003127]),\n", + " array([ 5.38156319, -1.81343007, 12.14810364, -1.96953707]),\n", + " array([ 5.50114158, -1.82400622, 11.95783944, -1.05761538]),\n", + " array([ 5.61684922, -1.82492397, 11.5707639 , -0.09177474]),\n", + " array([ 5.72699763, -1.81614718, 11.01484098, 0.87767905]),\n", + " array([ 5.83027723, -1.79809077, 10.32795985, 1.80564127]),\n", + " array([ 5.92578803, -1.7715189 , 9.55108061, 2.65718651]),\n", + " array([ 6.01301839, -1.73742662, 8.72303556, 3.40922815]),\n", + " array([ 6.09179257, -1.69692901, 7.87741826, 4.04976071]),\n", + " array([ 6.16220473, -1.65117055, 7.04121621, 4.57584654]),\n", + " array([ 6.22455115, -1.60125824, 6.23464168, 4.99123066]),\n", + " array([ 6.27926802, -1.54821732, 5.47168691, 5.30409227]),\n", + " array([ 6.32687857, -1.49296568, 4.76105501, 5.52516356]),\n", + " array([ 6.36795081, -1.43630286, 4.10722369, 5.66628276]),\n", + " array([ 6.40306563, -1.37890923, 3.51148212, 5.739363 ]),\n", + " array([ 6.43279411, -1.32135205, 2.97284831, 5.7557174 ]),\n", + " array([ 6.45768237, -1.2640954 , 2.48882544, 5.72566532]),\n", + " array([ 6.47824228, -1.20751194, 2.05599116, 5.65834575]),\n", + " array([ 6.49494663, -1.15189522, 1.67043511, 5.56167247]),\n", + " array([ 6.50822732, -1.09747143, 1.32806919, 5.44237898]),\n", + " array([ 6.51847569, -1.04441029, 1.02483744, 5.30611413]),\n", + " array([ 6.5260442 , -0.99283467, 0.75685039, 5.15756167]),\n", + " array([ 6.53124884, -0.94282901, 0.52046434, 5.0005659 ]),\n", + " array([ 6.53437206, -0.89444648, 0.31232229, 4.83825296]),\n", + " array([ 6.53566575, -0.84771506, 0.12936877, 4.67314194]),\n", + " array([ 6.53535423, -0.80264263, -0.03115233, 4.50724339]),\n", + " array([ 6.53363713, -0.75922118, -0.17171028, 4.34214452]),\n", + " array([ 6.53069206, -0.71743036, -0.29450614, 4.17908191]),\n", + " array([ 6.52667712, -0.67724034, -0.40149424, 4.01900266]),\n", + " array([ 6.52173308, -0.63861418, -0.49440462, 3.86261555]),\n", + " array([ 6.51598542, -0.60150985, -0.57476513, 3.71043343]),\n", + " array([ 6.5095462 , -0.56588176, -0.64392247, 3.56280839]),\n", + " array([ 6.50251558, -0.53168216, -0.70306169, 3.41996069]),\n", + " array([ 6.49498334, -0.49886213, -0.75322397, 3.28200254]),\n", + " array([ 6.48703012, -0.46737255, -0.79532272, 3.14895766]),\n", + " array([ 6.47872854, -0.43716478, -0.83015786, 3.02077728]),\n", + " array([ 6.47014425, -0.40819125, -0.8584286 , 2.89735317]),\n", + " array([ 6.46133681, -0.38040597, -0.88074464, 2.77852831]),\n", + " array([ 6.45236045, -0.35376491, -0.89763601, 2.66410548]),\n", + " array([ 6.44326483, -0.32822637, -0.90956179, 2.5538542 ]),\n", + " array([ 6.43409565, -0.30375121, -0.91691759, 2.44751625]),\n", + " array([ 6.42489523, -0.28030311, -0.92004217, 2.34481002]),\n", + " array([ 6.415703 , -0.25784877, -0.91922315, 2.24543385]),\n", + " array([ 6.40655598, -0.23635808, -0.91470197, 2.1490686 ]),\n", + " array([ 6.3974892 , -0.21580429, -0.90667819, 2.05537938]),\n", + " array([ 6.38853607, -0.19616412, -0.89531318, 1.96401677]),\n", + " array([ 6.37972873, -0.17741795, -0.88073334, 1.87461745]),\n", + " array([ 6.3710984 , -0.1595499 , -0.8630328 , 1.78680438]),\n", + " array([ 6.36267565, -0.14254804, -0.84227575, 1.70018653]),\n", + " array([ 6.35449066, -0.12640445, -0.81849845, 1.61435828]),\n", + " array([ 6.34657355, -0.11111547, -0.79171084, 1.52889842]),\n", + " array([ 6.33895457, -0.09668178, -0.76189797, 1.44336888]),\n", + " array([ 6.33166436, -0.08310865, -0.72902111, 1.35731313]),\n", + " array([ 6.32473418, -0.07040611, -0.69301869, 1.27025431]),\n", + " array([ 6.31819611, -0.05858917, -0.65380704, 1.18169312]),\n", + " array([ 6.3120833 , -0.04767812, -0.611281 , 1.09110542]),\n", + " array([ 6.30643015, -0.03769872, -0.56531434, 0.99793964]),\n", + " array([ 6.30127255, -0.02868258, -0.51576021, 0.90161405]),\n", + " array([ 6.29664804, -0.02066745, -0.46245145, 0.80151385]),\n", + " array([ 6.29259603, -0.01369756, -0.40520096, 0.69698825]),\n", + " array([ 6.289158 , -0.00782409, -0.34380213, 0.58734757]),\n", + " array([ 6.28637771e+00, -3.10548063e-03, -2.78029552e-01, 4.71860651e-01]),\n", + " array([ 6.28430131e+00, 3.92045719e-04, -2.07639902e-01, 3.49752635e-01]),\n", + " array([ 6.28297758e+00, 2.59408146e-03, -1.32373435e-01, 2.20203575e-01]),\n", + " array([ 6.28245801e+00, 3.41756373e-03, -5.19561254e-02, 8.23482266e-02]),\n", + " array([ 6.28279699e+00, 2.77034009e-03, 3.38971527e-02, -6.47223641e-02]),\n", + " array([ 6.28405162e+00, 5.51025211e-04, 1.25463523e-01, -2.21931488e-01]),\n", + " array([ 6.28403803e+00, 5.43145315e-04, -1.35868553e-03, -7.87989649e-04])],\n", + " [array([0.52657293]),\n", + " array([0.06560521]),\n", + " array([0.0885465]),\n", + " array([0.11290929]),\n", + " array([0.13787118]),\n", + " array([0.16247003]),\n", + " array([0.18577947]),\n", + " array([0.2071721]),\n", + " array([0.226524]),\n", + " array([0.24425101]),\n", + " array([0.26115843]),\n", + " array([0.27819085]),\n", + " array([0.29620404]),\n", + " array([0.3158346]),\n", + " array([0.33747302]),\n", + " array([0.36130321]),\n", + " array([0.38736589]),\n", + " array([0.41561647]),\n", + " array([0.44596353]),\n", + " array([0.47828332]),\n", + " array([0.51240881]),\n", + " array([0.54809175]),\n", + " array([0.58493384]),\n", + " array([0.62228251]),\n", + " array([0.65909015]),\n", + " array([0.69374912]),\n", + " array([0.72394483]),\n", + " array([0.74661976]),\n", + " array([0.75819647]),\n", + " array([0.75521342]),\n", + " array([0.73539264]),\n", + " array([0.69883682]),\n", + " array([0.64869889]),\n", + " array([0.59066594]),\n", + " array([0.53121548]),\n", + " array([0.47548303]),\n", + " array([0.42590509]),\n", + " array([0.38221238]),\n", + " array([0.34243647]),\n", + " array([0.3041615]),\n", + " array([0.26544407]),\n", + " array([0.22523097]),\n", + " array([0.18337588]),\n", + " array([0.14043259]),\n", + " array([0.09737254]),\n", + " array([0.05531914]),\n", + " array([0.01534388]),\n", + " array([-0.02166323]),\n", + " array([-0.05505574]),\n", + " array([-0.08444135]),\n", + " array([-0.10965878]),\n", + " array([-0.13073709]),\n", + " array([-0.14784897]),\n", + " array([-0.16126597]),\n", + " array([-0.17131971]),\n", + " array([-0.17837078]),\n", + " array([-0.18278545]),\n", + " array([-0.18491912]),\n", + " array([-0.18510568]),\n", + " array([-0.18365117]),\n", + " array([-0.18083081]),\n", + " array([-0.17688831]),\n", + " array([-0.17203679]),\n", + " array([-0.16646067]),\n", + " array([-0.16031807]),\n", + " array([-0.15374354]),\n", + " array([-0.14685071]),\n", + " array([-0.13973501]),\n", + " array([-0.13247608]),\n", + " array([-0.12514007]),\n", + " array([-0.11778163]),\n", + " array([-0.11044575]),\n", + " array([-0.10316933]),\n", + " array([-0.09598252]),\n", + " array([-0.08890999]),\n", + " array([-0.08197188]),\n", + " array([-0.0751847]),\n", + " array([-0.06856211]),\n", + " array([-0.06211555]),\n", + " array([-0.05585477]),\n", + " array([-0.04978834]),\n", + " array([-0.04392402]),\n", + " array([-0.03826915]),\n", + " array([-0.03283094]),\n", + " array([-0.02761675]),\n", + " array([-0.02263432]),\n", + " array([-0.01789204]),\n", + " array([-0.01339911]),\n", + " array([-0.00916576]),\n", + " array([-0.00520347]),\n", + " array([-0.00152512]),\n", + " array([0.00185478]),\n", + " array([0.0049199]),\n", + " array([0.00765189]),\n", + " array([0.01003017]),\n", + " array([0.01203174]),\n", + " array([0.01363093]),\n", + " array([0.01479925]),\n", + " array([0.01550285]),\n", + " array([-0.02045494])],\n", + " True)" + ] + }, + "execution_count": 23, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Creating the DDP solver for this OC problem, defining a logger\n", + "ddp = SolverFDDP(problem)\n", + "ddp.callback = [CallbackDDPVerbose()]\n", + "ddp.callback.append(CallbackDDPLogger())\n", + "\n", + "us0 = np.zeros([T,1])\n", + "#us0 = ddp.us\n", + "xs0 = [problem.initialState+0.1]*len(ddp.models())\n", + "\n", + "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n", + "#ddp.solve(maxiter=150)" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "metadata": {}, + "outputs": [], + "source": [ + "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "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": 8, + "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[0,0] = ddp.us[i]\n", + " nle[:,0] = m2a(robot.data.nle) \n", + " r[:] = tau - nle\n", + " q_dd = np.dot(Minv, r)\n", + " q = q + q_d*dt + q_dd*dt**2\n", + " q_d = q_d + q_dd*dt\n", + " #pin.forwardKinematics(robot.model, robot.data, q, q_d)\n", + " robot.display(q)\n", + " time.sleep(dt)" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<matplotlib.legend.Legend at 0x7f57076b5390>" + ] + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "control = np.vstack(ddp.us)\n", + "t = np.arange(0,T*dt, dt)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('Motor torques')\n", + "# axs[0].plot(t,control[:,0], t,control[:,1])\n", + "axs[0].plot(t,control[:,0])\n", + "axs[0].set_title('Moments')\n", + "axs[0].legend(['M1','M2'])\n", + "\n", + "t_state = np.append(t, t[-1]+dt)\n", + "state = np.vstack(ddp.xs)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('States')\n", + "axs[0].plot(t_state,state[:,0], t_state, state[:,1])\n", + "axs[0].set_title('Position')\n", + "axs[0].legend(['Link 1','Link2'])\n", + "axs[1].plot(t_state,state[:,2], t_state, state[:,3])\n", + "axs[1].set_title('Vels')\n", + "axs[1].legend(['Link 1','Link2'])" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.16" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/notebooks/acrobot.ipynb b/examples/notebooks/acrobot.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..b6eb826049d4f4b95f9c96a05450124d793549ef --- /dev/null +++ b/examples/notebooks/acrobot.ipynb @@ -0,0 +1,601 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl import *\n", + "import pinocchio as pin\n", + "import numpy as np\n", + "\n", + "robot = loadBorinotArm()\n", + "robot.initViewer(loadModel=True)\n", + "\n", + "q0 = [3.14, 0]\n", + "robot.q0.flat = q0\n", + "robot.framesForwardKinematics(robot.q0)\n", + "robot.display(robot.q0)\n", + "\n", + "IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)\n", + "IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)\n", + "Mlink1 = robot.data.oMf[IDX_LINK1]\n", + "Mlink2 = robot.data.oMf[IDX_LINK2]\n", + "\n", + "target_pos = np.array([0,0,0.3])\n", + "target_quat = pin.Quaternion(1, 0, 0, 0)\n", + "target_quat.normalize()\n", + "\n", + "Mref = pin.SE3()\n", + "Mref.translation = target_pos.reshape(3,1)\n", + "Mref.rotation = target_quat.matrix()\n", + "\n", + "robot.viewer.gui.refresh()" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [], + "source": [ + "state = StatePinocchio(robot.model)\n", + "\n", + "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)\n", + "uRegCost = CostModelControl(robot.model, nu = 1)\n", + "xPendCost = CostModelDoublePendulum(robot.model, \n", + " frame=state, \n", + " ref=state.zero, \n", + " nu=1,\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-3, cost=uRegCost)\n", + "runningCostModel.addCost(name=\"pend\", weight=1, cost=xPendCost)\n", + "terminalCostModel.addCost(name=\"ori2\", weight=1e5, cost=xPendCost)" + ] + }, + { + "cell_type": "code", + "execution_count": 24, + "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))" + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "metadata": {}, + "outputs": [], + "source": [ + "# Defining the time duration for running action models and the terminal one\n", + "dt = 1e-2\n", + "runningModel.timeStep = dt\n", + "\n", + "T = 100\n", + "x0 = np.array([3.14, 0, 0., 0. ])\n", + "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)" + ] + }, + { + "cell_type": "code", + "execution_count": 26, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 0 2.00201e+05 1.16096e+09 9.21968e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 1 2.00200e+05 1.54461e+07 3.14734e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 2 2.00199e+05 1.79399e+03 3.09626e-01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 3 2.00199e+05 3.39328e+03 5.89887e-01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 4 2.00197e+05 6.47120e+03 1.12549e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 5 2.00195e+05 1.23441e+04 2.14841e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 6 2.00190e+05 2.35492e+04 4.10323e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 7 2.00180e+05 4.49270e+04 7.84407e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 8 2.00162e+05 8.57134e+04 1.50217e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 9 2.00128e+05 1.63545e+05 2.88639e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 10 2.00061e+05 3.12250e+05 5.58218e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 11 1.99929e+05 5.97981e+05 1.09351e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 12 1.99660e+05 1.16043e+06 2.19929e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 13 1.99065e+05 2.38449e+06 4.68916e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 14 1.97416e+05 6.33753e+06 1.16250e+03 1.00000e+00 1.00000e+00 1.0000 1\n", + " 15 1.82461e+05 4.99746e+07 5.10514e+03 1.00000e+00 1.00000e+00 1.0000 1\n", + " 16 1.68743e+05 7.51342e+10 5.15698e+04 1.00000e+01 1.00000e+01 1.0000 1\n", + " 17 1.26802e+05 3.99501e+09 3.44668e+05 1.00000e+01 1.00000e+01 0.5000 1\n", + " 18 6.98759e+04 9.82853e+11 2.26947e+05 1.00000e+01 1.00000e+01 0.5000 1\n", + " 19 2.02725e+04 5.71522e+11 1.17776e+05 1.00000e+00 1.00000e+00 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 20 1.02926e+04 1.14975e+11 2.59392e+04 1.00000e+00 1.00000e+00 0.5000 1\n", + " 21 6.50756e+03 2.62667e+10 6.55275e+03 1.00000e-01 1.00000e-01 1.0000 1\n", + " 22 5.34085e+03 4.07997e+09 4.17908e+03 1.00000e-01 1.00000e-01 0.2500 1\n", + " 23 4.70136e+03 1.88124e+09 2.62343e+03 1.00000e-01 1.00000e-01 0.2500 1\n", + " 24 3.99760e+03 9.09931e+08 1.84358e+03 1.00000e-01 1.00000e-01 0.5000 1\n", + " 25 3.32742e+03 7.81105e+07 1.11239e+03 1.00000e-02 1.00000e-02 1.0000 1\n", + " 26 3.06404e+03 1.43324e+08 9.14533e+02 1.00000e-02 1.00000e-02 0.5000 1\n", + " 27 2.85334e+03 9.68882e+07 5.65338e+02 1.00000e-02 1.00000e-02 0.5000 1\n", + " 28 2.79953e+03 3.04477e+07 2.66526e+02 1.00000e-03 1.00000e-03 1.0000 1\n", + " 29 2.70925e+03 2.13333e+08 2.80254e+02 1.00000e-03 1.00000e-03 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 30 2.50004e+03 2.92098e+08 3.27901e+02 1.00000e-04 1.00000e-04 1.0000 1\n", + " 31 2.02035e+03 3.52509e+05 1.26929e+03 1.00000e-04 1.00000e-04 0.5000 1\n", + " 32 1.80103e+03 2.08929e+07 1.97848e+03 1.00000e-04 1.00000e-04 0.1250 1\n", + " 33 1.60557e+03 1.60392e+07 1.42325e+03 1.00000e-04 1.00000e-04 0.2500 1\n", + " 34 1.41725e+03 3.85125e+07 9.65434e+02 1.00000e-04 1.00000e-04 0.2500 1\n", + " 35 1.24798e+03 1.64564e+07 4.53406e+02 1.00000e-04 1.00000e-04 0.5000 1\n", + " 36 1.05211e+03 5.38901e+06 2.75515e+02 1.00000e-05 1.00000e-05 1.0000 1\n", + " 37 8.44057e+02 1.99724e+05 4.26936e+02 1.00000e-06 1.00000e-06 1.0000 1\n", + " 38 8.02529e+02 4.66864e+04 1.73189e+02 1.00000e-06 1.00000e-06 0.5000 1\n", + " 39 7.77646e+02 8.81186e+02 1.00350e+02 1.00000e-06 1.00000e-06 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 40 7.62149e+02 3.22748e+03 6.09360e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 41 7.52141e+02 1.11324e+03 3.83520e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 42 7.45253e+02 3.50300e+03 2.53379e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 43 7.40273e+02 2.73430e+03 1.76460e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 44 7.36427e+02 1.39565e+03 1.31192e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 45 7.33270e+02 6.20272e+02 1.03678e+01 1.00000e-06 1.00000e-06 0.5000 1\n", + " 46 7.30557e+02 2.80257e+02 8.59548e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 47 7.28152e+02 1.42955e+02 7.37005e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 48 7.25979e+02 8.63697e+01 6.45943e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 49 7.23994e+02 6.07746e+01 5.73694e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 7.22170e+02 4.73969e+01 5.13265e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 51 7.20493e+02 3.90506e+01 4.60615e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 52 7.18951e+02 3.29214e+01 4.13491e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 53 7.17537e+02 2.79148e+01 3.70581e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 54 7.16245e+02 2.36222e+01 3.31178e+00 1.00000e-06 1.00000e-06 0.5000 1\n", + " 55 7.15889e+02 1.99076e+01 2.94888e+00 1.00000e-07 1.00000e-07 1.0000 1\n", + " 56 7.12990e+02 2.01704e+01 6.55642e+00 1.00000e-08 1.00000e-08 1.0000 1\n", + " 57 7.10845e+02 6.67999e+02 4.07708e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 58 7.09461e+02 3.80830e+01 2.26922e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 59 7.08542e+02 6.82361e+00 1.34000e+00 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", + " 60 7.07909e+02 4.03002e+00 8.47089e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 61 7.07469e+02 2.73417e+00 5.52833e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 62 7.07165e+02 1.84088e+00 3.65584e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 63 7.06956e+02 1.23860e+00 2.43972e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 64 7.06812e+02 8.37368e-01 1.63849e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 65 7.06713e+02 5.67882e-01 1.10468e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 66 7.06646e+02 3.85585e-01 7.46353e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 67 7.06600e+02 2.61781e-01 5.04698e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 68 7.06569e+02 1.77570e-01 3.41303e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 69 7.06548e+02 1.20293e-01 2.30698e-02 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", + " 70 7.06533e+02 8.13736e-02 1.55814e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 71 7.06524e+02 5.49677e-02 1.05140e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 72 7.06517e+02 3.70811e-02 7.08778e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 73 7.06513e+02 2.49848e-02 4.77356e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 74 7.06510e+02 1.68167e-02 3.21213e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 75 7.06508e+02 1.13087e-02 2.15973e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 76 7.06507e+02 7.59883e-03 1.45112e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 77 7.06506e+02 5.10267e-03 9.74412e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 78 7.06505e+02 3.42460e-03 6.53968e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 79 7.06505e+02 2.29732e-03 4.38710e-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", + " 80 7.06505e+02 1.54053e-03 2.94196e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 81 7.06504e+02 1.03271e-03 1.97224e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 82 7.06504e+02 6.92113e-04 1.32181e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 83 7.06504e+02 4.63746e-04 8.85696e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 84 7.06504e+02 3.10676e-04 5.93365e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 85 7.06504e+02 2.08099e-04 3.97461e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 86 7.06504e+02 1.39374e-04 2.66203e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 87 7.06504e+02 9.33361e-05 1.78274e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 88 7.06504e+02 6.25004e-05 1.19379e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 89 7.06504e+02 4.18492e-05 7.99351e-06 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 90 7.06504e+02 2.80200e-05 5.35208e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 91 7.06504e+02 1.87599e-05 3.58333e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 92 7.06504e+02 1.25596e-05 2.39903e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 93 7.06504e+02 8.40829e-06 1.60609e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 94 7.06504e+02 5.62898e-06 1.07521e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 95 7.06504e+02 3.76828e-06 7.19797e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 96 7.06504e+02 2.52261e-06 4.81856e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 97 7.06504e+02 1.68869e-06 3.22566e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 98 7.06504e+02 1.13043e-06 2.15931e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 99 7.06504e+02 7.56723e-07 1.44547e-07 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", + " 100 7.06504e+02 5.06554e-07 9.67603e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 101 7.06504e+02 3.39087e-07 6.47715e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 102 7.06504e+02 2.26984e-07 4.33579e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 103 7.06504e+02 1.51942e-07 2.90235e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 104 7.06504e+02 1.01709e-07 1.94281e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 105 7.06504e+02 6.80828e-08 1.30050e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 106 7.06504e+02 4.55739e-08 8.70541e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 107 7.06504e+02 3.05066e-08 5.82730e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 108 7.06504e+02 2.04207e-08 3.90072e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 109 7.06504e+02 1.36693e-08 2.61109e-09 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", + " 110 7.06504e+02 9.15005e-09 1.74782e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 111 7.06504e+02 6.12490e-09 1.16997e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 112 7.06504e+02 4.09991e-09 7.83156e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 113 7.06504e+02 2.74441e-09 5.24232e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 114 7.06504e+02 1.83707e-09 3.50913e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 115 7.06504e+02 1.22970e-09 2.34895e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 116 7.06504e+02 8.23141e-10 1.57235e-10 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "data": { + "text/plain": [ + "([array([3.14, 0. , 0. , 0. ]),\n", + " array([ 3.18493482, -0.08713096, 4.49348194, -8.71309552]),\n", + " array([ 3.2298292 , -0.17422292, 4.48943827, -8.70919683]),\n", + " array([ 3.27463366, -0.26123502, 4.48044598, -8.70120942]),\n", + " array([ 3.31930113, -0.34813226, 4.46674667, -8.68972446]),\n", + " array([ 3.36378637, -0.43488521, 4.44852367, -8.67529474]),\n", + " array([ 3.4080461 , -0.52147097, 4.42597344, -8.65857575]),\n", + " array([ 3.45203903, -0.60787403, 4.39929332, -8.64030581]),\n", + " array([ 3.4957257 , -0.69408685, 4.36866653, -8.62128281]),\n", + " array([ 3.53906814, -0.78011023, 4.33424423, -8.60233717]),\n", + " array([ 3.58202938, -0.86595323, 4.29612405, -8.58430083]),\n", + " array([ 3.62457263, -0.95163295, 4.2543245 , -8.56797163]),\n", + " array([ 3.66666017, -1.03717368, 4.20875472, -8.55407264]),\n", + " array([ 3.70825196, -1.12260574, 4.15917857, -8.54320601]),\n", + " array([ 3.74930368, -1.20796374, 4.10517248, -8.53580074]),\n", + " array([ 3.78976444, -1.29328428, 4.04607602, -8.53205407]),\n", + " array([ 3.82957379, -1.37860295, 3.98093443, -8.53186644]),\n", + " array([ 3.86865812, -1.46395065, 3.90843271, -8.5347701 ]),\n", + " array([ 3.90692633, -1.54934918, 3.82682107, -8.53985257]),\n", + " array([ 3.94426465, -1.63480594, 3.73383282, -8.54567695]),\n", + " array([ 3.98053063, -1.72030798, 3.62659768, -8.55020316]),\n", + " array([ 4.01554619, -1.80581515, 3.50155634, -8.55071692]),\n", + " array([ 4.04909007, -1.89125292, 3.35438748, -8.54377767]),\n", + " array([ 4.08088973, -1.97650495, 3.17996605, -8.52520265]),\n", + " array([ 4.11061355, -2.06140607, 2.9723825 , -8.49011177]),\n", + " array([ 4.13786422, -2.14573673, 2.72506642, -8.43306615]),\n", + " array([ 4.16217494, -2.22922011, 2.43107181, -8.34833785]),\n", + " array([ 4.18301081, -2.31152354, 2.08358752, -8.23034349]),\n", + " array([ 4.19977803, -2.39226603, 1.67672214, -8.07424895]),\n", + " array([ 4.21184361, -2.47103299, 1.2065574 , -7.87669617]),\n", + " array([ 4.21856715, -2.54739816, 0.67235412, -7.63651698]),\n", + " array([ 4.21934356, -2.62095029, 0.07764073, -7.35521284]),\n", + " array([ 4.21365137, -2.69131985, -0.5692183 , -7.03695599]),\n", + " array([ 4.20109761, -2.75819961, -1.25537597, -6.68797565]),\n", + " array([ 4.18144808, -2.82135392, -1.96495324, -6.31543089]),\n", + " array([ 4.15463456, -2.88061511, -2.68135242, -5.92611935]),\n", + " array([ 4.12073641, -2.93586965, -3.38981479, -5.525454 ]),\n", + " array([ 4.07994156, -2.98703951, -4.07948487, -5.11698614]),\n", + " array([ 4.03249694, -3.03406423, -4.74446208, -4.70247228]),\n", + " array([ 3.97865966, -3.0768869 , -5.38372748, -4.28226633]),\n", + " array([ 3.91865772, -3.11544464, -6.00019469, -3.85577402]),\n", + " array([ 3.85266466, -3.14966263, -6.59930552, -3.42179966]),\n", + " array([ 3.78078902, -3.17945009, -7.18756462, -2.97874593]),\n", + " array([ 3.70307634, -3.20469726, -7.77126796, -2.52471678]),\n", + " array([ 3.61952115, -3.22527328, -8.3555189 , -2.05760147]),\n", + " array([ 3.5300861 , -3.24102531, -8.94350507, -1.57520325]),\n", + " array([ 3.43472662, -3.25177975, -9.53594786, -1.07544446]),\n", + " array([ 3.33342033, -3.25734622, -10.13062875, -0.55664642]),\n", + " array([ 3.22620107, -3.25752473, -10.72192632, -0.01785156]),\n", + " array([ 3.11319752, -3.25211597, -11.30035464, 0.54087625]),\n", + " array([ 2.99467581, -3.24093327, -11.85217104, 1.11826978]),\n", + " array([ 2.87108366, -3.22381409, -12.35921487, 1.71191798]),\n", + " array([ 2.74309134, -3.2006272 , -12.79923182, 2.31868886]),\n", + " array([ 2.61162144, -3.17127146, -13.14699083, 2.93557402]),\n", + " array([ 2.47785696, -3.13566294, -13.3764471 , 3.56085211]),\n", + " array([ 2.34321717, -3.09371085, -13.46397986, 4.19520901]),\n", + " array([ 2.20929372, -3.0452891 , -13.39234466, 4.84217551]),\n", + " array([ 2.07774808, -2.99021784, -13.1545638 , 5.50712605]),\n", + " array([ 1.95018035, -2.92827437, -12.75677323, 6.19434675]),\n", + " array([ 1.82798839, -2.85924962, -12.2191963 , 6.90247462]),\n", + " array([ 1.71224041, -2.78305121, -11.57479785, 7.61984101]),\n", + " array([ 1.60358529, -2.6998276 , -10.86551226, 8.32236121]),\n", + " array([ 1.50222254, -2.61006306, -10.13627404, 8.976454 ]),\n", + " array([ 1.40794413, -2.51459222, -9.42784116, 9.54708392]),\n", + " array([ 1.32023892, -2.41451805, -8.77052111, 10.0074172 ]),\n", + " array([ 1.23842745, -2.31106757, -8.18114766, 10.34504814]),\n", + " array([ 1.16178642, -2.20544538, -7.6641023 , 10.5622186 ]),\n", + " array([ 1.0896362 , -2.09873042, -7.21502244, 10.67149584]),\n", + " array([ 1.02138612, -1.99182797, -6.82500812, 10.69024557]),\n", + " array([ 0.95654761, -1.8854647 , -6.48385065, 10.63632652]),\n", + " array([ 0.8947285 , -1.78020782, -6.18191078, 10.52568849]),\n", + " array([ 0.83561923, -1.67649297, -5.91092732, 10.37148461]),\n", + " array([ 0.77897738, -1.5746524 , -5.66418506, 10.18405693]),\n", + " array([ 0.72461361, -1.4749394 , -5.43637709, 9.9713008 ]),\n", + " array([ 0.67238 , -1.37754814, -5.22336057, 9.73912544]),\n", + " array([ 0.62216096, -1.28262932, -5.02190441, 9.49188186]),\n", + " array([ 0.57386627, -1.19030217, -4.8294683 , 9.23271545]),\n", + " array([ 0.52742604, -1.10066377, -4.64402354, 8.96383942]),\n", + " array([ 0.48278691, -1.01379637, -4.46391333, 8.68674066]),\n", + " array([ 0.43990944, -0.92977304, -4.28774644, 8.40233236]),\n", + " array([ 0.39876627, -0.84866238, -4.11431701, 8.11106667]),\n", + " array([ 0.35934083, -0.7705322 , -3.94254454, 7.81301792]),\n", + " array([ 0.32162654, -0.69545275, -3.77142905, 7.50794454]),\n", + " array([ 0.28562636, -0.6234994 , -3.60001745, 7.1953355 ]),\n", + " array([ 0.25135258, -0.55475494, -3.42737839, 6.87444539]),\n", + " array([ 0.21882675, -0.48931173, -3.2525831 , 6.54432136]),\n", + " array([ 0.18807984, -0.42727349, -3.0746908 , 6.20382372]),\n", + " array([ 0.15915247, -0.36875707, -2.8927373 , 5.85164182]),\n", + " array([ 0.13209521, -0.31389401, -2.70572581, 5.48630617]),\n", + " array([ 0.10696901, -0.26283204, -2.51261927, 5.1061972 ]),\n", + " array([ 0.08384568, -0.21573653, -2.31233348, 4.70955131]),\n", + " array([ 0.06280837, -0.17279189, -2.10373072, 4.29446411]),\n", + " array([ 0.04395224, -0.13420298, -1.88561332, 3.85889105]),\n", + " array([ 0.02738507, -0.10019652, -1.65671694, 3.40064542]),\n", + " array([ 0.01322804, -0.07102258, -1.41570347, 2.91739391]),\n", + " array([ 1.61650040e-03, -4.69560835e-02, -1.16115350e+00, 2.40664990e+00]),\n", + " array([-0.00729909, -0.02829843, -0.89155866, 1.86576554]),\n", + " array([-0.01335223, -0.01537919, -0.60531455, 1.29192372]),\n", + " array([-0.01635938, -0.00855786, -0.30071529, 0.6821328 ]),\n", + " array([-0.01611896, -0.00822546, 0.02404208, 0.03323985]),\n", + " array([-0.01586976, -0.00809705, 0.02492077, 0.01284125])],\n", + " [array([-0.41707639]),\n", + " array([-0.02170736]),\n", + " array([-0.04339121]),\n", + " array([-0.06488339]),\n", + " array([-0.08608214]),\n", + " array([-0.10690605]),\n", + " array([-0.12728863]),\n", + " array([-0.14717918]),\n", + " array([-0.16654239]),\n", + " array([-0.18535658]),\n", + " array([-0.20361058]),\n", + " array([-0.22129932]),\n", + " array([-0.23841813]),\n", + " array([-0.25495595]),\n", + " array([-0.27088756]),\n", + " array([-0.28616505]),\n", + " array([-0.30070894]),\n", + " array([-0.31439939]),\n", + " array([-0.32706843]),\n", + " array([-0.33849405]),\n", + " array([-0.34839822]),\n", + " array([-0.3564508]),\n", + " array([-0.36228264]),\n", + " array([-0.36551154]),\n", + " array([-0.36578462]),\n", + " array([-0.36283921]),\n", + " array([-0.35657909]),\n", + " array([-0.34715357]),\n", + " array([-0.33501288]),\n", + " array([-0.32090036]),\n", + " array([-0.30574326]),\n", + " array([-0.29043471]),\n", + " array([-0.27556091]),\n", + " array([-0.26118713]),\n", + " array([-0.24681691]),\n", + " array([-0.23155717]),\n", + " array([-0.21440566]),\n", + " array([-0.19451738]),\n", + " array([-0.17134323]),\n", + " array([-0.14462508]),\n", + " array([-0.11430488]),\n", + " array([-0.08042383]),\n", + " array([-0.04306259]),\n", + " array([-0.00233759]),\n", + " array([0.04155727]),\n", + " array([0.0882841]),\n", + " array([0.13729043]),\n", + " array([0.18775348]),\n", + " array([0.23855829]),\n", + " array([0.28833105]),\n", + " array([0.3355495]),\n", + " array([0.37874419]),\n", + " array([0.41677769]),\n", + " array([0.44913947]),\n", + " array([0.47613113]),\n", + " array([0.49877609]),\n", + " array([0.51832359]),\n", + " array([0.53537352]),\n", + " array([0.54891866]),\n", + " array([0.55588481]),\n", + " array([0.55180844]),\n", + " array([0.53280124]),\n", + " array([0.49790594]),\n", + " array([0.4502027]),\n", + " array([0.39572102]),\n", + " array([0.34097891]),\n", + " array([0.2908931]),\n", + " array([0.2480415]),\n", + " array([0.21303487]),\n", + " array([0.18528336]),\n", + " array([0.16366376]),\n", + " array([0.14693799]),\n", + " array([0.13396036]),\n", + " array([0.12375473]),\n", + " array([0.115526]),\n", + " array([0.10864418]),\n", + " array([0.10262018]),\n", + " array([0.09708141]),\n", + " array([0.09175015]),\n", + " array([0.0864254]),\n", + " array([0.08096782]),\n", + " array([0.07528741]),\n", + " array([0.06933347]),\n", + " array([0.06308651]),\n", + " array([0.05655164]),\n", + " array([0.04975356]),\n", + " array([0.04273256]),\n", + " array([0.03554161]),\n", + " array([0.02824437]),\n", + " array([0.02091379]),\n", + " array([0.01363135]),\n", + " array([0.00648661]),\n", + " array([-0.00042301]),\n", + " array([-0.00699249]),\n", + " array([-0.01310974]),\n", + " array([-0.0186566]),\n", + " array([-0.02351091]),\n", + " array([-0.02754985]),\n", + " array([-0.03065489]),\n", + " array([-0.00059537])],\n", + " True)" + ] + }, + "execution_count": 26, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Creating the DDP solver for this OC problem, defining a logger\n", + "ddp = SolverFDDP(problem)\n", + "ddp.callback = [CallbackDDPVerbose()]\n", + "ddp.callback.append(CallbackDDPLogger())\n", + "\n", + "us0 = np.zeros([T,1])\n", + "#us0 = ddp.us\n", + "xs0 = [problem.initialState+0.1]*len(ddp.models())\n", + "\n", + "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n", + "#ddp.solve(maxiter=150)" + ] + }, + { + "cell_type": "code", + "execution_count": 27, + "metadata": {}, + "outputs": [], + "source": [ + "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "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": "markdown", + "metadata": {}, + "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": 28, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<matplotlib.legend.Legend at 0x7fa1936d3490>" + ] + }, + "execution_count": 28, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA3oAAAKGCAYAAAAcdOmuAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDIuMi4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvIxREBQAAIABJREFUeJzs3XmYXHWZ9//PXb3vSS/ZupPuzgIhhD2QIKgoMgKDZHwedUBABWSZEZfBcVweH/VBZ3F0fs6oOIqoSNhEZ0RUFEFhZAuSIGA2oJNe0ll6qU7Se7q76vv7o6pCGzpJL1V1Tp16v64rF6mqU+fcyXVxJZ98v9/7NuecAAAAAADBEfK6AAAAAABAchH0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAMyImbWY2YiZVR/2/gtm5sysYRL3+ICZPZnkur5gZncl854AAGQKgh4AIBmaJV2eeGFmJ0kqStfDzSw3E+4JAEC6EPQAAMmwTtL7xr1+v6Q7x19gZhVmdqeZdZlZq5l91sxCZnaCpG9LOtvM+s1s/9Guj3/2ATN7ysy+ZmY9kr5w2LMulPQZSX8dv+eL8fcXmNmDZtZjZk1mdt2473zBzH5iZneZWa+kD5hZkZndYWb7zGyLmX3CzNrHfceZ2dJxr+8wsy+Ne31JfGVzv5k9bWYnj/vsk2a2y8z6zOxlMzt/ur/5AAAcjn+tBAAkw3pJV8VD2yuS/lrSuZK+NO6ab0iqkLRYUpWk30ja45z7npndKOmDzrlzj3W9pO/FP18t6T5JcyTljS/GOfdrM/snSUudc1eO++heSZslLZC0XNIjZrbDOffb+OdrJb1bsdBaIOnzkpbEf5RI+tVkf0PM7HRJ35f0DkkbJF0p6UEzO15Sg6SbJJ3pnNsd396aM9l7AwBwLKzoAQCSJbGqd4GkbZJ2JT4wsxzFwt+nnXN9zrkWSf8m6aqJbjTJ63c7577hnBtzzg0dqzgzW6hY+Pykc27YOfeCpNsPu+czzrkHnHPR+D3fI+kfnXM9zrmdkr4+qd+JmOskfcc596xzLuKc+6Gkg5LWSIooFiRXmFmec67FObd9CvcGAOCoCHoAgGRZJ+m9kj6gw7ZtSqqWlC+pddx7rZJqj3CvyVy/c4r1LZDU45zrm8I9Fxz2Xqsmr17Sx+PbNvfHt6QulLTAOdck6WOKbTntNLP7zGzBFO4NAMBREfQAAEnhnGtVrCnLxZL++7CPuyWNKhZ+EhbptVU/N8XrJ/rO60o67PVuSZVmVjaFe+5RLJyNv368QUnF417PG/fznYqtBs4a96PYOXevJDnn7olvVa2PP/fLx/j1AAAwaQQ9AEAyXSvprc65gfFvOuciku6X9I9mVmZm9ZJulpQYf9Ahqc7M8id5/WR0SGpINHCJb718WtI/m1lhvDHKtZLuPso97pf0aTObbWZ1kj582OcvSHqvmeXEG8C8edxn35V0o5mttpgSM/vL+K/neDN7q5kVSBqWNKTYdk4AAJKCoAcASBrn3Hbn3IYjfPxhSQOSdkh6UtI9ijUrkaTfKdYkZa+ZdU/i+sn4cfy/YTN7Pv7zyxVrhLJb0k8lfd4598hR7vH/FNuu2axYM5h1h33+UcWareyXdIWkBxIfxH8frpP0TUn7JDUptq1Vip3P+xfFVi73KtZQ5jNT+LUBAHBU5tyxdr4AAABJMrPzJN3lnKvzuhYAAI6GFT0AAAAACBiCHgAAAAAEDFs3AQAAACBgWNEDAAAAgIAh6AEAAABAwBD0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAAAAgIAh6AEAAABAwBD0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAAAAgIAh6AEAAABAwBD0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAAAAgIAh6AEAAABAwBD0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAAAAgIAh6AEAAABAwBD0AAAAACBgCHoAAAAAEDAEPQAAAAAIGIIeAAAAAAQMQQ8AAAAAAoagBwAAAAABQ9ADAAAAgIAh6AEAAABAwBD0AAAAACBgCHrAJJhZi5mNmFn1Ye+/YGbOzBq8qez1zOwOM/uS13UAAADAOwQ9YPKaJV2eeGFmJ0kq8q4cAAAAYGIEPWDy1kl637jX75d0Z+KFmVWY2Z1m1mVmrWb2WTMLxT/7gJk9ZWZfM7P9ZrbDzN4Qf3+nmXWa2fvH3avAzL5qZm1m1mFm3zazovhn55lZu5l9PP69PWZ2dfyz6yVdIekfzKzfzH4ef/+TZrbLzPrM7GUzOz/lv1sAAADwDEEPmLz1ksrN7AQzy5H015LuGvf5NyRVSFos6c2KhcKrx32+WtJLkqok3SPpPklnSloq6UpJ3zSz0vi1X5Z0nKRT45/XSvrcuHvNiz+rVtK1km41s9nOudsk3S3pX51zpc65d5jZ8ZJuknSmc65M0tsltcz8twMAAAB+RdADpiaxqneBpG2SdsXfTwS/Tzvn+pxzLZL+TdJV477b7Jz7gXMuIulHkhZKusU5d9A59xtJI5KWmplJuk7S3znnepxzfZL+SdJl4+41Gv/uqHPuIUn9ko4/Qs0RSQWSVphZnnOuxTm3fYa/DwAAAPCxXK8LADLMOkm/l9Socds2JVVLypfUOu69VsVW3BI6xv18SJKcc4e/VyqpRlKxpI2xzCdJMsXCZELYOTc27vVg/Luv45xrMrOPSfqCpBPN7GFJNzvndh/xVwkAAICMxooeMAXOuVbFmrJcLOm/x33UrdgqW/249xbptRW/qehWLPSd6JybFf9R4ZybMMhNVOYEdd/jnDs3Xp9TbGsoAAAAAoqgB0zdtZLe6pwbGPdeRNL9kv7RzMrMrF7SzfrzM3yT4pyLSvqupK+Z2RxJMrNaM3v7JG/Rodg5QcW/e7yZvdXMCiQNKxYiI1OtCwAAAJmDoAdMkXNuu3NuwwQffVjSgKQdkp5UrOHK96f5mE9KapK03sx6JT2qI5/BO9z3FDuPt9/MHlDsfN6/KLZSuFfSHEmfmWZdAAAAyADm3Ot2eQEAAAAAMhgregAAAAAQMAQ9AABSxMy+b2adZrbpCJ+bmX3dzJrM7CUzOz3dNQIAgomgBwBA6twh6cKjfH6RpGXxH9dL+s801AQAyAIEPQAAUsQ593tJPUe5ZK2kO13MekmzzGx+eqoDAARZUgamm9mFkv5DsYHOtzvn/mWCa96j2MBmJ+lF59x7j3bP6upq19DQkIzyAAA+t3Hjxm7nXI3XdXigVtLOca/b4+/tOfxCM7tesVU/lZSUnLF8+fK0FAgA8M5M/nyccdAzsxxJt0q6QLE/oJ4zswedc1vGXbNM0qclneOc25eYDXY0DQ0N2rBhog72AICgMbNWr2vwiE3w3oTtsJ1zt0m6TZJWrVrl+DMSAIJvJn8+JmPr5lmSmpxzO5xzI5LuU2wrynjXSbrVObdPkpxznUl4LgAAma5d0sJxr+sk7faoFgBAgCQj6B1p28l4x0k6zsyeMrP18a2er2Nm15vZBjPb0NXVlYTSAADwtQclvS/efXONpAPOuddt2wQAYKqScUZvMttOchXrKHaeYv9a+YSZrXTO7f+zLx22LSUJtQEA4Bkzu1exP/uqzaxd0ucl5UmSc+7bkh6SdLGkJkmDkq72plIAQNAkI+hNZttJu6T1zrlRSc1m9rJiwe+5JDwfAAJvdHRU7e3tGh4e9rqUGSksLFRdXZ3y8vK8LiUtnHOXH+NzJ+lDaSoHAJBFkhH0npO0zMwaJe2SdJmkwztqPiDpckl3mFm1Yls5dyTh2QCQFdrb21VWVqaGhgaZTbSRwv+ccwqHw2pvb1djY6PX5QAAEGgzPqPnnBuTdJOkhyVtlXS/c26zmd1iZpfGL3tYUtjMtkh6TNInnHPhmT4bALLF8PCwqqqqMjbkSZKZqaqqKuNXJQEAyARJmaPnnHtIsXMG49/73LifO0k3x38AAKYhk0NeQhB+DQAAZIJkdN0EAAAAAPgIQQ8AMClmpquuuurQ67GxMdXU1OiSSy6RJG3btk1nn322CgoK9NWvftWrMgEAgJK0dRMAEHwlJSXatGmThoaGVFRUpEceeUS1ta+NTa2srNTXv/51PfDAAx5WCQAAJFb0AABTcNFFF+mXv/ylJOnee+/V5Ze/Nj1gzpw5OvPMM7NmdAIAAH7Gih4AZJj/9/PN2rK7N6n3XLGgXJ9/x4nHvO6yyy7TLbfcoksuuUQvvfSSrrnmGj3xxBNJrQUAAMwcK3oAgEk7+eST1dLSonvvvVcXX3yx1+UAAIAjYEUPADLMZFbeUunSSy/V3//93+vxxx9XOMxIVAAA/IigBwCYkmuuuUYVFRU66aST9Pjjj3tdDgAAmABBDwAwJXV1dfroRz/6uvf37t2rVatWqbe3V6FQSP/+7/+uLVu2qLy83IMqAQDIbgQ9AMCk9Pf3v+698847T+edd54kad68eWpvb09zVQAAYCI0YwEAAACAgCHoAQAAAEDAEPQAIEM457wuYcaC8GsAACATEPQAIAMUFhYqHA5ndFByzikcDquwsNDrUgAACDyasQBABqirq1N7e7u6urq8LmVGCgsLVVdX53UZAAAEHkEPwCFDIxF94icvqrIkX3/3tuM0uyTf65IQl5eXp8bGRq/LAAAAGYKgB0BSLORd+8PntH5HWGamB1/crU+8/XhdduYi5YTM6/IAAAAwBZzRA6Dh0Yiuu3ODntkR1r+95xQ99JE36vi5Zfo/P92k//2fT2t4NOJ1iQAAAJgCgh6Q5YZHI7p+3UY9tb1bX3nXKXrnaXU6fl6Z7rt+jb70Vyv1ws79enjzXq/LBAAAwBQQ9IAs9+3/2a7fv9KlL/+vk/WuM15rkmFmeu9Zi7SgolAP/HGXhxUCAABgqgh6QBY7MDiq7z3RrAtPnKf3nLnwdZ+HQqa1p9Xq9692q6vvoAcVAgAAYDoIekAWu/3JHeo7OKaPXbDsiNe887RaRaJOP39xdxorAwAAwEwQ9IAstW9gRN9/sll/efJ8LZ9XfsTrjptbphMXlOuBF9i+CQAAkCkIekCWuu2JHRocjehj5x95NS/hnafV6qX2A2rq7E9DZQAAAJgpgh6Qhbr7D+qHT7fo0lMWaNncsmNef+kpCxQy0ZQFAAAgQxD0gCx02+93aHg0oo9MYjVPkuaUF+rcZTX66R93KRp1Ka4OAAAAM0XQA7JM3/Co7lrfqktPWaAlNaWT/t47T1ugXfuHtKF1XwqrAwAAQDIQ9IAs87MXdmtwJKL3v6FhSt97+4nzVJSXo1+8RPdNAAAAvyPoAVnEOae7n23TivnlOnXhrCl9tzg/V6cunKUXd+5PUXUAAABIFoIekEVe2LlfW/f06r2rF8nMpvz9lbXl2rq3T6ORaAqqAwAAQLIQ9IAscs+zbSrOz9HaUxdM6/srays0MhbVqx2MWQAAAPAzgh6QJQ4MjernL+3W2lNrVVaYN617rKytkCRt2n0gmaUBAAAgyQh6QJZ44I+7NDwa1RWrF037Ho1VJSrJz9GmXQQ9AAAAPyPoAVkg1oSlVSfXVRxalZuOUMh04oIKgh4AAIDPEfSALPB82z690tE/o9W8hJW1Fdqyp1cRBqcDAAD4FkEPyAL/9fwuFeXl6JKTp9eEZbyVteUaHo1qexcNWQAAAPyKoAcE3MhYVA/9aY/+4sS5KinInfH9Tko0ZGH7JgAAgG8R9ICAe+LVLu0fHJ32SIXDLa4pVVFejv5E0AMAAPAtgh4QcD97YbdmF+fpjctqknK/nJBpxYJybd7Vm5T7AQAAIPkIekCADRwc0yNbOnTxSfOVl5O8/91XLijX5t0HFKUhCwAAgC8R9IAAe3Rrh4ZGI1p7am1S77uytkIDIxE1hweSel8AAAAkB0EPCLCfvbBbCyoKtap+dlLvu5KGLAAAAL5G0AMCqmdgRL9/pUvvOHWBQiFL6r2XzSlVQW6IoAcAAOBTBD0goB760x6NRZ3WnpLcbZuSlJsT0vL55dpEQxYAAABfIugBAfXgC7u1bE6pTphflpL7n1Rbrk27D8g5GrIAAAD4DUEPCKBw/0E919qji0+aL7PkbttMWDG/Qn3DY2rfN5SS+wMAAGD6CHpAAP1uW6ecky5YMTdlz1hcUyJJaqHzJgAAgO8Q9IAAenRrh+ZXFOrEBeUpe0ZDVTzodRP0AAAA/IagBwTM8GhET7zarfNPmJOybZuSNLe8QEV5OWruHkzZMwAAADA9BD0gYJ7ZEdbgSERvOyF12zYlycxUX1XM1k0AAAAfIugBAfPolg6V5Ofo7CVVKX9WY3UJWzcBAAB8iKAHBIhzTo9u7dAbl9WoIDcn5c9rqC5RW8+gxiLRlD8LAAAAk0fQAwJk065edfQe1NtS2G1zvMaqEo1FnXbtZ8QCAACAnxD0gAB5dGuHQia95fiatDyvoToxYoGGLAAAAH5C0AMC5NGtHTqjfraqSgvS8ryG6mJJjFgAAADwG4IeEBC79w9p8+5enZ/ibpvj1ZQWqCQ/R80EPQAAAF8h6AEB8fjLXZKk85fPSdszYyMWShixAAAA4DMEPSAgnt7erbnlBVo6pzStz2XEAgAAgP8Q9IAAcM5p/Y4enb24SmaW1mc3VBdr574hjTJiAQAAwDcIekAANHX2q7v/YFqGpB+uoapEkahT+z5GLAAAAPgFQQ8IgGd2hCVJZy+uTvuzGxMjFti+CQAA4BsEPSAAntkeVu2sIi2sLEr7sxOz9Oi8CQAA4B8EPSDDRaNOz+wI6+wl6T+fJ0lVJfkqK8il8yYAAICPEPSADLdtb5/2D47q7MXpP58nxUYsNFSXsKIHAADgIwQ9IMMdOp/nQSOWhIZqZukBAAD4CUEPyHDPbA+rvqpYC2al/3xeQmNVsXbtG9LIGCMWAAAA/ICgB2SwSNTp2eaw3uDhap4k1VeVKOqktp5BT+sAAABADEEPyGCbdx9Q3/CY1nh0Pi+hgRELAAAAvkLQAzLYM9sT8/O8DXqHZulxTg8AAMAXCHpABntmR1hLako0p7zQ0zpmF+epvJARCwAAAH5B0AMyVDTqtLF1n85q9HY1T4qNWFhUVaz2fUNelwIAAAAR9ICMtaN7QH3DYzpt0SyvS5Ek1c0q1k6asQAAAPgCQQ/IUC/u3C9JOnWhT4Le7CK17xuSc87rUgAAALIeQQ/IUC/s3K/SglwtqSn1uhRJ0sLKYh0ci6q7f8TrUgAAALIeQQ/IUC+279dJtRXKCZnXpUiKrehJ0s59bN8EAADwGkEPyEDDoxFt3dOrU3yybVOS6mYXSxINWQAAAHyAoAdkoC17ejUacb45nye9tqLXzooeAACA5wh6QAbyWyMWSSopyFVlSb529rCiBwAA4DWCHpCBXti5X/PKCzWvwttB6YeLdd5kRQ8AAMBrBD0gA724c79OWVjhdRmvUze7SLs4owcAAOA5gh6QYfYNjKglPKhTF872upTXWTi7WO37hxSNMksPAADASwQ9IMO82B47n+fXFb2Rsai6+g96XQoAAEBWI+gBGebFnQdkJp1U68eglxixwDk9AAAALxH0gAzzws59WjanVGWFeV6X8joLKxMjFjinBwAA4CWCHpBBnHN6sf2ATqnzz1iF8WpnxVb0dvawogcAAOAlgh6QQXb2DKlnYESnLvJn0CvKz1F1aT4regAAAB4j6AEZ5FAjFp+u6Emxc3oEPQAAAG8R9IAMsnVPr3JDpmVzS70u5YjqZhdpJ81YAAAAPEXQAzLItr19WlJTqoLcHK9LOaK62cXavX9IEWbpAQAAeIagB2SQbXt6dcL8Mq/LOKqFlUUajTh19g17XQoAAEDWIugBGWL/4Ih2HxjW8vnlXpdyVK/N0uOcHgAAgFcIekCG2La3T5K0fJ6/V/TqZsdm6TFiAQAAwDtJCXpmdqGZvWxmTWb2qaNc9y4zc2a2KhnPBbLJtj29kqQVPl/Rq53F0HQAAACvzTjomVmOpFslXSRphaTLzWzFBNeVSfqIpGdn+kwgG23b26fKknzVlBV4XcpRFeblaE5ZgdrpvAkAAOCZZKzonSWpyTm3wzk3Iuk+SWsnuO6Lkv5VEh0agGnYuqdXy+eVycy8LuWY6mYXaWcPK3oAAABeSUbQq5W0c9zr9vh7h5jZaZIWOud+cbQbmdn1ZrbBzDZ0dXUloTQgGCJRp5c7+nSCz7dtJiysLFb7flb0AAAAvJKMoDfR8sKhAVpmFpL0NUkfP9aNnHO3OedWOedW1dTUJKE0IBhawwMaHo36vhFLQt3sIu3ZP6yxSNTrUgAAALJSMoJeu6SF417XSdo97nWZpJWSHjezFklrJD1IQxZg8rbuiXXczJQVvbrZxRqLOu3tZac2cKyGZWa2yMweM7M/mtlLZnaxF3UCAIIlGUHvOUnLzKzRzPIlXSbpwcSHzrkDzrlq51yDc65B0npJlzrnNiTh2UBW2La3Vzkh09I5pV6XMimJEQt03kS2m2TDss9Kut85d5pif4Z+K71VAgCCaMZBzzk3JukmSQ9L2qrYH1abzewWM7t0pvcHEFvRW1xdosK8HK9LmZSFDE0HEibTsMxJSizXV+jPd8UAADAtucm4iXPuIUkPHfbe545w7XnJeCaQTbbt7dVpi2Z7XcakzZ9VKDMxYgGYuGHZ6sOu+YKk35jZhyWVSHrbRDcys+slXS9JixYtSnqhAIBgScrAdACp0zs8qvZ9QzphfmY0YpGkgtwczS0rZEUPOEbDsrjLJd3hnKuTdLGkdfFGZn/+JRqWAQCmgKAH+NzLe+ONWOZlRiOWhLrZRazoAcduWCZJ10q6X5Kcc89IKpRUnZbqAACBRdADfG7bnl5J0vIMWtGTEkGPFT1kvaM2LItrk3S+JJnZCYoFPYbJAgBmhKAH+NyWPX2qKMrTvPJCr0uZkrrZxdpzgFl6yG6TbFj2cUnXmdmLku6V9AHn3OHbOwEAmJKkNGMBkDrb9vbqhPllMpvoqI9/LawsUiTqtOfAsBZWFntdDuCZYzUsc85tkXROuusCAAQbK3qAjznn1NTRr+PmZta2TSm2oicxYgEAAMALBD3Axzr7Dqrv4FjGDEof77Wh6TRkAQAASDeCHuBjTZ39kqSlNZkX9OZXFMVn6bGiBwAAkG4EPcDHDgW9DFzRy88NaV45s/QAAAC8QNADfGx7V7/KCnJVU1bgdSnTsnB2MVs3AQAAPEDQA3ysqbNfS+aUZlzHzQRm6QEAAHiDoAf4WFNnf0Zu20yom12kPQeGNMosPQAAgLQi6AE+1Ts8qs6+gxke9IoVddLeA8NelwIAAJBVCHqAT22PN2JZkoEdNxMSIxZ2ck4PAAAgrQh6gE9lcsfNhIWVDE0HAADwAkEP8Kmmrn7l54S0ML4qlonmVRQqxCw9AACAtCPoAT61vbNfjdUlys3J3P9N83JCml9RpPYetm4CAACkU+b+DRIIuNhohRKvy5ixWkYsAAAApB1BD/Chg2MRtfUMamkGN2JJiM3SY0UPAAAgnQh6gA+1dA8q6qQlGdyIJaFudrH29g5rZIxZegAAAOlC0AN8KAgdNxMWzi5ilh4AAECaEfQAH2rq7JeZtLg684Ne3ezEiAW2bwIAAKQLQQ/woe1d/aqdVaSi/ByvS5mxxNB0GrIAAACkD0EP8KGmzv5AbNuUpPkVhcoJmXayogcAAJA2BD3AZ6JRpx3d/YHouClJuTkhza8oVBuz9AAAANKGoAf4zK79QxoejQZmRU+S6quK1Rom6AEAAKQLQQ/wmaauWMfNIIxWSFhUWcKKHgAAQBoR9ACfae4akCQtri7xuJLkqa8qVs/AiPqGR70uBQAAICsQ9ACfae4eUHlhripL8r0uJWnqK2MjFti+CQAAkB4EPcBnWsIDaqwukZl5XUrS1FfFVicJegAAAOlB0AN8prl7QA0B2rYpSYuq4it6PQMeVwIAAJAdCHqAjwyPRrRr/5AaqoIV9EoLclVdmq82VvQAAADSgqAH+MjOnkE5Jy2uCVbQk6RFlYxYAAAASBeCHuAjzd2xrY1BW9GTYuf0GLEAAACQHgQ9wEcOBb2AndGTYit6uw8M6eBYxOtSAAAAAo+gB/hIS3hAVSX5qijK87qUpKuvKpZz0s6eIa9LAQAACDyCHuAjQey4mVAf77zZRudNAACAlCPoAT7S0j0YyPN5ErP0AAAA0omgB/jE4MiY9vYOq7G62OtSUqKqJF8l+TkEPQAAgDQg6AE+0dIdC0CN1aUeV5IaZqZFdN4EAABIC4Ie4BMt4UTHzWCu6ElSfWWxWsOc0QMAAEg1gh7gE0GeoZdQX1WsnT1DikSd16UAAAAEGkEP8Inm7gHNLS9QSUGu16WkzKKqYo1EotrbO+x1KQAAAIFG0AN8oqV7INCreZJUX5novMn2TQAAgFQi6AE+0dw9oMaAztBLODRLj86bAAAAKUXQA3ygd3hU4YGRwA5LT5hfUai8HFMrnTcBAABSiqAH+EBLvBFL0Ff0cnNCqptdzIoeAABAihH0AB9ozpKgJ0mLKovV2sMZPQAAgFQi6AE+0Nw9ILNYCAq6+qpitXYPyjlGLAAAAKQKQQ/wgZbuAS2oKFJhXo7XpaRcfVWJ+g6OqWdgxOtSAAAAAougB/hAc3gwK7ZtStKSmtivs6mz3+NKAAAAgougB/hAa3jg0OiBoFs6p1SS1NRF0AMAAEgVgh7gsQODo9o/OJo1QW9BRZGK8nJY0QMAAEghgh7gsUQHyvqq7Ni6GQqZlswpIegBAACkEEEP8FhrfKZctqzoSdLSmlJtJ+gBAACkDEEP8FhrOLailw2jFRKWzinV7gPDGjg45nUpAAAAgUTQAzzWGh7UnLICFefnel1K2iQasmynIQsAAEBKEPQAj7X2DGbVtk1pXOdNtm8CAACkBEEP8FhstEJ2NGJJqK8qUW7ICHoAAAApQtDq6k7sAAAgAElEQVQDPDQ8GlFH70HVZ9H5PEnKywmpobpErxL0AAAAUoKgB3iorSfWcXNRlm3dlOi8CQAAkEoEPcBDLd2xjpsNWbZ1U4qd02vtGdTIWNTrUgAAAAKHoAd4KLGil23NWKRY0ItEnVri4yUAAACQPAQ9wEOt4UGVF+ZqVnG+16WkHZ03AQAAUoegB3ioJTyghurs27YpSYtrYr9ugh4AAEDyEfQAD7X1DGpRlnXcTCjOz1XtrCKCHgAAQAoQ9ACPjEaiat83lJWNWBKWzS0l6AEAAKQAQQ/wyO79Q4pEXVaOVkhYWlOq7V39ikSd16UAAAAECkEP8EhrON5xM0u3bkqxhiwHx6LatW/I61IAAAAChaAHeKQ1PlYgW5uxSOM6b3b1eVwJAABAsBD0AI+0hgdVmBfSnLICr0vxDCMWAAAAUoOgB3ikNd5x08y8LsUzs4rzVVNWoG17WdEDAABIJoIe4JHW8IDqs7jjZsLKBeXasrvX6zIAAAAChaAHeMA5p7aewaxuxJKwsrZCr3b2a3g04nUpAAAAgUHQAzzQ2XdQw6NR1WdxI5aEExdUKBJ12rqHVT0AAIBkIegBHmjpjnXcZEVPOqmuQpK0ie2bAAAASUPQAzzQ2hOfoZfFw9ITFlQUanZxnjbvOuB1KQAAAIFB0AM80BYeVE7ItGBWkdeleM7MtLK2Qn8i6AEAACQNQQ/wQFvPoBbMKlReDv8LSrGGLK909OngGA1ZAAAAkoG/ZQIeaO0ZVH0ljVgSVi6o0GjE6dUOBqcDAAAkA0EP8EBbeECLOJ93yMrackli+yYAAECSEPSANOsdHtW+wVEtouPmIYsqi1VWmKtNBD0AAICkIOgBadYWjnfcJOgdYmZauaCCEQsAAABJQtAD0qwtPlqBrZt/bmVtubbu6dVoJOp1KQAAABmPoAek2aGgx4ren1lZW6GRsaiaOmnIAgAAMFMEPSDNWsODqizJV1lhntel+MrK2gpJ4pweAABAEhD0gDRr6xlgNW8CjVUlKsnPIegBAAAkAUEPSLO2nkGC3gRCIdOKBeU0ZAEAAEgCgh6QRqORqHbvH1Y9jVgmtLK2Qlt29yoSdV6XAgAAkNEIekAa7do3pEjUaSErehM6deEsDY1GtHUPq3oAAAAzQdAD0ijRcZMZehNb3VglSVq/I+xxJQAAAJmNoAekUWsi6FWVeFyJP82rKFR9VbHW7+jxuhQAAICMRtAD0qgtPKD83JDmlBV4XYpvrWms0nMtPYpyTg8AAGDakhL0zOxCM3vZzJrM7FMTfH6zmW0xs5fM7LdmVp+M5wKZJtFxMxQyr0vxrdWLK3VgaFTb9vZ5XQoAAEDGmnHQM7McSbdKukjSCkmXm9mKwy77o6RVzrmTJf1E0r/O9LlAJmoND3I+7xhWL+acHgAAwEwlY0XvLElNzrkdzrkRSfdJWjv+AufcY865wfjL9ZLqkvBcIKM459TWM0jHzWOonVWkhZVFeraZoAcAADBdyQh6tZJ2jnvdHn/vSK6V9KuJPjCz681sg5lt6OrqSkJpgH+EB0Y0OBJhht4krGms0rPNnNMDAACYrmQEvYkOG034tzMzu1LSKklfmehz59xtzrlVzrlVNTU1SSgN8I/WcKLjJkHvWFYvrtL+wVG90sk5PQAAgOlIRtBrl7Rw3Os6SbsPv8jM3ibp/0i61Dl3MAnPBTJKW8+AJGkRWzePaXVjpSTpWcYsAAAATEsygt5zkpaZWaOZ5Uu6TNKD4y8ws9MkfUexkNeZhGcCGactPCQzqW42Qe9YFlYWq3ZWEQ1ZAAAApmnGQc85NybpJkkPS9oq6X7n3GYzu8XMLo1f9hVJpZJ+bGYvmNmDR7gdEFitPQOaV16owrwcr0vJCGsWx87pOcc5PQAAgKnKTcZNnHMPSXrosPc+N+7nb0vGc4BM1ham4+ZUrF5cqf96vl2vdvbruLllXpcDAACQUZIyMB3AsbX2MENvKtY0Mk8PAABgugh6QBoMjoypq+8gHTenYGFlbJ7e4y8zagUAAGCqCHpAGrT1xEYrLKoq8biSzGFm+osV8/Tkq93qPzjmdTkAAAAZhaAHpEFbYoYeWzen5O0nztNIJKrHX6ZZLzKXmV1oZi+bWZOZfeoI17zHzLaY2WYzuyfdNQIAgoegB6RBYkWPrZtTc0b9bFWX5uvXm/Z6XQowLWaWI+lWSRdJWiHpcjNbcdg1yyR9WtI5zrkTJX0s7YUCAAKHoAekQWt4UGWFuaooyvO6lIySEzJdsGKuHtvWqeHRiNflANNxlqQm59wO59yIpPskrT3smusk3eqc2ydJzJsFACQDQQ9Ig9aeQdVXFcvMvC4l4/zFifM0MBLR09u7vS4FmI5aSTvHvW6PvzfecZKOM7OnzGy9mV040Y3M7Hoz22BmG7q6aFIEADg6gh6QBm3hAdVX0ohlOt6wpEplBbl6eFOH16UA0zHRv+64w17nSlom6TxJl0u63cxmve5Lzt3mnFvlnFtVU1OT9EIBAMFC0ANSbCwSVfu+IS3ifN60FOTm6C3L5+iRrR0ai0S9LgeYqnZJC8e9rpO0e4JrfuacG3XONUt6WbHgBwDAtBH0gBTbc2BYY1FHx80ZuHDlPPUMjGhD6z6vSwGm6jlJy8ys0czyJV0m6cHDrnlA0lskycyqFdvKuSOtVQIAAoegB6RYazgxQ4+gN11vPq5G+bkhPbyZ7pvILM65MUk3SXpY0lZJ9zvnNpvZLWZ2afyyhyWFzWyLpMckfcI5F/amYgBAUOR6XQAQdK+NVuCM3nSVFOTqTcuq9fCmvfrcJStoaoOM4px7SNJDh733uXE/d5Jujv8AACApWNEDUqy1Z0D5OSHNKy/0upSM9pcnz9fuA8N6ZjsLHQAAAMdC0ANSrC08qLrKIuWEWIWaiYtWztfs4jytW9/qdSkAAAC+R9ADUqw1PEgjliQozMvRu1ct1G+2dKijd9jrcgAAAHyNoAekkHNObT2DnM9LkitWL1Ik6nTfH3Ye+2IAAIAsRtADUqhnYET9B8e0iBW9pKivKtGbjqvRvX9oY6YeAADAURD0gBRqjXfcJOglz5WrF2lv77Ae3drpdSkAAAC+RdADUqgtnBitQNBLlrcun6MFFYW6+1masgAAABwJQQ9IocSw9IWs6CVNbk5Il5+1SE+82q3m7gGvywEAAPAlgh6QQm09g5pXXqjCvByvSwmUvz5roXJDpu8/2ex1KQAAAL5E0ANSqK1nQIvYtpl0c8oK9Z4zF+q+59q0M34OEgAAAK8h6AEpxAy91Pno+csUMtPXHnnF61IAAAB8h6AHpMjQSESdfQdpxJIic8sL9YFzGvTTF3Zp295er8sBAADwFYIekCJtidEKDEtPmb958xKVFuTqqw+zqgcAADAeQQ9IkdZwrCMkWzdTZ1Zxvm588xI9urVDG1t7vC4HAADANwh6QIokVvQaWNFLqavPaVB1aYG+/KuX5ZzzuhwAAABfIOgBKdISHtCs4jxVFOd5XUqgFefn6u8uWKY/tPToxxvavS4HAADAFwh6QIq0hgdVz2peWlx+5iKtbqzUF3+xRbv2D3ldDgAAgOcIekCKtIQH1EDHzbQIhUxfedcpijinT/3XS2zhBAAAWY+gB6TAyFhUu/YNsaKXRouqivWZi0/QE6926+5n27wuBwAAwFMEPSAF2vcNKurEil6aXbF6kc5dWq1/emir2sKDXpcDAADgGYIekAKt8ZDBsPT0MjN9+V0nK8dMf3P3Rg2OjHldEgAAgCcIekAKtCRm6LF1M+1qZxXp65efpq17enXzj15UNMp5PQAAkH0IekAKtIYHVVqQq6qSfK9LyUpvWT5Hn7n4BP168179f4+84nU5AAAAaZfrdQFAELWEB1RfVSwz87qUrHXtuY1q6uzXNx9r0rK5pVp7aq3XJQEAAKQNK3pACrSGB9XAtk1PmZluWbtSqxsr9Ykfv6THtnV6XRIAAEDaEPSAJBuLRLWzZ5BGLD6QnxvSbVet0nHzSnXDuo167GXCHgAAyA4EPSDJ9hwY1ljUsaLnExXFebrr2tWxsHcnYQ8AAGQHgh6QZK913GRFzy9mFef/Wdh7dEuH1yUBAACkFEEPSLKW+Ay9hmpW9PwkEfaWzy/T9es2aN36Vq9LAgAASBmCHpBkrd0DKswLaU5Zgdel4DCzivN13/Vr9Jbj5+j/PrBJ//yrrczZAwAAgUTQA5KsJd5xk9EK/lScn6vvXHWGrlyzSN/5nx36yH1/1PBoxOuyAAAAkoo5ekCStYYHtLiGbZt+lpsT0hfXrlTd7GJ9+dfb1BIe0HeuWqXaWUVelwYAAJAUrOgBSRSNOrX2DKqejpu+Z2a68c1LdPv7Vqm1e1CXfuNJPbsj7HVZAAAASUHQA5Job++wRsaidNzMIOefMFc//dA5qijO0xW3P6s7nmqWc5zbAwAAmY2gByRRYrQCM/Qyy9I5pXrgQ+fovONr9IWfb9FH73tBAwfHvC4LAABg2gh6QBK1xkcrsKKXecoL83TbVav0ibcfr1+8tFt/detTaurs97osAACAaSHoAUnUEh5Qfk5I8yto6pGJQiHTh96yVOuuXa2egRGt/eaTeuhPe7wuCwAAYMoIekAStXYPamFlkXJCjFbIZOcsrdYvPnKujptXpr+9+3l96RdbNBqJel0WAADApBH0gCRqCQ/QcTMg5lcU6UfXn60PvKFBtz/ZrPd+d706eoe9LgsAAGBSCHpAkkSjTi3hATVWE/SCIj83pC9ceqL+47JTtWlXry75xpPa0NLjdVkAAADHRNADkqSjb1jDo1GCXgCtPbVWD3zoHJXk5+iy29Zr3TMtjGAAAAC+RtADkqS5KzZaYTFBL5COn1emn910rt64rFr/92eb9Q8/eUkHxyJelwUAADAhgh6QJDu6Y0GvsYagF1QVRXn63vvP1EfOX6Yfb2zX5betV2cf5/YAAID/EPSAJGnpHlBhXkhzywq9LgUpFAqZbr7gOH3ritO1ZU+v1n7zKW3adcDrsgAAAP4MQQ9IkubuATVUlSjEaIWscPFJ8/WTG98gk/Subz+tX29i3h4AAPAPgh6QJM3dA1rMts2ssrK2Qj+76VydML9cf3P387r9iR00aQEAAL5A0AOSYCwSVVvPoBqYoZd1asoKdO91a3ThifP0pV9u1ed+tlljDFcHAAAeI+gBSdC+b0hjUcdohSxVmJejW997um5402KtW9+qG9Zt1ODImNdlAQCALEbQA5KgOd5xk62b2SsUMn364hP0xb9aqcde7tQVtz+rfQMjXpcFAACyFEEPSIJE0GPrJq5aU69vXXG6Nu/u1bu/84x27x/yuiQAAJCFCHpAEjR3D6i8MFeVJflelwIfuHDlfN15zVnqODCs//2fT6ups8/rkgAAQJYh6AFJ0Nw9oMaaUpkxWgExaxZX6Uc3nK2xqNN7vrOeWXsAACCtCHpAEjR3D2gxjVhwmBULyvXjG85WUV6OLv/uem1s7fG6JAAAkCUIesAMDY9GtPvAEOfzMKGG6hLdf+PZqi4t0JW3/0FPvtrtdUkAACALEPSAGWoND8o5qZGOmziC2llF+tENa7SosljX/PA5Pf5yp9clAQCAgCPoATPU3N0vSWzdxFHNKSvUfdev0dKaUl1/50Y9to2wBwAAUoegB8xQc/egpNgWPeBoZpfk657rVuu4eaW6Yd1G/XZrh9clAQCAgCLoATPU3N2vmrIClRbkel0KMsCs4nzdfe0aLZ9fphvv2qhHtxD2AABA8hH0gBlq7h5QI6t5mIKK4jytu3a1Vswv19/e/bwe48weAABIMoIeMEPN3YNqpOMmpqiiKE93XvPaNs7fv9LldUkAACBACHrADPQOj6q7/yAdNzEtFcV5WnfNai2pKdV1d27Q002MXgAAAMlB0ANmoKV7QJLYuolpm12Sr7uuPUv1VcW69ocb9FwLQ9UBAMDMEfSAGWgm6CEJqkoLdPcH12h+RaGu/sFzeql9v9clAQCADEfQA2agqbNfOSFTfVWx16Ugw9WUFeju61ZrVnGe3vf9P2jb3l6vSwIAABmMoAfMwPaufi2qLFZBbo7XpSAA5lcU6Z4PrlFhbo6uvP0P2tHV73VJAAAgQxH0gBnY3jmgJTRiQRItqirWXR9cLcnpytuf1a79Q16XBAAAMhBBD5imSNSpuXtAS+aUel0KAmbpnFLdec1q9R8c0xXfXa/OvmGvSwIAABmGoAdMU/u+QY1EolpSQ9BD8q1YUK4fXH2WOvsO6n3f+4P2D454XRIAAMggBD1gmrbHz08R9JAqZ9TP1nfft0o7ugb0gR88p/6DY16XBAAAMgRBD5imps5E0OOMHlLnnKXVuvWK0/WnXQd0/Z0bNDwa8bokAACQAQh6wDRt7xxQdWm+ZhXne10KAu6CFXP11XefrKe3h3XTPX/UaCTqdUkAAMDnCHrANG3v6tditm0iTd55Wp1uWXuiHt3aoU/8+EVFo87rkgAAgI/lel0AkKm2d/XrwpXzvS4DWeR9Zzeob3hMX3n4ZZUW5uqLa1fKzLwuCwAA+BBBD5iGnoER7Rsc5Xwe0u5vz1ui3qFRfef3O1RakKdPXbTc65IAAIAPEfSAaTjUcZMZekgzM9OnLlqu/oNj+vb/bFdZYa4+9JalXpcFAAB8hqAHTEOi4+ZSzujBA2amL65dqYGD8W2cBbl6/xsavC4LAAD4CEEPmIbtnf0qyA1pwawir0tBlgqFTF959ykaGIno8w9uVlFejt5z5kKvywIAAD5B101gGrZ39auxukQ5IRphwDt5OSF9872n6Y3LqvXJ/35JP3thl9clAQAAnyDoAdOwvWtASzmfBx8oyM3RbVet0urGSt18/4v69aY9XpcEAAB8gKAHTNHwaEQ79w1qCefz4BNF+Tm6/f1n6pS6Cn343j/qd9s6vC4JAAB4LClBz8wuNLOXzazJzD41wecFZvaj+OfPmllDMp4LeKElPCDn6LgJfyktyNUPrj5LJ8wv143rntdj2zq9LgkAAHhoxkHPzHIk3SrpIkkrJF1uZisOu+xaSfucc0slfU3Sl2f6XMAr2zsHJIkZevCdiqI8rbtmtY6fV6Yb1m0k7AEAkMWSsaJ3lqQm59wO59yIpPskrT3smrWSfhj/+U8knW9mdLFARkqMVlhczYoe/KeiOE93Xbtax80rjYW9l1MX9pxz+kNzj4ZGIil7BgAAmJ5kBL1aSTvHvW6PvzfhNc65MUkHJFUdfiMzu97MNpjZhq6uriSUBiTf9q5+1c4qUlF+jtelABNKhL1lc0t1w50b9ciW1JzZa+4e0Hu+8wzdPgEA8KFkBL2JVubcNK6Rc+4259wq59yqmpqaJJQGJF9TZz/n8+B7s4rzdc8H1+iEBeW68a6NevDF3Ul/xobWfZKkVQ2zk35vAAAwM8kIeu2Sxk/prZN0+N8oDl1jZrmSKiT1JOHZQFpFok7bu/p1HEEPGSC2sneWzqifrY/e90fd/9zOY39pCp5v3aeKojy2MQMA4EPJCHrPSVpmZo1mli/pMkkPHnbNg5LeH//5uyT9zjn3uhU9wO/aegZ1cCyq4+aWeV0KMCllhXn64dVn6dyl1fqH/3pJtz+xI2n33tC6T2fUz1YoxJFrAAD8ZsZBL37m7iZJD0vaKul+59xmM7vFzC6NX/Y9SVVm1iTpZkmvG8EAZIJXOvokScvmsoKBzBGbs7dKF580T1/65Vbd8vMtikZn9m9t+wdH1NTZrzPq2bYJAIAf5SbjJs65hyQ9dNh7nxv382FJ707GswAvvbI3EfRY0UNmKcjN0TcuP11zyrbo+081q6NvWP/27lNUmDe9pkLPt8XO5xH0AADwp6QEPSBbvNIZ67hZWsD/Osg8OSHT59+xQvMrCvXPv9qmrt6D+taVp6u6tGDK99rQsk+5IdMpdbNSUCkAAJipZJzRA7LGqx19Oo5tm8hgZqYb3rxE/3HZqXqhfb/WfvMpbdp1YMr32di6TycuKGfMCAAAPkXQAyZpLBLVjq4BGrEgENaeWquf3Hi2os7pXd9+ekqz8EYjUb3Yvl9n1FemsEIAADATBD1gklrCgxqJ0HETwXFy3Sw9eNO5Oqm2Qh+97wV99oE/aWgkcszvbd7dq+HRKOfzAADwsawJeh29w3rs5U6vy0AGS3TcJOghSGrKCnT3B9fog+c26q71bbrkG08ccyvnRgalAwDge1kT9O55tk1X/+A57T0w7HUpyFCvdPTJTFrKsHQETH5uSJ+9ZIXuuna1+g+O6Z3fekrf/N2rOjg28erextYe1c4q0tzywjRXCgAAJitrgt5w/C8sj2zZ63ElyFSvdvRr4eximk8gsM5dVq2HP/Ym/cWKefrqb17Rhf/+xOt2QjjntLF1H6t5AAD4XNYEvbFIbDjww5s7PK4EmeqVjj62bSLwZhXn69YrTtcPrj5TJunqHzyna+94Tpt3x7Zztu8bUkfvQc7nAQDgc1kzDCwSjQW99TvCOjA4qoriPI8rQiYZGYuquXtAF6yY63UpQFq85fg5OmdJte54ullf/22T/vLrT+qcpVVaNif2jx0EPQAA/C1rVvRGI1FJ0ljU6bfbWNXD1DR3D2gs6ljRQ1bJzw3p+jct0VOffKs+eeFyNXX2646nW1SSn6Pl88q9Lg8AABxFVq3ozSkrkJn08Oa9+l+n13ldEjJIouPmMoalIwtVFOfpb85bomvPbdRDf9qjwryQckLmdVkZw8wulPQfknIk3e6c+5cjXPcuST+WdKZzbkMaSwQABFDWBL3RiFNeTkhvXT5HP964U0MjEZpqYNJe7ehTyKQlNQQ9ZK/83JD+6rRar8vIKGaWI+lWSRdIapf0nJk96Jzbcth1ZZI+IunZ9FcJAAiirNm6GYlGlZtjunDlPA2PRvU/r3R5XRIyyCsd/WqoKlFhHv84AGBKzpLU5Jzb4ZwbkXSfpLUTXPdFSf8qiRlAAICkyJqgNxZ1ygmZzmqsVEVRnn6zmTELmLxXOvvYtglgOmol7Rz3uj3+3iFmdpqkhc65XxztRmZ2vZltMLMNXV38YyUA4OiyJ+hFnPJCIeXlhHT+CXP06NaOQw1agKMZHo2oNTxIIxYA0zHRYUZ36EOzkKSvSfr4sW7knPv/27vz6Ljq++7jn++MFi/ybsmS5UXe8G5jI8y+QzCbgTyEEEIDeQi05JDTk7Q9TZ+kffqkJ+dkaZuetkkbkiaQNAsQmuAECGHfMbYBb9jGC15ky5Y3ycK2rJl7f88fM2MUW7Y10szcmXvfr3N8PKO5nvudn5frj36/+/s+4JxrdM41VldX57BEAEAYRSfopWf0JOnqmbU62JHUks37A64KpWDznkPy2HETQO80SRrb5fkYSTu7PB8kaZakF81si6RzJS02s8aCVQgACKUIBT1f5fFU0Lt4SrX6l8f1+zXNAVeFUrB+90FJ0tRagh6ArC2VNMXMJphZhaTbJC3OvOica3POjXTONTjnGiS9KWkRu24CAPoqMkHP6zKj178irkunVusPa3bL991pfiWibm1zuyrKYpo4cmDQpQAoMc65pKT7JT0taa2kR5xza8zsa2a2KNjqAABhFqH2Cr7K4h/l2oWzavXU6l16Z3urzho/LMDKUOzWNh/UGaOq/ujPDwD0lHPuSUlPHve1vzvJsZcWoiYAQPhF5n+unu9U1qXB72XTalQeNz3N7ps4jbXNBzW9dnDQZQAAAAA9Fpmgl/DcH83IDO5Xrgsmj9TvV++ScyzfRPda2ju098NOTa8j6AEAAKB0RCboHT+jJ0kLZ9Zq2/7DWtvcHlBVKHbv7UxtxELQAwAAQCmJTNBLeP6xzVgyrpwxSjGTfs/yTZxE5psAMwh6AAAAKCGRCXqe7461V8gYWVWpsxuG6+nVBD10b23zQdUP7a8hA8qDLgUAAADosUgFvXjsxI+7cFat1u9u1+Y9HwZQFYrd2uaDml5H/zwAAACUlsgEvYTvq/y4pZuSdPXMWknS02t2F7okFLmOhKfNew9xfx4AAABKTmSCnue5E+7Rk6TRQ/tr7pgh3KeHE2zY/aE83xH0AAAAUHIiE/QSvjtpw+urZ9VqxfZWNbcdKXBVKGZrm9lxEwAAAKUpMkGvu/YKGQvTyzd/z6Ys6OK95oMaUBHX+OEDgi4FAAAAyEpkgl7C81UW7z7oTayu0tRRg/TUKoIePvJe80FNrR2k2Em+QQAAAAAUq8gEvVPN6Emp3TeXbt2vlvaOAlaFYuWc09rmg/TPAwAAQEmKTNBLeie/R0+SrpldK+ekP7D7JiTtaD2i9o4k9+cBAACgJEUn6Pn+KWf0po4apAkjB3KfHiRJa5vbJbERCwAAAEpTJIKe7zv5Tt22V8gwMy2cVas3Nu/TgUOdBawOxWht80GZSdNqaZYOAACA0hOJoJf0nSSp/BRLNyXpmlm18nynZ9ayfDPq1jYf1PjhAzSwsizoUgAAAICsRSLoeemgd6oZPUmaXT9E9UP7s3wTWr2zTTNGs2wTAAAApSkSQS/h+5J0ynv0pI+Wb766Ya/aOxKFKA1F6MChTm3ff0RzxgwNuhQAAACgVyIR9DwvNaN3uqAnpZZvdnq+nl/Xku+yUKRW7WiTJM2pHxJwJQAAAEDvRCLoHZvRO809epI0f9wwjRpcqSdXNee7LBSpTNCbSdADAABAiYpE0Mvco9eTGb1YzHTNrDq9uH6PDh1N5rs0FKGVTa2aMHKghvQvD7oUAAAAoFciEfSSmaWbPZjRk1LLN48mWb4ZVaua2jSb2TwAAACUsGgEvSxm9CSpsWG4qgexfDOK9rQf1c62Ds0ZQ9ADAABA6YpG0PMy9+j1LOjFY6aFM2v1wvoWHe5k+WaUrE7fn8eMHgAAAEpZNIJeljN6knTt7Dp1JHy9sG5PvspCEVrZ1CYzNmIBAABAaYtG0PMyDdN7/nEXTKRvmHcAACAASURBVBiukVUVenI1yzejZNWOVk2qrlJVZVnQpQAAAAC9Fo2g52e3dFNKLd+8ematnl/boiOdXr5KQ5FZ2dRG/zwAAACUvEgEvWzaK3R13ew6HUl4eul9dt+Mgt0HO9TSflSz2YgFAAAAJS4SQS+Raa+QxdJNKbV8c/jACj2xalc+ykKRWdnERiwAAAAIh0gEvWMzelks3UwdH9PVM2v13Nrd6kiwfDPsVjW1KmbSjNGDgy4FAAAA6JNIBL1E5h69LJduStL1c+p0uNPTi+tZvhl2K3e0aUrNIA2oYCMWAAAAlLZIBD2vl0s3JemcCcM1YmCFfruS3TfDzDmnVU1t3J8HAACAUIhE0OvNrpsZZfGYrpmd2n2T5unhtbOtQ/sOdWoOQQ8AAAAhEJGg17tdNzOumz1aRxIezdNDbMX2VklsxAIAAIBwiEbQyyzdjPfu4y6YMFzVgyr1u5U7c1kWisjyrQdUWRbTzNEEPQAAAJS+aAS9Ps7oxWOma2fV6vl1LTp0lOWbYbR86wHNHTNUFWWR+CsBAACAkIvE/2qTXuoevXgvg54kXTdntI4mfT27dneuykKR6Eh4WrOzTfPHDwu6FAAAACAnohH0etlHr6vG8cM0anClnmD3zdBZtaNNCc/pLIIeAAAAQiISQe9Yw/RetFfIiMVM186u04vv71F7RyJXpaEILN96QJI0f9zQgCsBAAAAciMSQS/h9b69QlfXzxmtTpZvhs7yrQc0YeRAjaiqDLoUAAAAICciEfS8Pm7GkjFv7FDVD+2v365g+WZYOOf09tYDmj+OZZsAAAAIj0gEvWQOlm5KqeWb18+p08vv79GBQ525KA0B27rvsPYd6uT+PAAAAIRKNIKel5sZPUm6Ye5oJX2n36/Z1ef3QvAy9+cR9AAAABAm0Qh6vq+YpWbk+mrm6MGaOHKgFr9L8/QwWL7tgAb1K9OUmqqgSwEAAAByJiJBz/V52WaGmemGuaP15gf71HKwIyfvieBk7s/LxTcBAAAAgGIRjaDn+X1qln68G+aOlnPS7+ipV9LajiS0fnc7yzYBAAAQOtEIer7rc2uFribXVGlG3WD9diXLN0vZu9tb5Rz35wEAACB8ohH0PJeTjVi6umHuaL2zrVXb9x/O6fuicJZvPaCYSXPH0igdAAAA4RKNoOc7lcVz+1Gvn1MnSczqlbDlW/drau1gVVWWBV0KAAAAkFORCHqe7+d8Rm/s8AGaP24ou2+WqKNJT8u3HtC5E4cHXQoAAACQc5EIekkvt/foZdx4Zr3W7WrX+l3tOX9v5Ne721rVkfB1/qSRQZcCAAAA5Fw0gl4O2yt0dd2cOsVjpsff3ZHz90Z+vb5pn2ImLZjAjB4AAADCJyJBL/dLNyVpZFWlLpw8Uo+/u1O+73L+/sifNzbt0+z6IRrSvzzoUgAAAICci0bQ81xO++h1ddO80drRekTLtx3Iy/sj9w53JvXO9gM6j2WbAAAACKloBD3fqTzHu25mfGxGrfqXx/Wbd1i+WSqWbTmghOd03qQRQZcCAAAA5EVkgl6+ZvQGVpbpqhmj9MSqZnUm/bycA7n1+qZ9KouZzm6gUToAAADCKRpBz8vPPXoZN80brdbDCb38/p68nQO588amvZo3bqgGVNA/DwAAAOEUjaDn56e9QsZFU6o1fGCFfsPum0Wv7UhCq3a0cX8eAAAAQi0aQc/z89JeIaM8HtN1s+v07Nrd+vBoMm/nQd+99cF++U46n/vzAAAAEGKRCHpenmf0pNTyzY6Er9+v3pXX86BvXt+0V5VlMc0bNzToUgAAAIC8iUTQSzVMz2/Qmz9umMYNH8Dum0XujU37dHbDcFWWxYMuBQAAAMibaAQ9z+V16aYkmZlunlev1zbtVXPbkbyeC72z78OjWrernbYKAAAACL1oBD3fVzzPSzcl6ePz6+Wc9Pi7O/N+LmTv1Y17JXF/HgAAAMIvIkHPqTzPSzclafyIgTpr/DA9trxJzrm8nw/ZeW5ti0YMrNDcMdyfBwAAgHCLRtDznOJ5XrqZ8fH59drQ8qHW7DxYkPOhZ5Ker5fe36PLptUoVoDQDwAAAAQpGkHP91VegKWbknT97NGqiMf0P2+zKUsxeXtbq9qOJHTFtJqgSwEAAADyLhJBz/Od4gWaxRkyoFxXTK/R4hU7lPT8gpwTp/fcut0qj5sunEKjdAAAAIRfJIJewst/e4Wubp5Xr70fduqVDXsLdk6c2vNrW3TOhBEa1K886FIAAACAvItE0Es1TC/cR710ao2GDSjXY283FeycOLlt+w5rQ8uHupxlmwAAAIiISAS9hOcXdEavoiymRXNH6w/v7VbbkUTBzovuPb9utyTpiukEPQAAAERDJIJeakavsDst3nLWWHUmff1uJT31gvbcuhZNqh6o8SMGBl0KAAAAUBChD3rOOSX9wrVXyJhVP1hTRw3So8tYvhmkD48mtWTzfl0xfVTQpQAAAAAFE/qg5/mpxuWFaJjelZnpE41j9O72Vm1saS/oufGRVzfsVafn67KpLNsEAABAdIQ+6CXTQS9e4KWbknTjmfWKx0y/Wk5PvaA8t3a3BvUrU2PDsKBLAQAAAAqmT0HPzIab2TNmtiH98wn/mzazM83sDTNbY2YrzeyTfTlntpLHZvQKn2mrB1XqsqnV+p+3m+ipF4DOpK9n1u7W5dNqVF7AXVcBAACAoPX1f79flvScc26KpOfSz493WNJnnHMzJS2U9C9mNrSP5+0xz0vP6BV46WbGLWeNVUv7Ub2ykZ56hfbaxr1qPZzQormjgy4FAAAAKKi+Br0bJT2UfvyQpJuOP8A5975zbkP68U5JLZKq+3jeHkv4qZm08gCWbkrS5dNqNHxghX7FpiwFt3jFTg3pX66LphTsjxsAAABQFPoa9EY555olKf3zKXe8MLMFkiokbTrJ6/ea2TIzW7Znz54+lpaS2Yyl0LtuZlSUxXTjmaP1zHu71Xq4M5Aaoqgj4ekPa3bpmlm1qihj2SYAAACi5bT/AzazZ81sdTc/bszmRGZWJ+mnkj7rnOv2hjXn3APOuUbnXGN1dW5mYRLpe+MK2TD9eLecNUadnq/FK+ipVyjPr2vRoU5PN7BsEwAAABFUdroDnHNXnuw1M9ttZnXOueZ0kGs5yXGDJT0h6avOuTd7XW0vZGb0Ct0wvauZo4do5ujBenjpdn3mvIbA6oiS367YqZFVlTp34oigSwEAAAAKrq9r2hZLujP9+E5Jjx9/gJlVSPq1pJ845x7t4/mylgh4M5aM284eqzU7D2r1jrZA64iC9o6EnlvXouvn1AX++w4AAAAEoa9B7xuSrjKzDZKuSj+XmTWa2Q/Tx9wq6WJJd5nZu+kfZ/bxvD12rGF6wNvrLzqzXpVlMT28dHugdUTBM+/tVmfSZ9kmAAAAIuu0SzdPxTm3T9IV3Xx9maTPpR//t6T/7st5+iKZ3nUz6JmdIf3Lde3sOv3m3R36P9dOV/+KeKD1hNniFTtVP7S/5o8rWBcPAAAAoKiEfjvCpJeZ0Qt+Cd+tjWPV3pHUU6ubgy4ltPYf6tSrG/bqhrmjZRb87zkAAAAQhPAHvYDbK3R17sThahgxgOWbefTrd3Yo6TvdNI9lmwAAAIiu4NNPniXT7RXKi2BTDjPTJxrHaskH+/XB3kNBlxM6zjn94q1tmjduqKbVDg66HAAAACAwoQ96HzVMDz7oSameevGY6ZFlzOrl2tItB7Sx5UN9asG4oEsBAAAAAhX6oJcogj56XY0a3E+XTa3Rr5Y3HWvmjtz4+ZKtGtSvTDfMYdkmAAAAoi30Qc9L77pZVgT36GV8asFY7Wk/qufW7g66lNA4cKhTT67epZvn1bOjKQAAACKveNJPnhRLw/SuLp1ao7oh/fSzJduCLiU0Hnu7SZ1JX7efw7JNAAAAIPRBr1gapncVj5k+efZYvbJhr7btOxx0OSXPOaefv7VN89mEBQAAAJAUgaCXuQ+umGb0JOmTZ49VzKRfLGVWr6+WfLBfm/ccYhMWAAAAIC30Qe+jGb3iCnp1Q/rr8mmj9Oiy7epMsilLX/xsyTYN6lem69mEBQAAAJAUgaCXLLL2Cl19+pxx2vthp55lU5Ze29l6RE+uatatjWPZhAUAAABIC3/Q84rvHr2Mi8+oVv3Q/vo5m7L02oOvb5EkffaChkDrAAAAAIpJ8aWfHMu0VyjGGb14zHTb2WP16sa92rL3UNDllJz2joR+sWSbrp1dpzHDBgRdDgAAAFA0Qh/0Mu0Vyouoj15Xt549VvGY6edvMauXrYeXblf70aTuuWhC0KUAAAAARaU4008OZTZjiRfZZiwZowb309UzR+mRZdvVkfCCLqdkJDxfP35tixZMGK45Y4YGXQ4AAABQVEIf9BLppZtlRbh0M+OOc8er9XBCv1vZHHQpJePJVc3a0XpE9140MehSAAAAgKIT+qDnpZduFnPQO2/iCE2uqdJP39gSdCklwTmnH77ygSZWD9Tl02qCLgcAAAAoOqEPeokibq+QYWb6k3PHa0VTm1Zsbw26nKL3xuZ9WrWjTXdfOEGxIv59BQBJMrOFZrbezDaa2Ze7ef1LZvaema00s+fMbHwQdQIAwiX0Qc/zfZXFTGbFHQhunl+vARVx/fTNrUGXUvS+98ImVQ+q1P+aPyboUgDglMwsLum7kq6RNEPSp8xsxnGHvSOp0Tk3R9KvJH2rsFUCAMIo9EEv6bmins3LGNyvXDfPq9dvV+zUgUOdQZdTtN7d3qpXN+7VPRdNUL9yGqQDKHoLJG10zm12znVK+qWkG7se4Jx7wTl3OP30TUl8FwsA0GfhD3q+K8pm6d35k/PG62jS16PLtwddStH67gsbNaR/uW4/h5VNAEpCvaSu/6g3pb92MndLeqq7F8zsXjNbZmbL9uzZk8MSAQBhVBoJqA88vzRm9CRpWu1gLWgYrp++ufVYWwh8ZN2ug3rmvd367AUNqqosC7ocAOiJ7i5A3f4Db2Z3SGqU9O3uXnfOPeCca3TONVZXV+ewRABAGIU+6CU8X+VF2kOvO585f7y27z+iF9a1BF1K0fneC5s0sCKuu85vCLoUAOipJkljuzwfI2nn8QeZ2ZWSviJpkXPuaIFqAwCEWOiDXinN6EnS1TNrVTekn378+gdBl1JUtuw9pN+t3Kk7zh2voQMqgi4HAHpqqaQpZjbBzCok3SZpcdcDzGyepO8rFfL4Lh8AICdCH/QSnlNZrHQ+Znk8pjvOHa/XNu7T+7vbgy6naPznS5tUFo/p7gsnBF0KAPSYcy4p6X5JT0taK+kR59waM/uamS1KH/ZtSVWSHjWzd81s8UneDgCAHiudBNRLnu+rrISWbkrS7QvGqbIsph+/tiXoUopCc9sRPfZ2k25tHKOawf2CLgcAsuKce9I5d4ZzbpJz7uvpr/2dc25x+vGVzrlRzrkz0z8WnfodAQA4vdAHvUSJLd2UpGEDK3TzvHr9+p0mtR6m1cIDL2+W76Q/vXhS0KUAAAAAJSH0Qc/znMpLaOlmxl0XNKgj4euXS6PdamHfh0f1i7e26aYz6zV2+ICgywEAAABKQukloCwlfb/kZvSkVKuF8yaO0E/f2Kqk5wddTmB+9NoHOpr0dd+lzOYBAAAAPRWBoOdKqr1CV3dd0KAdrUf0h/d2B11KIA52JPST17fqmlm1mlxTFXQ5AAAAQMkIf9DzSu8evYwrp4/SuOED9MNXNgddSiB++sZWtR9N6vOXTg66FAAAAKCkhD/o+b7K4qX5MeMx090XTtDb21q1fOv+oMspqCOdnv7r1Q906dRqzaofEnQ5AAAAQEkpzQSUBc93KivRGT1J+kTjGA3pX64fvBytBuqPLNuu/Yc6mc0DAAAAeiH0QS/huZKd0ZOkARVl+vQ54/T0e7u0dd+hoMspiKTn6wevbNZZ44dpwYThQZcDAAAAlJzSTUA9VOozepJ05/kNKouZfvRqNGb1nljVrKYDR/SnF08MuhQAAACgJIU+6CW80myv0NWowf20aG69HlkW/gbqzjl9/6XNmlQ9UFdOHxV0OQAAAEBJCn3Q80q4vUJXn7togo4kPP1sybagS8mrVzbs1XvNB/WnF09SrMQDOgAAABCU0Ae9pO8Uj5X+x5xeN1gXTRmpB1/foo6EF3Q5efP9lzdp1OBK3ThvdNClAAAAACWr9BPQaSR9X+UhmRn6s0smaU/7UT32dlPQpeTFqqY2vbZxn/73BRNUWRYPuhwAAACgZIU/6JVww/TjnT9phOaOGaLvv7RZSc8Pupyc+/7LmzSosky3nzMu6FIAAACAkhb+oOeXdnuFrsxM9106Wdv2H9YTq5qDLientu8/rCdXNev2c8ZpUL/yoMsBAAAASlo4EtApJD2/5NsrdPWxGaM0uaZK//HiJjnngi4nZ3782hbFzHTXBQ1BlwIAAACUvPAHPd+pLAS7bmbEYqb7Lpmkdbva9fy6lqDLyYm2Iwk9vHSbbpg7WnVD+gddDgAAAFDyQh/0wtAw/XiLzhyt+qH99b2QzOr98q1tOtTp6XMXTQi6FAAAACAUQh/0kl547tHLKI/HdO/FE7V86wEt+WB/0OX0ScLz9eDrW3T+pBGaOXpI0OUAAAAAoRCuBNSNpB+ue/QyPnn2WI2sqtS/Prch6FL65ImVzWpu69A9F00MuhQAAAAgNEId9HzfyXcKTXuFrvqVx/Vnl0zU65v2acnmfUGX0yvOOf3glc2aXFOlS86oDrocAAAAIDRCHfSSfur+tfKQLd3MuOPc8aoeVKl/ebY0Z/Xe2LRPa3Ye1OcunKBYCMM4AAAAEJRwJqC0pJ9qKh7GGT0pNat33yWT9MbmfXqzBGf1Hnhls0ZWVeimefVBlwIAAACESsiDXmpGL4z36GXcfs441Qyq1HeeeT/oUrKyfle7Xly/R3ee16B+5fGgywEAAABCJdxBzwt/0OtXHtd9l07Skg/2641NpTOr98NXNqtfeUx3nDs+6FIAAACA0Al30Esv3Qxbe4XjfWrBR7N6pdBXr+Vgh37z7g7d2jhWwwZWBF0OAAAAEDqhTkBRmNGTUrN6X7h8st7asl8vrG8JupzTevD1LUr6TndfSIN0AAAAIB9CHfS8zD16IZ/Rk6TbFoxTw4gB+uZT64997mJ06GhS//3mVi2cWavxIwYGXQ4AAAAQSqFOQAkvvXQz5DN6UqqFxF9dPU3rd7frsbebgi7npB5eul0HO5K652IapAMAAAD5Euqg99GMXviDniRdO7tWc8cO1XeeeV8dCS/ock7QmfT1w1c2q3H8MM0fNyzocgAAAIDQCnXQi0J7ha7MTH9zzTQ1t3Xox69tCbqcEzz2dpN2tnXo/ssnB10KAAAAEGrhDnrpzVjisVB/zD9y7sQRunxajb734kYdONQZdDnHJD1f33txo+aMGaJLzqgOuhwAAAAg1EKdgD5qrxCNGb2Mv144TYeOJvXPRdRE/fF3d2r7/iP6wuVTZBat3w8AAACg0EIe9KK1dDNjau0gfea8Bv1syVat3tEWdDnyfKfvvrBR0+sG68rpNUGXAwAAAIReuIPesT56of6Y3friVWdo+MAK/e3jq+UH3G7hyVXN2rz3kO6/bDKzeQAAAEABhDoBRXXppiQN6V+uv7lmut7Z1qpHl28PrA7fd/r35zdqck2VrplVG1gdAAAAQJSEPOhFc+lmxsfn1+vshmH6xlPr1Ho4mI1Zfrtyp9bvbtf9l01WLKK/DwAAAEChhTvoRXjpppRqt/C1G2fpYEdS33p6fcHPf6TT0zefWqdZ9YO1aO7ogp8fAAAAiKpQJyAvwks3M6bXDdZd5zfo50u26dUNewt67h++slk72zr0t9fNYDYPAAAAKKBQB72EF+2lmxl/+bGpmlQ9UH/56Aq1HU4U5Jy7D3boP17apIUza3XOxBEFOScAAACAlFAHPS9zj1481B/ztPpXxPWdT56pvR8e1d8+vrog5/zHp9cr6Tn9zbXTCnI+AAAAAB8JdQKK+mYsXc0ZM1R/fsUULV6xU4tX7MzruVbvaNOv3m7SXRc0aPyIgXk9FwAAAIAThTvoeal79OIEPUnSfZdO0rxxQ/XVX6/SztYjeTlHwvP1lV+v0rABFbr/8sl5OQcAAACAUwt30Du2dJOgJ6WWsP7zrWfKd9I9P1mmQ0eTOT/HP/5hvVY0tenrN83S4H7lOX9/AAAAAKcX7qCXntGLanuF7kwYOVD/dvs8rW0+qD//5TvH7mPMhZff36Pvv7RZt58zTtfMrsvZ+wIAAADITqgTEDN63btsao3+36KZenZti77+xNqcvOee9qP60iMrdMaoKv3d9TNy8p4AAAAAeqcs6ALyic1YTu5PzmvQ5r2H9KPXPtC44f111wUTev1enu/0F4+uUHtHQj/73DnqVx7PYaUAAAAAshXqoHesvQJLN7v11etmaPv+I/r7376n/Yc69cWrzpBZdqH4aNLTFx9+Vy+/v0dfv3mWptYOylO1AAAAAHoq1AkocewePWb0uhOPmb736fn6xFlj9K/Pb9QXfvGOOhJej399e0dCn/3xUj25ape+et10ffqc8XmsFgAAAEBPhX5GL2ZSjKB3UhVlMX3rljmaWF2lb/5+nXa0HtG3b5mryTVVp/x1Le0d+uyPl2r9rnb9861z9fH5YwpUMQAAAIDTCXXQS3iOZZs9YGa679JJmjBygL70yApd9Z2X9LEZo3TfpZN15tihf3Tsul0H9dDrW/Trd3ZIkn5wZ6Mum1oTRNkAAAAATiLUQc/zfZqlZ2HhrDqd3TBcD72+RQ++vkVPr9mthhEDNKhfufqXx3U06WlFU5sqy2K66cx63XPxBE2u4Z48AAAAoNiEOuglfUdrhSyNqKrUlz42VfdeMkm/fGub3t52QB0JX4c7kyqPx/TXC6fptrPHatjAiqBLBQAAAHAS4Q56nmMjll6qqizT5y6aGHQZAAAAAHoh1DewpWb0Qv0RAQAAAOAEoU5BSc9nRg8AAABA5IQ66HncowcAAAAggkId9BI+7RUAAAAARE+oU5Dns3QTAAAAQPSEOuglPEcfPQAAAACRE+qg5/lO5ey6CQAAACBiQp2CEp7PjB4AAACAyAl10PN8GqYDAAAAiJ5QB70k7RUAAAAARFC4g57n014BAAAAQOSEOgXRMB0AAABAFPUp6JnZcDN7xsw2pH8edopjB5vZDjP7976cMxsJj3v0AAAAAERPX2f0vizpOefcFEnPpZ+fzD9IeqmP58tKajOWUE9aAgAAAMAJ+pqCbpT0UPrxQ5Ju6u4gMztL0ihJf+jj+bKS8H3FWboJAAAAIGL6GvRGOeeaJSn9c83xB5hZTNI/Sfqr072Zmd1rZsvMbNmePXv6WFq6YTpLNwEAAABETNnpDjCzZyXVdvPSV3p4js9LetI5t93s1KHLOfeApAckqbGx0fXw/U8q6TnFWboJAAAAIGJOG/Scc1ee7DUz221mdc65ZjOrk9TSzWHnSbrIzD4vqUpShZl96Jw71f18OZH0fZWzdBMAAABAxJw26J3GYkl3SvpG+ufHjz/AOffpzGMzu0tSYyFCnpSZ0SPoAQAAAIiWvq5r/Iakq8xsg6Sr0s9lZo1m9sO+FtdXSZ/2CgAAAACip08zes65fZKu6ObryyR9rpuvPyjpwb6cMxuphuncowcAAAAgWkKdghKez4weAAAAgMgJddBLzegR9AAAAABES2iDnnNOSZ/2CgAAAACiJ7QpyHfS5JoqVVdVBF0KAAAAABRUX9srFK14zPTsly4JugwAAAAAKLjQzugBAAAAQFQR9AAAAAAgZAh6AAAAABAyBD0AAAAACBmCHgAAAACEDEEPAAAAAEKGoAcAAAAAIUPQAwAAAICQIegBAAAAQMgQ9AAAAAAgZAh6AAAAABAyBD0AAAAACBmCHgAAAACEDEEPAAAAAEKGoAcAAAAAIUPQAwAAAICQIegBAAAAQMgQ9AAAAAAgZAh6AAAAABAyBD0AAAAACBmCHgAAeWRmC81svZltNLMvd/N6pZk9nH59iZk1FL5KAEDYEPQAAMgTM4tL+q6kayTNkPQpM5tx3GF3SzrgnJss6TuSvlnYKgEAYUTQAwAgfxZI2uic2+yc65T0S0k3HnfMjZIeSj/+laQrzMwKWCMAIITKgi7gZJYvX77XzLbm4K1GStqbg/cJG8blRIxJ9xiX7jEu3evtuIzPdSFFol7S9i7PmySdc7JjnHNJM2uTNELHjaOZ3Svp3vTTo2a2Oi8VhxN/X7PDeGWH8coO45Wdqb39hUUb9Jxz1bl4HzNb5pxrzMV7hQnjciLGpHuMS/cYl+4xLifobmbO9eIYOecekPSAxDhni/HKDuOVHcYrO4xXdsxsWW9/LUs3AQDInyZJY7s8HyNp58mOMbMySUMk7S9IdQCA0CLoAQCQP0slTTGzCWZWIek2SYuPO2axpDvTj2+R9Lxz7oQZPQAAslG0Szdz6IGgCyhSjMuJGJPuMS7dY1y6x7h0kb7n7n5JT0uKS/qRc26NmX1N0jLn3GJJ/yXpp2a2UamZvNt68NaMc3YYr+wwXtlhvLLDeGWn1+NlfNMQAAAAAMKFpZsAAAAAEDIEPQAAAAAImVAEPTNbaGbrzWyjmX25m9crzezh9OtLzKyh8FUWXg/G5Utm9p6ZrTSz58wsrH2s/sjpxqXLcbeYmTOzSGwB3JNxMbNb039m1pjZzwtdYxB68PdonJm9YGbvpP8uXRtEnYVkZj8ys5aT9XGzlH9Nj9lKM5tf6BrDgutbdrjuZYfrYXa4TmaH62d28nJtdc6V9A+lbm7fJGmipApJKyTNOO6Yz0v6z/Tj2yQ9HHTdRTIul0kakH58H+PyR8cNkvSypDclNQZddzGMi6Qpkt6RNCz9vCbouotkXB6QdF/68QxJW4KuuwDjcrGk+ZJWn+T1ayU93sV9kgAAA6dJREFUpVR/uHMlLQm65lL8wfUtL+MVueteX8YrfVykrod9Ga8oXif7OF6Ru36eZsxyfm0Nw4zeAkkbnXObnXOdkn4p6cbjjrlR0kPpx7+SdIWZddegNkxOOy7OuRecc4fTT99Uqr9T2PXkz4sk/YOkb0nqKGRxAerJuNwj6bvOuQOS5JxrKXCNQejJuDhJg9OPh+jEHmmh45x7Wafu83ajpJ+4lDclDTWzusJUFypc37LDdS87XA+zw3UyO1w/s5SPa2sYgl69pO1dnjelv9btMc65pKQ2SSMKUl1wejIuXd2t1HcJwu6042Jm8ySNdc79rpCFBawnf17OkHSGmb1mZm+a2cKCVRecnozL30u6w8yaJD0p6QuFKa2oZfvvD7rH9S07XPeyw/UwO1wns8P1M/eyvraGoY9ed9+5PL5nRE+OCZsef2Yzu0NSo6RL8lpRcTjluJhZTNJ3JN1VqIKKRE/+vJQptSzlUqW+C/6Kmc1yzrXmubYg9WRcPiXpQefcP5nZeUr1Q5vlnPPzX17RiuK/ufnA9S07XPeyw/UwO1wns8P1M/ey/vc+DDN6TZLGdnk+RidO/R47xszKlJoePtXUaBj0ZFxkZldK+oqkRc65owWqLUinG5dBkmZJetHMtii1BnpxBG5A7+nfo8edcwnn3AeS1it1QQuznozL3ZIekSTn3BuS+kkaWZDqileP/v3BaXF9yw7XvexwPcwO18nscP3MvayvrWEIekslTTGzCWZWodTN6IuPO2axpDvTj2+R9LxL39UYYqcdl/SSjO8rdbGLyjryU46Lc67NOTfSOdfgnGtQ6h6ORc65ZcGUWzA9+Xv0G6U2MpCZjVRqicrmglZZeD0Zl22SrpAkM5uu1IVqT0GrLD6LJX0mvUPYuZLanHPNQRdVgri+ZYfrXna4HmaH62R2uH7mXtbX1pJfuumcS5rZ/ZKeVmqHnx8559aY2dckLXPOLZb0X0pNB29U6judtwVXcWH0cFy+LalK0qPpe/e3OecWBVZ0AfRwXCKnh+PytKSPmdl7kjxJf+Wc2xdc1fnXw3H5C0k/MLMvKrWE4q6w/0fbzH6h1NKkkel7K/6vpHJJcs79p1L3WlwraaOkw5I+G0ylpY3rW3a47mWH62F2uE5mh+tn9vJxbbUIjycAAAAAhFIYlm4CAAAAALog6AEAAABAyBD0AAAAACBkCHoAAAAAEDIEPQAAAAAIGYIeAAAAAIQMQQ8AAAAAQub/Azi0hbb+GPrBAAAAAElFTkSuQmCC\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "control = np.vstack(ddp.us)\n", + "t = np.arange(0,T*dt, dt)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('Motor torques')\n", + "# axs[0].plot(t,control[:,0], t,control[:,1])\n", + "axs[0].plot(t,control[:,0])\n", + "axs[0].set_title('Moments')\n", + "axs[0].legend(['M1','M2'])\n", + "\n", + "t_state = np.append(t, t[-1]+dt)\n", + "state = np.vstack(ddp.xs)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('States')\n", + "axs[0].plot(t_state,state[:,0], t_state, state[:,1])\n", + "axs[0].set_title('Position')\n", + "axs[0].legend(['Link 1','Link2'])\n", + "axs[1].plot(t_state,state[:,2], t_state, state[:,3])\n", + "axs[1].set_title('Vels')\n", + "axs[1].legend(['Link 1','Link2'])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.16" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/notebooks/acrobot_limited_torque.ipynb b/examples/notebooks/acrobot_limited_torque.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..caeef7593586db99cc10dc3dd08c88f4fbf044bd --- /dev/null +++ b/examples/notebooks/acrobot_limited_torque.ipynb @@ -0,0 +1,605 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from crocoddyl import *\n", + "import pinocchio as pin\n", + "import numpy as np\n", + "\n", + "robot = loadBorinotArm()\n", + "robot.initViewer(loadModel=True)\n", + "\n", + "q0 = [3.14, 0]\n", + "robot.q0.flat = q0\n", + "robot.framesForwardKinematics(robot.q0)\n", + "robot.display(robot.q0)\n", + "\n", + "IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)\n", + "IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)\n", + "Mlink1 = robot.data.oMf[IDX_LINK1]\n", + "Mlink2 = robot.data.oMf[IDX_LINK2]\n", + "\n", + "target_pos = np.array([0,0,0.3])\n", + "target_quat = pin.Quaternion(1, 0, 0, 0)\n", + "target_quat.normalize()\n", + "\n", + "Mref = pin.SE3()\n", + "Mref.translation = target_pos.reshape(3,1)\n", + "Mref.rotation = target_quat.matrix()\n", + "\n", + "robot.viewer.gui.refresh()" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "state = StatePinocchio(robot.model)\n", + "\n", + "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)\n", + "xPendCost = CostModelDoublePendulum(robot.model, \n", + " frame=state, \n", + " ref=state.zero, \n", + " nu=1,\n", + " activation=ActivationModelWeightedQuad(np.array([1,1,1,1]+[0.1]*2)))\n", + "\n", + "uRegCost = CostModelControl(robot.model, nu = 1)\n", + "uLimCost = CostModelControl(robot.model, nu=1,\n", + " activation = ActivationModelInequality(np.array([-2]), np.array([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-3, cost=uRegCost)\n", + "runningCostModel.addCost(name=\"limu\", weight=1e4, cost=uLimCost)\n", + "runningCostModel.addCost(name=\"pend\", weight=1, cost=xPendCost)\n", + "terminalCostModel.addCost(name=\"ori2\", weight=1e5, cost=xPendCost)" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [], + "source": [ + "actModel = ActuationModelDoublePendulum(robot.model)\n", + "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n", + "terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "# Defining the time duration for running action models and the terminal one\n", + "dt = 1e-2\n", + "runningModel.timeStep = dt\n", + "\n", + "T = 100\n", + "x0 = np.array([3.14, 0, 0., 0. ])\n", + "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)" + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 0 2.00201e+05 1.16096e+09 9.21968e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 1 2.00200e+05 1.54461e+07 3.14734e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 2 2.00199e+05 1.79399e+03 3.09626e-01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 3 2.00199e+05 3.39328e+03 5.89887e-01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 4 2.00197e+05 6.47120e+03 1.12549e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 5 2.00195e+05 1.23441e+04 2.14841e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 6 2.00190e+05 2.35492e+04 4.10323e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 7 2.00180e+05 4.49270e+04 7.84407e+00 1.00000e+00 1.00000e+00 1.0000 1\n", + " 8 2.00162e+05 8.57134e+04 1.50217e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 9 2.00128e+05 1.63545e+05 2.88639e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 10 2.00061e+05 3.12250e+05 5.58218e+01 1.00000e+00 1.00000e+00 1.0000 1\n", + " 11 1.99929e+05 5.97981e+05 1.09351e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 12 1.99660e+05 1.16043e+06 2.19929e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 13 1.99065e+05 2.38449e+06 4.68916e+02 1.00000e+00 1.00000e+00 1.0000 1\n", + " 14 1.97416e+05 6.33753e+06 1.16250e+03 1.00000e+00 1.00000e+00 1.0000 1\n", + " 15 1.82461e+05 4.99746e+07 5.10514e+03 1.00000e+00 1.00000e+00 1.0000 1\n", + " 16 1.68743e+05 7.51342e+10 5.15698e+04 1.00000e+01 1.00000e+01 1.0000 1\n", + " 17 9.38464e+04 3.99501e+09 3.44668e+05 1.00000e+01 1.00000e+01 0.2500 1\n", + " 18 6.20709e+04 1.73733e+09 1.89145e+05 1.00000e+01 1.00000e+01 0.2500 1\n", + " 19 3.85974e+04 6.30092e+09 1.17716e+05 1.00000e+01 1.00000e+01 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 20 1.03516e+04 4.31280e+10 6.82940e+04 1.00000e+00 1.00000e+00 1.0000 1\n", + " 21 4.87909e+03 5.44394e+08 1.76780e+04 1.00000e+00 1.00000e+00 0.5000 1\n", + " 22 2.74900e+03 1.36185e+08 6.80593e+03 1.00000e+00 1.00000e+00 0.5000 1\n", + " 23 2.26525e+03 3.23389e+07 2.48792e+03 1.00000e+00 1.00000e+00 0.2500 1\n", + " 24 2.00218e+03 1.72113e+07 1.45235e+03 1.00000e+00 1.00000e+00 0.2500 1\n", + " 25 1.78225e+03 9.35526e+06 8.88130e+02 1.00000e+00 1.00000e+00 0.5000 1\n", + " 26 1.70900e+03 3.25766e+06 4.87219e+02 1.00000e+00 1.00000e+00 0.5000 1\n", + " 27 1.45437e+03 2.81074e+06 4.28763e+02 1.00000e-01 1.00000e-01 1.0000 1\n", + " 28 1.44650e+03 7.18130e+04 3.24673e+02 1.00000e-01 1.00000e-01 0.2500 1\n", + " 29 1.28009e+03 1.35835e+06 4.07315e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 30 1.17083e+03 3.72045e+05 2.46910e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 31 1.07234e+03 1.14892e+05 2.09363e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 32 9.81458e+02 2.95951e+04 1.97437e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 33 9.12396e+02 7.56477e+04 1.61160e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 34 8.67297e+02 1.56992e+05 1.14369e+02 1.00000e-01 1.00000e-01 0.5000 1\n", + " 35 8.37954e+02 1.38782e+05 7.93409e+01 1.00000e-01 1.00000e-01 0.5000 1\n", + " 36 8.32553e+02 9.20304e+04 5.62021e+01 1.00000e-02 1.00000e-02 1.0000 1\n", + " 37 8.04302e+02 4.47949e+06 1.05152e+02 1.00000e-02 1.00000e-02 0.5000 1\n", + " 38 7.91927e+02 1.85335e+06 6.00869e+01 1.00000e-02 1.00000e-02 0.2500 1\n", + " 39 7.84905e+02 1.91063e+06 3.94869e+01 1.00000e-02 1.00000e-02 0.2500 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 40 7.78048e+02 1.56453e+06 3.35363e+01 1.00000e-02 1.00000e-02 0.2500 1\n", + " 41 7.65557e+02 1.06110e+06 3.75758e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 42 7.57086e+02 2.43896e+05 2.67326e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 43 7.52138e+02 1.02634e+05 1.76361e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 44 7.47640e+02 7.48769e+04 1.50511e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 45 7.44045e+02 4.62155e+04 1.20408e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 46 7.40895e+02 2.21082e+04 1.00404e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 47 7.38150e+02 9.12470e+03 8.33494e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 48 7.34128e+02 3.44749e+03 1.13019e+01 1.00000e-02 1.00000e-02 0.5000 1\n", + " 49 7.31396e+02 1.09334e+03 7.80453e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 50 7.29142e+02 4.34632e+02 6.37590e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 51 7.27131e+02 2.04619e+02 5.57687e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 52 7.25288e+02 1.11751e+02 5.00524e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 53 7.23581e+02 6.98146e+01 4.53997e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 54 7.21996e+02 4.87408e+01 4.13758e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 55 7.20522e+02 3.69315e+01 3.77785e+00 1.00000e-02 1.00000e-02 0.5000 1\n", + " 56 7.20226e+02 2.95394e+01 3.44965e+00 1.00000e-03 1.00000e-03 1.0000 1\n", + " 57 7.17749e+02 2.87417e+01 8.36866e+00 1.00000e-04 1.00000e-04 1.0000 1\n", + " 58 7.14277e+02 5.02383e+02 8.30024e+00 1.00000e-05 1.00000e-05 1.0000 1\n", + " 59 7.11729e+02 4.48620e+02 5.13914e+00 1.00000e-06 1.00000e-06 1.0000 1\n", + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 60 7.10064e+02 3.92263e+01 2.89454e+00 1.00000e-07 1.00000e-07 1.0000 1\n", + " 61 7.08957e+02 8.47074e+00 1.69626e+00 1.00000e-08 1.00000e-08 1.0000 1\n", + " 62 7.08197e+02 4.96030e+00 1.05786e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 63 7.07669e+02 3.34772e+00 6.83466e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 64 7.07303e+02 2.24922e+00 4.49028e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 65 7.07051e+02 1.50899e+00 2.98350e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 66 7.06877e+02 1.01782e+00 1.99807e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 67 7.06758e+02 6.89397e-01 1.34486e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 68 7.06676e+02 4.67906e-01 9.07836e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 69 7.06621e+02 3.17727e-01 6.13704e-02 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", + " 70 7.06583e+02 2.15630e-01 4.15043e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 71 7.06557e+02 1.46175e-01 2.80621e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 72 7.06540e+02 9.89539e-02 1.89612e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 73 7.06528e+02 6.68904e-02 1.28007e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 74 7.06520e+02 4.51535e-02 8.63346e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 75 7.06515e+02 3.04416e-02 5.81726e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 76 7.06511e+02 2.05000e-02 3.91612e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 77 7.06509e+02 1.37916e-02 2.63408e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 78 7.06507e+02 9.27066e-03 1.77043e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 79 7.06506e+02 6.22726e-03 1.18918e-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", + " 80 7.06506e+02 4.18045e-03 7.98304e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 81 7.06505e+02 2.80499e-03 5.35650e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 82 7.06505e+02 1.88130e-03 3.59268e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 83 7.06505e+02 1.26134e-03 2.40883e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 84 7.06504e+02 8.45442e-04 1.61462e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 85 7.06504e+02 5.66542e-04 1.08201e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 86 7.06504e+02 3.79573e-04 7.24944e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 87 7.06504e+02 2.54266e-04 4.85633e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 88 7.06504e+02 1.70304e-04 3.25276e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 89 7.06504e+02 1.14055e-04 2.17846e-05 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", + " 90 7.06504e+02 7.63770e-05 1.45883e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 91 7.06504e+02 5.11423e-05 9.76851e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 92 7.06504e+02 3.42431e-05 6.54071e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 93 7.06504e+02 2.29268e-05 4.37925e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 94 7.06504e+02 1.53496e-05 2.93195e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 95 7.06504e+02 1.02763e-05 1.96290e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 96 7.06504e+02 6.87959e-06 1.31409e-06 1.00000e-09 1.00000e-09 1.0000 1\n", + " 97 7.06504e+02 4.60553e-06 8.79723e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 98 7.06504e+02 3.08311e-06 5.88921e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 99 7.06504e+02 2.06392e-06 3.94241e-07 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", + " 100 7.06504e+02 1.38163e-06 2.63913e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 101 7.06504e+02 9.24878e-07 1.76667e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 102 7.06504e+02 6.19119e-07 1.18262e-07 1.00000e-09 1.00000e-09 1.0000 1\n", + " 103 7.06504e+02 4.14440e-07 7.91650e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 104 7.06504e+02 2.77425e-07 5.29930e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 105 7.06504e+02 1.85707e-07 3.54733e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 106 7.06504e+02 1.24311e-07 2.37456e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 107 7.06504e+02 8.32129e-08 1.58951e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 108 7.06504e+02 5.57018e-08 1.06400e-08 1.00000e-09 1.00000e-09 1.0000 1\n", + " 109 7.06504e+02 3.72861e-08 7.12231e-09 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", + " 110 7.06504e+02 2.49589e-08 4.76758e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 111 7.06504e+02 1.67071e-08 3.19136e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 112 7.06504e+02 1.11835e-08 2.13625e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 113 7.06504e+02 7.48607e-09 1.42997e-09 1.00000e-09 1.00000e-09 1.0000 1\n", + " 114 7.06504e+02 5.01106e-09 9.57201e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 115 7.06504e+02 3.35432e-09 6.40735e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 116 7.06504e+02 2.24533e-09 4.28898e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 117 7.06504e+02 1.50299e-09 2.87097e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 118 7.06504e+02 1.00607e-09 1.92178e-10 1.00000e-09 1.00000e-09 1.0000 1\n", + " 119 7.06504e+02 6.73448e-10 1.28641e-10 1.00000e-09 1.00000e-09 1.0000 1\n" + ] + }, + { + "data": { + "text/plain": [ + "([array([3.14, 0. , 0. , 0. ]),\n", + " array([ 3.18493483, -0.08713097, 4.49348266, -8.71309691]),\n", + " array([ 3.22982922, -0.17422295, 4.48943897, -8.70919818]),\n", + " array([ 3.27463368, -0.26123506, 4.48044665, -8.70121073]),\n", + " array([ 3.31930116, -0.34813232, 4.46674731, -8.68972573]),\n", + " array([ 3.3637864 , -0.43488528, 4.44852429, -8.67529596]),\n", + " array([ 3.40804614, -0.52147104, 4.42597405, -8.65857693]),\n", + " array([ 3.45203908, -0.60787411, 4.3992939 , -8.64030695]),\n", + " array([ 3.49572575, -0.69408695, 4.36866709, -8.6212839 ]),\n", + " array([ 3.5390682 , -0.78011034, 4.33424476, -8.60233823]),\n", + " array([ 3.58202944, -0.86595335, 4.29612455, -8.58430185]),\n", + " array([ 3.62457269, -0.95163308, 4.25432498, -8.56797262]),\n", + " array([ 3.66666024, -1.03717382, 4.20875518, -8.5540736 ]),\n", + " array([ 3.70825203, -1.12260589, 4.15917901, -8.54320694]),\n", + " array([ 3.74930376, -1.2079639 , 4.1051729 , -8.53580164]),\n", + " array([ 3.78976453, -1.29328445, 4.04607641, -8.53205496]),\n", + " array([ 3.82957387, -1.37860312, 3.98093479, -8.5318673 ]),\n", + " array([ 3.86865821, -1.46395083, 3.90843304, -8.53477094]),\n", + " array([ 3.90692642, -1.54934937, 3.82682136, -8.53985338]),\n", + " array([ 3.94426475, -1.63480614, 3.73383306, -8.54567774]),\n", + " array([ 3.98053073, -1.72030818, 3.62659787, -8.55020392]),\n", + " array([ 4.01554629, -1.80581536, 3.50155646, -8.55071764]),\n", + " array([ 4.04909017, -1.89125314, 3.35438753, -8.54377834]),\n", + " array([ 4.08088983, -1.97650518, 3.179966 , -8.52520325]),\n", + " array([ 4.11061365, -2.0614063 , 2.97238232, -8.49011228]),\n", + " array([ 4.13786431, -2.14573696, 2.72506609, -8.43306657]),\n", + " array([ 4.16217503, -2.22922035, 2.4310713 , -8.34833814]),\n", + " array([ 4.18301089, -2.31152378, 2.08358681, -8.23034362]),\n", + " array([ 4.19977811, -2.39226627, 1.6767212 , -8.07424892]),\n", + " array([ 4.21184367, -2.47103323, 1.20655621, -7.87669595]),\n", + " array([ 4.21856719, -2.5473984 , 0.67235267, -7.63651656]),\n", + " array([ 4.21934358, -2.62095052, 0.07763904, -7.35521223]),\n", + " array([ 4.21365138, -2.69132007, -0.56922022, -7.03695521]),\n", + " array([ 4.2010976 , -2.75819982, -1.25537806, -6.68797471]),\n", + " array([ 4.18144805, -2.82135412, -1.96495545, -6.31542982]),\n", + " array([ 4.1546345 , -2.8806153 , -2.68135469, -5.92611818]),\n", + " array([ 4.12073633, -2.93586983, -3.38981707, -5.52545275]),\n", + " array([ 4.07994146, -2.98703967, -4.07948713, -5.11698483]),\n", + " array([ 4.03249681, -3.03406438, -4.74446431, -4.70247092]),\n", + " array([ 3.97865952, -3.07688703, -5.38372967, -4.28226492]),\n", + " array([ 3.91865755, -3.11544476, -6.00019685, -3.85577255]),\n", + " array([ 3.85266447, -3.14966274, -6.59930767, -3.42179813]),\n", + " array([ 3.78078881, -3.17945018, -7.18756677, -2.97874435]),\n", + " array([ 3.7030761 , -3.20469733, -7.77127012, -2.52471514]),\n", + " array([ 3.61952089, -3.22527333, -8.3555211 , -2.05759976]),\n", + " array([ 3.53008582, -3.24102535, -8.9435073 , -1.57520148]),\n", + " array([ 3.43472632, -3.25177977, -9.53595011, -1.07544263]),\n", + " array([ 3.33342001, -3.25734622, -10.130631 , -0.55664453]),\n", + " array([ 3.22620072, -3.25752471, -10.72192855, -0.01784962]),\n", + " array([ 3.11319716, -3.25211593, -11.30035679, 0.54087823]),\n", + " array([ 2.99467543, -3.24093321, -11.85217304, 1.11827178]),\n", + " array([ 2.87108326, -3.22381401, -12.35921665, 1.71191999]),\n", + " array([ 2.74309093, -3.20062711, -12.79923328, 2.31869085]),\n", + " array([ 2.61162101, -3.17127135, -13.14699188, 2.93557598]),\n", + " array([ 2.47785653, -3.13566281, -13.37644766, 3.56085404]),\n", + " array([ 2.34321673, -3.0937107 , -13.46397986, 4.19521091]),\n", + " array([ 2.20929329, -3.04528892, -13.39234406, 4.84217741]),\n", + " array([ 2.07774767, -2.99021764, -13.15456262, 5.50712797]),\n", + " array([ 1.95017995, -2.92827416, -12.75677153, 6.1943487 ]),\n", + " array([ 1.82798801, -2.85924939, -12.21919418, 6.90247658]),\n", + " array([ 1.71224005, -2.78305096, -11.57479545, 7.61984292]),\n", + " array([ 1.60358496, -2.69982733, -10.86550973, 8.32236297]),\n", + " array([ 1.50222224, -2.61006278, -10.13627152, 8.9764555 ]),\n", + " array([ 1.40794385, -2.51459193, -9.42783876, 9.54708506]),\n", + " array([ 1.32023866, -2.41451775, -8.7705189 , 10.00741791]),\n", + " array([ 1.23842721, -2.31106726, -8.18114567, 10.34504843]),\n", + " array([ 1.1617862 , -2.20544508, -7.66410053, 10.5622185 ]),\n", + " array([ 1.08963599, -2.09873012, -7.21502086, 10.67149541]),\n", + " array([ 1.02138593, -1.99182767, -6.82500671, 10.69024488]),\n", + " array([ 0.95654743, -1.88546442, -6.48384938, 10.63632564]),\n", + " array([ 0.89472834, -1.78020754, -6.18190962, 10.52568747]),\n", + " array([ 0.83561907, -1.67649271, -5.91092625, 10.3714835 ]),\n", + " array([ 0.77897723, -1.57465215, -5.66418407, 10.18405575]),\n", + " array([ 0.72461347, -1.47493915, -5.43637616, 9.97129959]),\n", + " array([ 0.67237988, -1.37754791, -5.2233597 , 9.73912421]),\n", + " array([ 0.62216084, -1.28262911, -5.02190358, 9.49188063]),\n", + " array([ 0.57386616, -1.19030196, -4.82946752, 9.23271423]),\n", + " array([ 0.52742594, -1.10066358, -4.64402279, 8.96383822]),\n", + " array([ 0.48278681, -1.01379619, -4.46391262, 8.68673947]),\n", + " array([ 0.43990935, -0.92977287, -4.28774576, 8.4023312 ]),\n", + " array([ 0.39876619, -0.84866222, -4.11431636, 8.11106554]),\n", + " array([ 0.35934075, -0.77053205, -3.94254392, 7.81301681]),\n", + " array([ 0.32162647, -0.69545262, -3.77142845, 7.50794347]),\n", + " array([ 0.2856263 , -0.62349927, -3.60001688, 7.19533445]),\n", + " array([ 0.25135252, -0.55475483, -3.42737784, 6.87444438]),\n", + " array([ 0.21882669, -0.48931162, -3.25258257, 6.54432038]),\n", + " array([ 0.18807979, -0.4272734 , -3.07469029, 6.20382277]),\n", + " array([ 0.15915242, -0.36875699, -2.89273681, 5.85164091]),\n", + " array([ 0.13209517, -0.31389394, -2.70572535, 5.48630528]),\n", + " array([ 0.10696898, -0.26283197, -2.51261882, 5.10619635]),\n", + " array([ 0.08384565, -0.21573647, -2.31233305, 4.70955049]),\n", + " array([ 0.06280835, -0.17279183, -2.10373031, 4.29446332]),\n", + " array([ 0.04395222, -0.13420293, -1.88561292, 3.85889028]),\n", + " array([ 0.02738505, -0.10019648, -1.65671656, 3.40064469]),\n", + " array([ 0.01322802, -0.07102255, -1.41570311, 2.9173932 ]),\n", + " array([ 1.61648865e-03, -4.69560594e-02, -1.16115315e+00, 2.40664923e+00]),\n", + " array([-0.00729909, -0.02829841, -0.89155834, 1.8657649 ]),\n", + " array([-0.01335224, -0.01537918, -0.60531424, 1.29192311]),\n", + " array([-0.01635939, -0.00855786, -0.30071499, 0.68213222]),\n", + " array([-0.01611896, -0.00822546, 0.02404236, 0.0332393 ]),\n", + " array([-0.01586976, -0.00809705, 0.02492077, 0.01284125])],\n", + " [array([-0.41707646]),\n", + " array([-0.02170737]),\n", + " array([-0.04339122]),\n", + " array([-0.0648834]),\n", + " array([-0.08608215]),\n", + " array([-0.10690607]),\n", + " array([-0.12728865]),\n", + " array([-0.1471792]),\n", + " array([-0.16654242]),\n", + " array([-0.18535661]),\n", + " array([-0.20361061]),\n", + " array([-0.22129935]),\n", + " array([-0.23841816]),\n", + " array([-0.25495599]),\n", + " array([-0.2708876]),\n", + " array([-0.28616509]),\n", + " array([-0.30070897]),\n", + " array([-0.31439943]),\n", + " array([-0.32706846]),\n", + " array([-0.33849408]),\n", + " array([-0.34839825]),\n", + " array([-0.35645082]),\n", + " array([-0.36228266]),\n", + " array([-0.36551154]),\n", + " array([-0.36578462]),\n", + " array([-0.3628392]),\n", + " array([-0.35657906]),\n", + " array([-0.34715352]),\n", + " array([-0.33501282]),\n", + " array([-0.3209003]),\n", + " array([-0.3057432]),\n", + " array([-0.29043464]),\n", + " array([-0.27556084]),\n", + " array([-0.26118707]),\n", + " array([-0.24681685]),\n", + " array([-0.23155711]),\n", + " array([-0.21440559]),\n", + " array([-0.1945173]),\n", + " array([-0.17134315]),\n", + " array([-0.14462498]),\n", + " array([-0.11430477]),\n", + " array([-0.08042371]),\n", + " array([-0.04306246]),\n", + " array([-0.00233745]),\n", + " array([0.04155742]),\n", + " array([0.08828425]),\n", + " array([0.13729058]),\n", + " array([0.18775363]),\n", + " array([0.23855843]),\n", + " array([0.28833118]),\n", + " array([0.33554962]),\n", + " array([0.37874429]),\n", + " array([0.41677778]),\n", + " array([0.44913954]),\n", + " array([0.47613118]),\n", + " array([0.49877613]),\n", + " array([0.51832363]),\n", + " array([0.53537355]),\n", + " array([0.54891868]),\n", + " array([0.5558848]),\n", + " array([0.55180838]),\n", + " array([0.53280114]),\n", + " array([0.4979058]),\n", + " array([0.45020253]),\n", + " array([0.39572084]),\n", + " array([0.34097874]),\n", + " array([0.29089296]),\n", + " array([0.24804139]),\n", + " array([0.21303479]),\n", + " array([0.18528331]),\n", + " array([0.16366372]),\n", + " array([0.14693796]),\n", + " array([0.13396035]),\n", + " array([0.12375473]),\n", + " array([0.11552599]),\n", + " array([0.10864418]),\n", + " array([0.10262018]),\n", + " array([0.09708141]),\n", + " array([0.09175015]),\n", + " array([0.0864254]),\n", + " array([0.08096782]),\n", + " array([0.0752874]),\n", + " array([0.06933347]),\n", + " array([0.0630865]),\n", + " array([0.05655164]),\n", + " array([0.04975356]),\n", + " array([0.04273255]),\n", + " array([0.0355416]),\n", + " array([0.02824436]),\n", + " array([0.02091378]),\n", + " array([0.01363134]),\n", + " array([0.00648661]),\n", + " array([-0.00042301]),\n", + " array([-0.0069925]),\n", + " array([-0.01310974]),\n", + " array([-0.0186566]),\n", + " array([-0.02351091]),\n", + " array([-0.02754985]),\n", + " array([-0.03065489]),\n", + " array([-0.00059534])],\n", + " True)" + ] + }, + "execution_count": 25, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Creating the DDP solver for this OC problem, defining a logger\n", + "ddp = SolverFDDP(problem)\n", + "ddp.callback = [CallbackDDPVerbose()]\n", + "ddp.callback.append(CallbackDDPLogger())\n", + "\n", + "#us0 = np.zeros([T,1])\n", + "us0 = ddp.us\n", + "xs0 = [problem.initialState+0.1]*len(ddp.models())\n", + "\n", + "ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n", + "#ddp.solve(maxiter=150)" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [], + "source": [ + "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "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": 35, + "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": 31, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<matplotlib.legend.Legend at 0x7f46c17e2650>" + ] + }, + "execution_count": 31, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "<Figure size 1080x720 with 2 Axes>" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "control = np.vstack(ddp.us)\n", + "t = np.arange(0,T*dt, dt)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('Motor torques')\n", + "# axs[0].plot(t,control[:,0], t,control[:,1])\n", + "axs[0].plot(t,control[:,0])\n", + "axs[0].set_title('Moments')\n", + "axs[0].legend(['M1','M2'])\n", + "\n", + "t_state = np.append(t, t[-1]+dt)\n", + "state = np.vstack(ddp.xs)\n", + "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", + "fig.suptitle('States')\n", + "axs[0].plot(t_state,state[:,0], t_state, state[:,1])\n", + "axs[0].set_title('Position')\n", + "axs[0].legend(['Link 1','Link2'])\n", + "axs[1].plot(t_state,state[:,2], t_state, state[:,3])\n", + "axs[1].set_title('Vels')\n", + "axs[1].legend(['Link 1','Link2'])" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.16" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/notebooks/borinot_arm.ipynb b/examples/notebooks/borinot_arm.ipynb deleted file mode 100644 index 2159b523293176b99817040f581f8e26148fdf27..0000000000000000000000000000000000000000 --- a/examples/notebooks/borinot_arm.ipynb +++ /dev/null @@ -1,620 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [], - "source": [ - "from crocoddyl import *\n", - "import pinocchio as pin\n", - "import numpy as np\n", - "\n", - "robot = loadBorinotArm()\n", - "robot.initViewer(loadModel=True)\n", - "\n", - "q0 = [3.14, 0]\n", - "robot.q0.flat = q0\n", - "robot.framesForwardKinematics(robot.q0)\n", - "robot.display(robot.q0)\n", - "\n", - "IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)\n", - "IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)\n", - "Mlink1 = robot.data.oMf[IDX_LINK1]\n", - "Mlink2 = robot.data.oMf[IDX_LINK2]\n", - "\n", - "target_pos = np.array([0,0,0.3])\n", - "target_quat = pin.Quaternion(1, 0, 0, 0)\n", - "target_quat.normalize()\n", - "\n", - "Mref = pin.SE3()\n", - "Mref.translation = target_pos.reshape(3,1)\n", - "Mref.rotation = target_quat.matrix()\n", - "\n", - "#robot.viewer.gui.addXYZaxis('world/framelink1', [1., 0., 0., 1.], .005, 0.05)\n", - "#robot.viewer.gui.addXYZaxis('world/framelink2', [1., 0., 0., 1.], .005, 0.05)\n", - "#robot.viewer.gui.addXYZaxis('world/frameref', [1., 0., 0., 1.], .005, 0.05)\n", - "\n", - "#robot.viewer.gui.applyConfiguration('world/framelink1', pin.se3ToXYZQUATtuple(Mlink1))\n", - "#robot.viewer.gui.applyConfiguration('world/framelink2', pin.se3ToXYZQUATtuple(Mlink2))\n", - "#robot.viewer.gui.applyConfiguration('world/frameref', pin.se3ToXYZQUATtuple(Mref))\n", - "\n", - "robot.viewer.gui.refresh()" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [], - "source": [ - "import time \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,1])\n", - "q_dd = np.zeros([2,1])" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "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, 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", - " 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": 31, - "metadata": {}, - "outputs": [], - "source": [ - "state = StatePinocchio(robot.model)\n", - "\n", - "xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)\n", - "uRegCost = CostModelControl(robot.model, nu = 1)\n", - "xPendCost = CostModelDoublePendulum(robot.model, \n", - " frame=state, \n", - " ref=state.zero, \n", - " nu=1,\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-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": 32, - "metadata": {}, - "outputs": [], - "source": [ - "actModel = ActuationModelDoublePendulum(robot.model)\n", - "runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))\n", - "terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))" - ] - }, - { - "cell_type": "code", - "execution_count": 33, - "metadata": {}, - "outputs": [], - "source": [ - "# Defining the time duration for running action models and the terminal one\n", - "dt = 1e-2\n", - "runningModel.timeStep = dt\n", - "\n", - "T = 100\n", - "x0 = np.array([3.14, 0, 0., 0. ])\n", - "problem = ShootingProblem(x0, [runningModel] * T, terminalModel)" - ] - }, - { - "cell_type": "code", - "execution_count": 34, - "metadata": { - "scrolled": false - }, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\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", - " 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", - " 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", - " 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", - " 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" - ] - }, - { - "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": [ - "# Creating the DDP solver for this OC problem, defining a logger\n", - "ddp = SolverFDDP(problem)\n", - "ddp.callback = [CallbackDDPVerbose()]\n", - "ddp.callback.append(CallbackDDPLogger())\n", - "\n", - "us0 = np.zeros([T,1])\n", - "us0 = us0 + 4\n", - "xs0 = [problem.initialState+0.1]*len(ddp.models())\n", - "\n", - "#ddp.solve(init_xs=xs0,init_us=us0,maxiter=100)\n", - "ddp.solve(maxiter=150)" - ] - }, - { - "cell_type": "code", - "execution_count": 36, - "metadata": {}, - "outputs": [], - "source": [ - "displayTrajectory(robot, ddp.xs, runningModel.timeStep)" - ] - }, - { - "cell_type": "code", - "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 0x7f5c45cd9b90>" - ] - }, - "execution_count": 37, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "<matplotlib.figure.Figure at 0x7f5c75ef6dd0>" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "<matplotlib.figure.Figure at 0x7f5c75e957d0>" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "\n", - "control = np.vstack(ddp.us)\n", - "t = np.arange(0,T*dt, dt)\n", - "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", - "fig.suptitle('Motor torques')\n", - "# axs[0].plot(t,control[:,0], t,control[:,1])\n", - "axs[0].plot(t,control[:,0])\n", - "axs[0].set_title('Moments')\n", - "axs[0].legend(['M1','M2'])\n", - "\n", - "t_state = np.append(t, t[-1]+dt)\n", - "state = np.vstack(ddp.xs)\n", - "fig, axs = plt.subplots(1,2, figsize=(15,10))\n", - "fig.suptitle('States')\n", - "axs[0].plot(t_state,state[:,0], t_state, state[:,1])\n", - "axs[0].set_title('Position')\n", - "axs[0].legend(['Link 1','Link2'])\n", - "axs[1].plot(t_state,state[:,2], t_state, state[:,3])\n", - "axs[1].set_title('Vels')\n", - "axs[1].legend(['Link 1','Link2'])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "H = np.zeros([6, 4])\n", - "c1 = 1\n", - "c2 = 1\n", - "s1 = 0\n", - "s2 = 0\n", - "H[:2,:2] = np.diag([c1**2-s1**2, c2**2-s2**2])\n", - "H[2:4,:2] = np.diag([s1**2+(1-c1)*c1, s2**2+(1-c2)*c2])\n", - "H[4:6,2:4] = np.diag([1,1])\n", - "weights = np.array([10]*4 + [0.1]*2)\n", - "Axx = weights[:, None]\n", - "Lxx = np.dot(H.T, Axx)\n", - "Lxx\n", - "L = np.zeros([4,4])\n", - "L[:,:] = np.diag([Lxx[0,0], Lxx[1,0], Lxx[2,0], Lxx[3,0]])\n", - "L" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 2", - "language": "python", - "name": "python2" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 2 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.12" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/examples/notebooks/kinton_flying_ee.ipynb b/examples/notebooks/kinton_flying_ee.ipynb index 2b178b5473fadce6ab482ef73e7011e67c501258..63b5c5fc9008710fc84a3e43237ad15965c9e2cb 100644 --- a/examples/notebooks/kinton_flying_ee.ipynb +++ b/examples/notebooks/kinton_flying_ee.ipynb @@ -520,7 +520,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4,