Skip to content
Snippets Groups Projects
Commit f1b84540 authored by Pep Martí Saumell's avatar Pep Martí Saumell
Browse files

"conflict possible"

parent e4133f1f
No related branches found
No related tags found
No related merge requests found
......@@ -13,12 +13,12 @@ class ActuationModelDoublePendulum:
self.actLink = actLink
def calc(self, data, x, u):
S = np.zeros([self.nv,self.nu])
S = np.zeros([self.nv, self.nu])
if self.actLink == 1:
S[0] = 1
else:
S[1] = 1
data.a[:] = np.dot(S,u)
data.a[:] = np.dot(S, u)
return data.a
def calcDiff(self, data, x, u, recalc=True):
......@@ -29,6 +29,7 @@ class ActuationModelDoublePendulum:
def createData(self, pinocchioData):
return ActuationDataDoublePendulum(self, pinocchioData)
class ActuationDataDoublePendulum:
def __init__(self, model, pinocchioData):
self.pinocchio = pinocchioData
......@@ -38,9 +39,9 @@ class ActuationDataDoublePendulum:
self.Ax = self.A[:, :ndx]
self.Au = self.A[:, ndx:]
if model.actLink == 1:
self.Au[0,0] = 1
self.Au[0, 0] = 1
else:
self.Au[1,0] = 1
self.Au[1, 0] = 1
class ActuationModelUAM:
......@@ -63,12 +64,11 @@ class ActuationModelUAM:
self.cf = coefF
def calc(self, data, x, u):
# data.a[2:] = u
d, cf, cm = self.d, self.cf, self.cf
S = np.array(np.zeros([self.nv,self.nu]))
S[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
S = np.array(np.zeros([self.nv, self.nu]))
S[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
np.fill_diagonal(S[6:, 4:], 1)
data.a = np.dot(S,u)
data.a = np.dot(S, u)
return data.a
def calcDiff(self, data, x, u, recalc=True):
......@@ -79,6 +79,7 @@ class ActuationModelUAM:
def createData(self, pinocchioData):
return ActuationDataUAM(self, pinocchioData)
class ActuationDataUAM:
def __init__(self, model, pinocchioData):
self.pinocchio = pinocchioData
......@@ -88,9 +89,9 @@ class ActuationDataUAM:
self.A = np.zeros([nv, ndx + nu]) # result of calcDiff
self.Ax = self.A[:, :ndx]
self.Au = self.A[:, ndx:]
self.Au[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]])
self.Au[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
np.fill_diagonal(self.Au[6:, 4:], 1)
#np.fill_diagonal(self.Au[2:, :], 1)
# np.fill_diagonal(self.Au[2:, :], 1)
# This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment
# [ 0, 0, 0, 0]
# [ 0, 0, 0, 0]
......@@ -105,6 +106,7 @@ class ActuationModelFreeFloating:
This model transforms an actuation u into a joint torque tau.
We implement here the simplest model: tau = S.T*u, where S is constant.
'''
def __init__(self, pinocchioModel):
self.pinocchio = pinocchioModel
if (pinocchioModel.joints[1].shortname() != 'JointModelFreeFlyer'):
......
......@@ -15,6 +15,7 @@ class CostModelPinocchio:
can be retrieved from Pinocchio data, through the calc and calcDiff
functions, respectively.
"""
def __init__(self, pinocchioModel, ncost, withResiduals=True, nu=None):
self.ncost = ncost
self.nq = pinocchioModel.nq
......@@ -40,6 +41,7 @@ class CostDataPinocchio:
It stores the data corresponting to the CostModelPinocchio class.
"""
def __init__(self, model, pinocchioData):
ncost, nv, ndx, nu = model.ncost, model.nv, model.ndx, model.nu
self.pinocchio = pinocchioData
......@@ -70,6 +72,7 @@ class CostDataPinocchio:
class CostModelNumDiff(CostModelPinocchio):
""" Abstract cost model that uses NumDiff for derivative computation.
"""
def __init__(self, costModel, State, withGaussApprox=False, reevals=[]):
'''
reevals is a list of lambdas of (pinocchiomodel,pinocchiodata,x,u) to be
......
......@@ -4,6 +4,7 @@ import pinocchio
from .state import StatePinocchio, StateVector
from .utils import EPS, a2m, m2a, randomOrthonormalMatrix
class DifferentialActionModelAbstract:
""" Abstract class for the differential action model.
......@@ -13,6 +14,7 @@ class DifferentialActionModelAbstract:
the dynamics, cost functions and their derivatives. These computations are
mainly carry on inside calc() and calcDiff(), respectively.
"""
def __init__(self, nq, nv, nu):
self.nq = nq
self.nv = nv
......
%% Cell type:code id: tags:
``` python
from crocoddyl import *
import pinocchio as pin
import numpy as np
robot = loadBorinotArm()
robot.initViewer(loadModel=True)
q0 = [3.14, 0]
robot.q0.flat = q0
robot.framesForwardKinematics(robot.q0)
robot.display(robot.q0)
IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)
IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)
Mlink1 = robot.data.oMf[IDX_LINK1]
Mlink2 = robot.data.oMf[IDX_LINK2]
target_pos = np.array([0,0,0.3])
target_quat = pin.Quaternion(1, 0, 0, 0)
target_quat.normalize()
Mref = pin.SE3()
Mref.translation = target_pos.reshape(3,1)
Mref.rotation = target_quat.matrix()
robot.viewer.gui.refresh()
```
%% Cell type:code id: tags:
``` python
state = StatePinocchio(robot.model)
xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)
uRegCost = CostModelControl(robot.model, nu = 1)
xPendCost = CostModelDoublePendulum(robot.model,
frame=state,
ref=state.zero,
nu=1,
activation=ActivationModelWeightedQuad(np.array([1,1,1,1]+[0.1]*2)))
runningCostModel = CostModelSum(robot.model, nu=1)
terminalCostModel = CostModelSum(robot.model, nu=1)
# runningCostModel.addCost(name="regx", weight=1e-6, cost=xRegCost)
runningCostModel.addCost(name="regu", weight=1e-3, cost=uRegCost)
runningCostModel.addCost(name="pend", weight=1, cost=xPendCost)
terminalCostModel.addCost(name="ori2", weight=1e5, cost=xPendCost)
```
%% Cell type:code id: tags:
``` python
actModel = ActuationModelDoublePendulum(robot.model, actLink = 1)
runningModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, runningCostModel))
terminalModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, terminalCostModel))
```
%% Cell type:code id: tags:
``` python
# Defining the time duration for running action models and the terminal one
dt = 1e-2
runningModel.timeStep = dt
T = 100
x0 = np.array([3.14, 0, 0., 0. ])
problem = ShootingProblem(x0, [runningModel] * T, terminalModel)
```
%% Cell type:code id: tags:
``` python
# Creating the DDP solver for this OC problem, defining a logger
ddp = SolverFDDP(problem)
ddp.callback = [CallbackDDPVerbose()]
ddp.callback.append(CallbackDDPLogger())
us0 = np.zeros([T,1])
#us0 = ddp.us
xs0 = [problem.initialState+0.1]*len(ddp.models())
ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)
#ddp.solve(maxiter=150)
```
%% Output
iter cost stop grad xreg ureg step feas
0 2.00251e+05 2.49231e+09 -2.00919e+04 1.00000e+03 1.00000e+03 0.5000 0
1 2.00219e+05 6.36115e+08 -5.07140e+03 1.00000e+03 1.00000e+03 0.5000 0
2 2.00207e+05 1.61402e+08 -1.25930e+03 1.00000e+03 1.00000e+03 0.5000 0
3 2.00202e+05 4.15162e+07 -3.08384e+02 1.00000e+03 1.00000e+03 0.5000 0
4 2.00200e+05 1.10519e+07 -7.35331e+01 1.00000e+03 1.00000e+03 0.5000 0
5 2.00200e+05 3.15617e+06 -1.63488e+01 1.00000e+03 1.00000e+03 0.5000 0
6 2.00199e+05 1.03152e+06 -2.80766e+00 1.00000e+03 1.00000e+03 0.5000 0
7 2.00199e+05 4.24028e+05 1.43417e+00 1.00000e+02 1.00000e+02 1.0000 1
8 2.00198e+05 1.23707e+05 7.82398e-01 1.00000e+02 1.00000e+02 1.0000 1
9 2.00197e+05 1.44061e+05 9.11869e-01 1.00000e+02 1.00000e+02 1.0000 1
iter cost stop grad xreg ureg step feas
10 2.00196e+05 1.75495e+05 1.11113e+00 1.00000e+02 1.00000e+02 1.0000 1
11 2.00194e+05 2.20187e+05 1.39435e+00 1.00000e+02 1.00000e+02 1.0000 1
12 2.00192e+05 2.81390e+05 1.78217e+00 1.00000e+02 1.00000e+02 1.0000 1
13 2.00190e+05 3.63597e+05 2.30309e+00 1.00000e+02 1.00000e+02 1.0000 1
14 2.00187e+05 4.72875e+05 2.99561e+00 1.00000e+02 1.00000e+02 1.0000 1
15 2.00183e+05 6.17300e+05 3.91099e+00 1.00000e+02 1.00000e+02 1.0000 1
16 2.00177e+05 8.07554e+05 5.11708e+00 1.00000e+02 1.00000e+02 1.0000 1
17 2.00170e+05 1.05770e+06 6.70327e+00 1.00000e+02 1.00000e+02 1.0000 1
18 2.00160e+05 1.38620e+06 8.78711e+00 1.00000e+02 1.00000e+02 1.0000 1
19 2.00148e+05 1.81727e+06 1.15229e+01 1.00000e+02 1.00000e+02 1.0000 1
iter cost stop grad xreg ureg step feas
20 2.00132e+05 2.38258e+06 1.51129e+01 1.00000e+02 1.00000e+02 1.0000 1
21 2.00111e+05 3.12354e+06 1.98223e+01 1.00000e+02 1.00000e+02 1.0000 1
22 2.00083e+05 4.09415e+06 2.59981e+01 1.00000e+02 1.00000e+02 1.0000 1
23 2.00046e+05 5.36473e+06 3.40939e+01 1.00000e+02 1.00000e+02 1.0000 1
24 1.99998e+05 7.02658e+06 4.47026e+01 1.00000e+02 1.00000e+02 1.0000 1
25 1.99935e+05 9.19784e+06 5.85970e+01 1.00000e+02 1.00000e+02 1.0000 1
26 1.99853e+05 1.20307e+07 7.67828e+01 1.00000e+02 1.00000e+02 1.0000 1
27 1.99745e+05 1.57200e+07 1.00566e+02 1.00000e+02 1.00000e+02 1.0000 1
28 1.99604e+05 2.05133e+07 1.31634e+02 1.00000e+02 1.00000e+02 1.0000 1
29 1.99420e+05 2.67219e+07 1.72161e+02 1.00000e+02 1.00000e+02 1.0000 1
iter cost stop grad xreg ureg step feas
30 1.99178e+05 3.47316e+07 2.24929e+02 1.00000e+02 1.00000e+02 1.0000 1
31 1.98864e+05 4.50114e+07 2.93468e+02 1.00000e+02 1.00000e+02 1.0000 1
32 1.98455e+05 5.81166e+07 3.82212e+02 1.00000e+02 1.00000e+02 1.0000 1
33 1.97923e+05 7.46804e+07 4.96646e+02 1.00000e+02 1.00000e+02 1.0000 1
34 1.97235e+05 9.53860e+07 6.43430e+02 1.00000e+02 1.00000e+02 1.0000 1
35 1.96347e+05 1.20909e+08 8.30429e+02 1.00000e+02 1.00000e+02 1.0000 1
36 1.95208e+05 1.51819e+08 1.06660e+03 1.00000e+02 1.00000e+02 1.0000 1
37 1.93756e+05 1.88436e+08 1.36160e+03 1.00000e+02 1.00000e+02 1.0000 1
38 1.91919e+05 2.30651e+08 1.72507e+03 1.00000e+02 1.00000e+02 1.0000 1
39 1.89618e+05 2.77749e+08 2.16542e+03 1.00000e+02 1.00000e+02 1.0000 1
iter cost stop grad xreg ureg step feas
40 1.52107e+05 1.19024e+10 7.99311e+05 1.00000e+02 1.00000e+02 0.0312 1
41 1.04287e+05 2.47125e+09 9.87329e+04 1.00000e+01 1.00000e+01 1.0000 1
42 6.84717e+04 5.83726e+09 1.92524e+05 1.00000e+01 1.00000e+01 0.2500 1
43 5.54649e+04 6.51313e+09 1.22500e+05 1.00000e+01 1.00000e+01 0.5000 1
44 2.16775e+04 5.33861e+10 1.01503e+05 1.00000e+01 1.00000e+01 0.5000 1
45 6.00681e+03 1.37814e+10 3.79650e+04 1.00000e+00 1.00000e+00 1.0000 1
46 2.19039e+03 1.66324e+06 1.07710e+04 1.00000e+00 1.00000e+00 0.5000 1
47 5.48511e+02 7.68537e+05 3.28492e+03 1.00000e-01 1.00000e-01 1.0000 1
48 4.66669e+02 5.26506e+04 2.00445e+02 1.00000e-01 1.00000e-01 0.5000 1
49 4.26123e+02 1.19294e+04 9.27419e+01 1.00000e-01 1.00000e-01 0.5000 1
iter cost stop grad xreg ureg step feas
50 4.02336e+02 8.75391e+03 5.26777e+01 1.00000e-01 1.00000e-01 0.5000 1
51 3.95506e+02 6.51720e+03 3.41902e+01 1.00000e-01 1.00000e-01 0.2500 1
52 3.90174e+02 3.77447e+03 3.02021e+01 1.00000e-01 1.00000e-01 0.2500 1
53 3.84577e+02 2.19823e+03 2.71642e+01 1.00000e-01 1.00000e-01 0.5000 1
54 3.75302e+02 5.68460e+02 2.75948e+01 1.00000e-01 1.00000e-01 0.5000 1
55 3.68301e+02 2.13517e+02 1.92654e+01 1.00000e-01 1.00000e-01 0.5000 1
56 3.65215e+02 1.11803e+02 1.30171e+01 1.00000e-02 1.00000e-02 1.0000 1
57 3.61628e+02 1.36622e+02 2.03598e+01 1.00000e-02 1.00000e-02 0.2500 1
58 3.59448e+02 1.24390e+02 1.60325e+01 1.00000e-03 1.00000e-03 1.0000 1
59 3.56167e+02 2.19222e+02 2.09220e+01 1.00000e-03 1.00000e-03 0.5000 1
iter cost stop grad xreg ureg step feas
60 3.51001e+02 9.11162e+02 1.73022e+01 1.00000e-03 1.00000e-03 0.5000 1
61 3.46090e+02 2.28356e+02 9.54641e+00 1.00000e-04 1.00000e-04 1.0000 1
62 3.43280e+02 2.71194e+01 4.10627e+00 1.00000e-05 1.00000e-05 1.0000 1
63 3.41468e+02 7.65346e+01 2.03785e+00 1.00000e-06 1.00000e-06 1.0000 1
64 3.39961e+02 6.75324e+01 1.53178e+00 1.00000e-07 1.00000e-07 1.0000 1
65 3.38531e+02 1.08191e+01 1.42259e+00 1.00000e-08 1.00000e-08 1.0000 1
66 3.37121e+02 9.26116e+00 1.38538e+00 1.00000e-09 1.00000e-09 1.0000 1
67 3.35688e+02 9.42177e+00 1.39556e+00 1.00000e-09 1.00000e-09 1.0000 1
68 3.34205e+02 9.40791e+00 1.43652e+00 1.00000e-09 1.00000e-09 1.0000 1
69 3.32659e+02 9.67683e+00 1.49385e+00 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
70 3.31050e+02 9.94176e+00 1.55426e+00 1.00000e-09 1.00000e-09 1.0000 1
71 3.29398e+02 1.00794e+01 1.60111e+00 1.00000e-09 1.00000e-09 1.0000 1
72 3.27739e+02 9.96503e+00 1.61612e+00 1.00000e-09 1.00000e-09 1.0000 1
73 3.26128e+02 9.50706e+00 1.58267e+00 1.00000e-09 1.00000e-09 1.0000 1
74 3.24627e+02 8.67890e+00 1.49097e+00 1.00000e-09 1.00000e-09 1.0000 1
75 3.23291e+02 7.54031e+00 1.34281e+00 1.00000e-09 1.00000e-09 1.0000 1
76 3.22161e+02 6.22333e+00 1.15245e+00 1.00000e-09 1.00000e-09 1.0000 1
77 3.21249e+02 4.88773e+00 9.42434e-01 1.00000e-09 1.00000e-09 1.0000 1
78 3.20545e+02 3.66962e+00 7.36308e-01 1.00000e-09 1.00000e-09 1.0000 1
79 3.20023e+02 2.65008e+00 5.52115e-01 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
80 3.19649e+02 1.85335e+00 3.99546e-01 1.00000e-09 1.00000e-09 1.0000 1
81 3.19389e+02 1.26320e+00 2.80640e-01 1.00000e-09 1.00000e-09 1.0000 1
82 3.19212e+02 8.43751e-01 1.92351e-01 1.00000e-09 1.00000e-09 1.0000 1
83 3.19094e+02 5.54803e-01 1.29252e-01 1.00000e-09 1.00000e-09 1.0000 1
84 3.19016e+02 3.60420e-01 8.54864e-02 1.00000e-09 1.00000e-09 1.0000 1
85 3.18965e+02 2.31964e-01 5.58319e-02 1.00000e-09 1.00000e-09 1.0000 1
86 3.18932e+02 1.48221e-01 3.61020e-02 1.00000e-09 1.00000e-09 1.0000 1
87 3.18911e+02 9.41830e-02 2.31609e-02 1.00000e-09 1.00000e-09 1.0000 1
88 3.18898e+02 5.95885e-02 1.47664e-02 1.00000e-09 1.00000e-09 1.0000 1
89 3.18890e+02 3.75740e-02 9.36834e-03 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
90 3.18884e+02 2.36308e-02 5.92065e-03 1.00000e-09 1.00000e-09 1.0000 1
91 3.18881e+02 1.48311e-02 3.73036e-03 1.00000e-09 1.00000e-09 1.0000 1
92 3.18879e+02 9.29344e-03 2.34470e-03 1.00000e-09 1.00000e-09 1.0000 1
93 3.18877e+02 5.81606e-03 1.47096e-03 1.00000e-09 1.00000e-09 1.0000 1
94 3.18877e+02 3.63627e-03 9.21431e-04 1.00000e-09 1.00000e-09 1.0000 1
95 3.18876e+02 2.27165e-03 5.76518e-04 1.00000e-09 1.00000e-09 1.0000 1
96 3.18876e+02 1.41829e-03 3.60379e-04 1.00000e-09 1.00000e-09 1.0000 1
97 3.18876e+02 8.85065e-04 2.25106e-04 1.00000e-09 1.00000e-09 1.0000 1
98 3.18876e+02 5.52110e-04 1.40528e-04 1.00000e-09 1.00000e-09 1.0000 1
99 3.18875e+02 3.44304e-04 8.76879e-05 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
100 3.18875e+02 2.14665e-04 5.46966e-05 1.00000e-09 1.00000e-09 1.0000 1
101 3.18875e+02 1.33812e-04 3.41081e-05 1.00000e-09 1.00000e-09 1.0000 1
102 3.18875e+02 8.34004e-05 2.12646e-05 1.00000e-09 1.00000e-09 1.0000 1
103 3.18875e+02 5.19741e-05 1.32550e-05 1.00000e-09 1.00000e-09 1.0000 1
104 3.18875e+02 3.23871e-05 8.26115e-06 1.00000e-09 1.00000e-09 1.0000 1
105 3.18875e+02 2.01800e-05 5.14819e-06 1.00000e-09 1.00000e-09 1.0000 1
106 3.18875e+02 1.25733e-05 3.20797e-06 1.00000e-09 1.00000e-09 1.0000 1
107 3.18875e+02 7.83347e-06 1.99883e-06 1.00000e-09 1.00000e-09 1.0000 1
108 3.18875e+02 4.88032e-06 1.24537e-06 1.00000e-09 1.00000e-09 1.0000 1
109 3.18875e+02 3.04036e-06 7.75895e-07 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
110 3.18875e+02 1.89408e-06 4.83384e-07 1.00000e-09 1.00000e-09 1.0000 1
111 3.18875e+02 1.17993e-06 3.01141e-07 1.00000e-09 1.00000e-09 1.0000 1
112 3.18875e+02 7.35050e-07 1.87602e-07 1.00000e-09 1.00000e-09 1.0000 1
113 3.18875e+02 4.57895e-07 1.16869e-07 1.00000e-09 1.00000e-09 1.0000 1
114 3.18875e+02 2.85244e-07 7.28040e-08 1.00000e-09 1.00000e-09 1.0000 1
115 3.18875e+02 1.77689e-07 4.53530e-08 1.00000e-09 1.00000e-09 1.0000 1
116 3.18875e+02 1.10689e-07 2.82523e-08 1.00000e-09 1.00000e-09 1.0000 1
117 3.18875e+02 6.89515e-08 1.75994e-08 1.00000e-09 1.00000e-09 1.0000 1
118 3.18875e+02 4.29523e-08 1.09633e-08 1.00000e-09 1.00000e-09 1.0000 1
119 3.18875e+02 2.67560e-08 6.82939e-09 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
120 3.18875e+02 1.66672e-08 4.25423e-09 1.00000e-09 1.00000e-09 1.0000 1
121 3.18875e+02 1.03824e-08 2.65008e-09 1.00000e-09 1.00000e-09 1.0000 1
122 3.18875e+02 6.46749e-09 1.65081e-09 1.00000e-09 1.00000e-09 1.0000 1
123 3.18875e+02 4.02873e-09 1.02833e-09 1.00000e-09 1.00000e-09 1.0000 1
124 3.18875e+02 2.50961e-09 6.40576e-10 1.00000e-09 1.00000e-09 1.0000 1
125 3.18875e+02 1.56329e-09 3.99031e-10 1.00000e-09 1.00000e-09 1.0000 1
126 3.18875e+02 9.73817e-10 2.48566e-10 1.00000e-09 1.00000e-09 1.0000 1
([array([3.14, 0. , 0. , 0. ]),
array([ 3.17269079, -0.05672873, 3.26907942, -5.6728731 ]),
array([ 3.20808333, -0.11791405, 3.53925368, -6.11853221]),
array([ 3.24602991, -0.18303993, 3.79465829, -6.51258806]),
array([ 3.28631146, -0.25143034, 4.02815487, -6.83904043]),
array([ 3.32863628, -0.32225426, 4.23248143, -7.08239242]),
array([ 3.37265336, -0.39456111, 4.40170846, -7.23068519]),
array([ 3.41797962, -0.46734364, 4.53262634, -7.27825265]),
array([ 3.46423776, -0.53961941, 4.62581357, -7.22757736]),
array([ 3.51109735, -0.6105138 , 4.68595932, -7.08943814]),
array([ 3.55831017, -0.67932569, 4.72128149, -6.8811892 ]),
array([ 3.60573282, -0.74556377, 4.74226543, -6.62380789]),
array([ 3.65333474, -0.80895137, 4.76019217, -6.33875985]),
array([ 3.70119372, -0.86940691, 4.78589762, -6.04555448]),
array([ 3.74948362, -0.92701044, 4.82898998, -5.76035323]),
array([ 3.79845891, -0.98196575, 4.89752875, -5.49553029]),
array([ 3.84843933, -1.03456439, 4.99804218, -5.25986456]),
array([ 3.89979668, -1.08515473, 5.13573525, -5.0590335 ]),
array([ 3.95294438, -1.13411643, 5.31476949, -4.89617035]),
array([ 4.00832974, -1.18183989, 5.53853623, -4.77234634]),
array([ 4.06642848, -1.228709 , 5.80987453, -4.68691048]),
array([ 4.12774046, -1.27508556, 6.13119769, -4.63765658]),
array([ 4.19278536, -1.32129356, 6.50448952, -4.62080012]),
array([ 4.26209653, -1.36760105, 6.93111689, -4.63074879]),
array([ 4.33621036, -1.41419757, 7.4113833 , -4.65965185]),
array([ 4.41564764, -1.46116489, 7.94372822, -4.69673219]),
array([ 4.50088242, -1.5084395 , 8.52347822, -4.72746088]),
array([ 4.5922936 , -1.55576706, 9.14111733, -4.73275575]),
array([ 4.69009581, -1.60265295, 9.78022093, -4.68858863]),
array([ 4.79425117, -1.64831927, 10.4155366 , -4.56663234]),
array([ 4.90437268, -1.69168637, 11.01215056, -4.33671047]),
array([ 5.01964264, -1.73140172, 11.5269963 , -3.97153451]),
array([ 5.13877937, -1.76593439, 11.91367256, -3.45326678]),
array([ 5.26008215, -1.7937347 , 12.13027836, -2.78003127]),
array([ 5.38156319, -1.81343007, 12.14810364, -1.96953707]),
array([ 5.50114158, -1.82400622, 11.95783944, -1.05761538]),
array([ 5.61684922, -1.82492397, 11.5707639 , -0.09177474]),
array([ 5.72699763, -1.81614718, 11.01484098, 0.87767905]),
array([ 5.83027723, -1.79809077, 10.32795985, 1.80564127]),
array([ 5.92578803, -1.7715189 , 9.55108061, 2.65718651]),
array([ 6.01301839, -1.73742662, 8.72303556, 3.40922815]),
array([ 6.09179257, -1.69692901, 7.87741826, 4.04976071]),
array([ 6.16220473, -1.65117055, 7.04121621, 4.57584654]),
array([ 6.22455115, -1.60125824, 6.23464168, 4.99123066]),
array([ 6.27926802, -1.54821732, 5.47168691, 5.30409227]),
array([ 6.32687857, -1.49296568, 4.76105501, 5.52516356]),
array([ 6.36795081, -1.43630286, 4.10722369, 5.66628276]),
array([ 6.40306563, -1.37890923, 3.51148212, 5.739363 ]),
array([ 6.43279411, -1.32135205, 2.97284831, 5.7557174 ]),
array([ 6.45768237, -1.2640954 , 2.48882544, 5.72566532]),
array([ 6.47824228, -1.20751194, 2.05599116, 5.65834575]),
array([ 6.49494663, -1.15189522, 1.67043511, 5.56167247]),
array([ 6.50822732, -1.09747143, 1.32806919, 5.44237898]),
array([ 6.51847569, -1.04441029, 1.02483744, 5.30611413]),
array([ 6.5260442 , -0.99283467, 0.75685039, 5.15756167]),
array([ 6.53124884, -0.94282901, 0.52046434, 5.0005659 ]),
array([ 6.53437206, -0.89444648, 0.31232229, 4.83825296]),
array([ 6.53566575, -0.84771506, 0.12936877, 4.67314194]),
array([ 6.53535423, -0.80264263, -0.03115233, 4.50724339]),
array([ 6.53363713, -0.75922118, -0.17171028, 4.34214452]),
array([ 6.53069206, -0.71743036, -0.29450614, 4.17908191]),
array([ 6.52667712, -0.67724034, -0.40149424, 4.01900266]),
array([ 6.52173308, -0.63861418, -0.49440462, 3.86261555]),
array([ 6.51598542, -0.60150985, -0.57476513, 3.71043343]),
array([ 6.5095462 , -0.56588176, -0.64392247, 3.56280839]),
array([ 6.50251558, -0.53168216, -0.70306169, 3.41996069]),
array([ 6.49498334, -0.49886213, -0.75322397, 3.28200254]),
array([ 6.48703012, -0.46737255, -0.79532272, 3.14895766]),
array([ 6.47872854, -0.43716478, -0.83015786, 3.02077728]),
array([ 6.47014425, -0.40819125, -0.8584286 , 2.89735317]),
array([ 6.46133681, -0.38040597, -0.88074464, 2.77852831]),
array([ 6.45236045, -0.35376491, -0.89763601, 2.66410548]),
array([ 6.44326483, -0.32822637, -0.90956179, 2.5538542 ]),
array([ 6.43409565, -0.30375121, -0.91691759, 2.44751625]),
array([ 6.42489523, -0.28030311, -0.92004217, 2.34481002]),
array([ 6.415703 , -0.25784877, -0.91922315, 2.24543385]),
array([ 6.40655598, -0.23635808, -0.91470197, 2.1490686 ]),
array([ 6.3974892 , -0.21580429, -0.90667819, 2.05537938]),
array([ 6.38853607, -0.19616412, -0.89531318, 1.96401677]),
array([ 6.37972873, -0.17741795, -0.88073334, 1.87461745]),
array([ 6.3710984 , -0.1595499 , -0.8630328 , 1.78680438]),
array([ 6.36267565, -0.14254804, -0.84227575, 1.70018653]),
array([ 6.35449066, -0.12640445, -0.81849845, 1.61435828]),
array([ 6.34657355, -0.11111547, -0.79171084, 1.52889842]),
array([ 6.33895457, -0.09668178, -0.76189797, 1.44336888]),
array([ 6.33166436, -0.08310865, -0.72902111, 1.35731313]),
array([ 6.32473418, -0.07040611, -0.69301869, 1.27025431]),
array([ 6.31819611, -0.05858917, -0.65380704, 1.18169312]),
array([ 6.3120833 , -0.04767812, -0.611281 , 1.09110542]),
array([ 6.30643015, -0.03769872, -0.56531434, 0.99793964]),
array([ 6.30127255, -0.02868258, -0.51576021, 0.90161405]),
array([ 6.29664804, -0.02066745, -0.46245145, 0.80151385]),
array([ 6.29259603, -0.01369756, -0.40520096, 0.69698825]),
array([ 6.289158 , -0.00782409, -0.34380213, 0.58734757]),
array([ 6.28637771e+00, -3.10548063e-03, -2.78029552e-01, 4.71860651e-01]),
array([ 6.28430131e+00, 3.92045719e-04, -2.07639902e-01, 3.49752635e-01]),
array([ 6.28297758e+00, 2.59408146e-03, -1.32373435e-01, 2.20203575e-01]),
array([ 6.28245801e+00, 3.41756373e-03, -5.19561254e-02, 8.23482266e-02]),
array([ 6.28279699e+00, 2.77034009e-03, 3.38971527e-02, -6.47223641e-02]),
array([ 6.28405162e+00, 5.51025211e-04, 1.25463523e-01, -2.21931488e-01]),
array([ 6.28403803e+00, 5.43145315e-04, -1.35868553e-03, -7.87989649e-04])],
[array([0.52657293]),
array([0.06560521]),
array([0.0885465]),
array([0.11290929]),
array([0.13787118]),
array([0.16247003]),
array([0.18577947]),
array([0.2071721]),
array([0.226524]),
array([0.24425101]),
array([0.26115843]),
array([0.27819085]),
array([0.29620404]),
array([0.3158346]),
array([0.33747302]),
array([0.36130321]),
array([0.38736589]),
array([0.41561647]),
array([0.44596353]),
array([0.47828332]),
array([0.51240881]),
array([0.54809175]),
array([0.58493384]),
array([0.62228251]),
array([0.65909015]),
array([0.69374912]),
array([0.72394483]),
array([0.74661976]),
array([0.75819647]),
array([0.75521342]),
array([0.73539264]),
array([0.69883682]),
array([0.64869889]),
array([0.59066594]),
array([0.53121548]),
array([0.47548303]),
array([0.42590509]),
array([0.38221238]),
array([0.34243647]),
array([0.3041615]),
array([0.26544407]),
array([0.22523097]),
array([0.18337588]),
array([0.14043259]),
array([0.09737254]),
array([0.05531914]),
array([0.01534388]),
array([-0.02166323]),
array([-0.05505574]),
array([-0.08444135]),
array([-0.10965878]),
array([-0.13073709]),
array([-0.14784897]),
array([-0.16126597]),
array([-0.17131971]),
array([-0.17837078]),
array([-0.18278545]),
array([-0.18491912]),
array([-0.18510568]),
array([-0.18365117]),
array([-0.18083081]),
array([-0.17688831]),
array([-0.17203679]),
array([-0.16646067]),
array([-0.16031807]),
array([-0.15374354]),
array([-0.14685071]),
array([-0.13973501]),
array([-0.13247608]),
array([-0.12514007]),
array([-0.11778163]),
array([-0.11044575]),
array([-0.10316933]),
array([-0.09598252]),
array([-0.08890999]),
array([-0.08197188]),
array([-0.0751847]),
array([-0.06856211]),
array([-0.06211555]),
array([-0.05585477]),
array([-0.04978834]),
array([-0.04392402]),
array([-0.03826915]),
array([-0.03283094]),
array([-0.02761675]),
array([-0.02263432]),
array([-0.01789204]),
array([-0.01339911]),
array([-0.00916576]),
array([-0.00520347]),
array([-0.00152512]),
array([0.00185478]),
array([0.0049199]),
array([0.00765189]),
array([0.01003017]),
array([0.01203174]),
array([0.01363093]),
array([0.01479925]),
array([0.01550285]),
array([-0.02045494])],
True)
%% Cell type:code id: tags:
``` python
displayTrajectory(robot, ddp.xs, runningModel.timeStep)
```
%% Cell type:code id: tags:
``` python
import time
dt = 0.01
t = np.arange(0,1,dt)
q0 = np.array([[3.14,0]]).T
q = q0
q_d = np.zeros([2,1])
q_dd = np.zeros([2,1])
```
%% Cell type:code id: tags:
``` python
nle = np.zeros([2,1])
for i in range(len(t)):
pin.computeAllTerms(robot.model, robot.data, q, q_d)
M = robot.data.M
Minv = np.linalg.inv(M)
r = np.zeros([2,1])
tau = np.zeros([2,1])
tau[0,0] = ddp.us[i]
nle[:,0] = m2a(robot.data.nle)
r[:] = tau - nle
q_dd = np.dot(Minv, r)
q = q + q_d*dt + q_dd*dt**2
q_d = q_d + q_dd*dt
#pin.forwardKinematics(robot.model, robot.data, q, q_d)
robot.display(q)
time.sleep(dt)
```
%% Cell type:code id: tags:
``` python
import numpy as np
import matplotlib.pyplot as plt
control = np.vstack(ddp.us)
t = np.arange(0,T*dt, dt)
fig, axs = plt.subplots(1,2, figsize=(15,10))
fig.suptitle('Motor torques')
# axs[0].plot(t,control[:,0], t,control[:,1])
axs[0].plot(t,control[:,0])
axs[0].set_title('Moments')
axs[0].legend(['M1','M2'])
t_state = np.append(t, t[-1]+dt)
state = np.vstack(ddp.xs)
fig, axs = plt.subplots(1,2, figsize=(15,10))
fig.suptitle('States')
axs[0].plot(t_state,state[:,0], t_state, state[:,1])
axs[0].set_title('Position')
axs[0].legend(['Link 1','Link2'])
axs[1].plot(t_state,state[:,2], t_state, state[:,3])
axs[1].set_title('Vels')
axs[1].legend(['Link 1','Link2'])
```
%% Output
<matplotlib.legend.Legend at 0x7f57076b5390>
......
%% Cell type:code id: tags:
``` python
from crocoddyl import *
import pinocchio as pin
import numpy as np
robot = loadBorinotArm()
robot.initViewer(loadModel=True)
q0 = [3.14, 0]
robot.q0.flat = q0
robot.framesForwardKinematics(robot.q0)
robot.display(robot.q0)
IDX_LINK1 = robot.model.getFrameId('link1', pin.FrameType.BODY)
IDX_LINK2 = robot.model.getFrameId('link2', pin.FrameType.BODY)
Mlink1 = robot.data.oMf[IDX_LINK1]
Mlink2 = robot.data.oMf[IDX_LINK2]
target_pos = np.array([0,0,0.3])
target_quat = pin.Quaternion(1, 0, 0, 0)
target_quat.normalize()
Mref = pin.SE3()
Mref.translation = target_pos.reshape(3,1)
Mref.rotation = target_quat.matrix()
robot.viewer.gui.refresh()
```
%% Cell type:code id: tags:
``` python
state = StatePinocchio(robot.model)
xRegCost = CostModelState(robot.model, state, ref=state.zero(), nu=1)
uRegCost = CostModelControl(robot.model, nu = 1)
xPendCost = CostModelDoublePendulum(robot.model,
frame=state,
ref=state.zero,
nu=1,
activation=ActivationModelWeightedQuad(np.array([1,1,1,1]+[0.1]*2)))
runningCostModel = CostModelSum(robot.model, nu=1)
terminalCostModel = CostModelSum(robot.model, nu=1)
# runningCostModel.addCost(name="regx", weight=1e-6, cost=xRegCost)
runningCostModel.addCost(name="regu", weight=1e-3, cost=uRegCost)
runningCostModel.addCost(name="pend", weight=1, cost=xPendCost)
terminalCostModel.addCost(name="ori2", weight=1e5, cost=xPendCost)
```
%% Cell type:code id: tags:
``` python
actModel = ActuationModelDoublePendulum(robot.model, actLink=2)
runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel))
terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel))
runningModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, runningCostModel))
terminalModel = IntegratedActionModelEuler(DifferentialActionModelActuated(robot.model, actModel, terminalCostModel))
```
%% Cell type:code id: tags:
``` python
# Defining the time duration for running action models and the terminal one
dt = 1e-2
runningModel.timeStep = dt
T = 100
x0 = np.array([3.14, 0, 0., 0. ])
problem = ShootingProblem(x0, [runningModel] * T, terminalModel)
```
%% Cell type:code id: tags:
``` python
# Creating the DDP solver for this OC problem, defining a logger
ddp = SolverFDDP(problem)
ddp.callback = [CallbackDDPVerbose()]
ddp.callback.append(CallbackDDPLogger())
us0 = np.zeros([T,1])
#us0 = ddp.us
xs0 = [problem.initialState+0.1]*len(ddp.models())
ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)
#ddp.solve(maxiter=150)
```
%% Output
iter cost stop grad xreg ureg step feas
0 2.00201e+05 1.16096e+09 9.21968e+01 1.00000e+00 1.00000e+00 1.0000 1
1 2.00200e+05 1.54461e+07 3.14734e+00 1.00000e+00 1.00000e+00 1.0000 1
2 2.00199e+05 1.79399e+03 3.09626e-01 1.00000e+00 1.00000e+00 1.0000 1
3 2.00199e+05 3.39328e+03 5.89887e-01 1.00000e+00 1.00000e+00 1.0000 1
4 2.00197e+05 6.47120e+03 1.12549e+00 1.00000e+00 1.00000e+00 1.0000 1
5 2.00195e+05 1.23441e+04 2.14841e+00 1.00000e+00 1.00000e+00 1.0000 1
6 2.00190e+05 2.35492e+04 4.10323e+00 1.00000e+00 1.00000e+00 1.0000 1
7 2.00180e+05 4.49270e+04 7.84407e+00 1.00000e+00 1.00000e+00 1.0000 1
8 2.00162e+05 8.57134e+04 1.50217e+01 1.00000e+00 1.00000e+00 1.0000 1
9 2.00128e+05 1.63545e+05 2.88639e+01 1.00000e+00 1.00000e+00 1.0000 1
iter cost stop grad xreg ureg step feas
10 2.00061e+05 3.12250e+05 5.58218e+01 1.00000e+00 1.00000e+00 1.0000 1
11 1.99929e+05 5.97981e+05 1.09351e+02 1.00000e+00 1.00000e+00 1.0000 1
12 1.99660e+05 1.16043e+06 2.19929e+02 1.00000e+00 1.00000e+00 1.0000 1
13 1.99065e+05 2.38449e+06 4.68916e+02 1.00000e+00 1.00000e+00 1.0000 1
14 1.97416e+05 6.33753e+06 1.16250e+03 1.00000e+00 1.00000e+00 1.0000 1
15 1.82461e+05 4.99746e+07 5.10514e+03 1.00000e+00 1.00000e+00 1.0000 1
16 1.68743e+05 7.51342e+10 5.15698e+04 1.00000e+01 1.00000e+01 1.0000 1
17 1.26802e+05 3.99501e+09 3.44668e+05 1.00000e+01 1.00000e+01 0.5000 1
18 6.98759e+04 9.82853e+11 2.26947e+05 1.00000e+01 1.00000e+01 0.5000 1
19 2.02725e+04 5.71522e+11 1.17776e+05 1.00000e+00 1.00000e+00 1.0000 1
iter cost stop grad xreg ureg step feas
20 1.02926e+04 1.14975e+11 2.59392e+04 1.00000e+00 1.00000e+00 0.5000 1
21 6.50756e+03 2.62667e+10 6.55275e+03 1.00000e-01 1.00000e-01 1.0000 1
22 5.34085e+03 4.07997e+09 4.17908e+03 1.00000e-01 1.00000e-01 0.2500 1
23 4.70136e+03 1.88124e+09 2.62343e+03 1.00000e-01 1.00000e-01 0.2500 1
24 3.99760e+03 9.09931e+08 1.84358e+03 1.00000e-01 1.00000e-01 0.5000 1
25 3.32742e+03 7.81105e+07 1.11239e+03 1.00000e-02 1.00000e-02 1.0000 1
26 3.06404e+03 1.43324e+08 9.14533e+02 1.00000e-02 1.00000e-02 0.5000 1
27 2.85334e+03 9.68882e+07 5.65338e+02 1.00000e-02 1.00000e-02 0.5000 1
28 2.79953e+03 3.04477e+07 2.66526e+02 1.00000e-03 1.00000e-03 1.0000 1
29 2.70925e+03 2.13333e+08 2.80254e+02 1.00000e-03 1.00000e-03 0.5000 1
iter cost stop grad xreg ureg step feas
30 2.50004e+03 2.92098e+08 3.27901e+02 1.00000e-04 1.00000e-04 1.0000 1
31 2.02035e+03 3.52509e+05 1.26929e+03 1.00000e-04 1.00000e-04 0.5000 1
32 1.80103e+03 2.08929e+07 1.97848e+03 1.00000e-04 1.00000e-04 0.1250 1
33 1.60557e+03 1.60392e+07 1.42325e+03 1.00000e-04 1.00000e-04 0.2500 1
34 1.41725e+03 3.85125e+07 9.65434e+02 1.00000e-04 1.00000e-04 0.2500 1
35 1.24798e+03 1.64564e+07 4.53406e+02 1.00000e-04 1.00000e-04 0.5000 1
36 1.05211e+03 5.38901e+06 2.75515e+02 1.00000e-05 1.00000e-05 1.0000 1
37 8.44057e+02 1.99724e+05 4.26936e+02 1.00000e-06 1.00000e-06 1.0000 1
38 8.02529e+02 4.66864e+04 1.73189e+02 1.00000e-06 1.00000e-06 0.5000 1
39 7.77646e+02 8.81186e+02 1.00350e+02 1.00000e-06 1.00000e-06 0.5000 1
iter cost stop grad xreg ureg step feas
40 7.62149e+02 3.22748e+03 6.09360e+01 1.00000e-06 1.00000e-06 0.5000 1
41 7.52141e+02 1.11324e+03 3.83520e+01 1.00000e-06 1.00000e-06 0.5000 1
42 7.45253e+02 3.50300e+03 2.53379e+01 1.00000e-06 1.00000e-06 0.5000 1
43 7.40273e+02 2.73430e+03 1.76460e+01 1.00000e-06 1.00000e-06 0.5000 1
44 7.36427e+02 1.39565e+03 1.31192e+01 1.00000e-06 1.00000e-06 0.5000 1
45 7.33270e+02 6.20272e+02 1.03678e+01 1.00000e-06 1.00000e-06 0.5000 1
46 7.30557e+02 2.80257e+02 8.59548e+00 1.00000e-06 1.00000e-06 0.5000 1
47 7.28152e+02 1.42955e+02 7.37005e+00 1.00000e-06 1.00000e-06 0.5000 1
48 7.25979e+02 8.63697e+01 6.45943e+00 1.00000e-06 1.00000e-06 0.5000 1
49 7.23994e+02 6.07746e+01 5.73694e+00 1.00000e-06 1.00000e-06 0.5000 1
iter cost stop grad xreg ureg step feas
50 7.22170e+02 4.73969e+01 5.13265e+00 1.00000e-06 1.00000e-06 0.5000 1
51 7.20493e+02 3.90506e+01 4.60615e+00 1.00000e-06 1.00000e-06 0.5000 1
52 7.18951e+02 3.29214e+01 4.13491e+00 1.00000e-06 1.00000e-06 0.5000 1
53 7.17537e+02 2.79148e+01 3.70581e+00 1.00000e-06 1.00000e-06 0.5000 1
54 7.16245e+02 2.36222e+01 3.31178e+00 1.00000e-06 1.00000e-06 0.5000 1
55 7.15889e+02 1.99076e+01 2.94888e+00 1.00000e-07 1.00000e-07 1.0000 1
56 7.12990e+02 2.01704e+01 6.55642e+00 1.00000e-08 1.00000e-08 1.0000 1
57 7.10845e+02 6.67999e+02 4.07708e+00 1.00000e-09 1.00000e-09 1.0000 1
58 7.09461e+02 3.80830e+01 2.26922e+00 1.00000e-09 1.00000e-09 1.0000 1
59 7.08542e+02 6.82361e+00 1.34000e+00 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
60 7.07909e+02 4.03002e+00 8.47089e-01 1.00000e-09 1.00000e-09 1.0000 1
61 7.07469e+02 2.73417e+00 5.52833e-01 1.00000e-09 1.00000e-09 1.0000 1
62 7.07165e+02 1.84088e+00 3.65584e-01 1.00000e-09 1.00000e-09 1.0000 1
63 7.06956e+02 1.23860e+00 2.43972e-01 1.00000e-09 1.00000e-09 1.0000 1
64 7.06812e+02 8.37368e-01 1.63849e-01 1.00000e-09 1.00000e-09 1.0000 1
65 7.06713e+02 5.67882e-01 1.10468e-01 1.00000e-09 1.00000e-09 1.0000 1
66 7.06646e+02 3.85585e-01 7.46353e-02 1.00000e-09 1.00000e-09 1.0000 1
67 7.06600e+02 2.61781e-01 5.04698e-02 1.00000e-09 1.00000e-09 1.0000 1
68 7.06569e+02 1.77570e-01 3.41303e-02 1.00000e-09 1.00000e-09 1.0000 1
69 7.06548e+02 1.20293e-01 2.30698e-02 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
70 7.06533e+02 8.13736e-02 1.55814e-02 1.00000e-09 1.00000e-09 1.0000 1
71 7.06524e+02 5.49677e-02 1.05140e-02 1.00000e-09 1.00000e-09 1.0000 1
72 7.06517e+02 3.70811e-02 7.08778e-03 1.00000e-09 1.00000e-09 1.0000 1
73 7.06513e+02 2.49848e-02 4.77356e-03 1.00000e-09 1.00000e-09 1.0000 1
74 7.06510e+02 1.68167e-02 3.21213e-03 1.00000e-09 1.00000e-09 1.0000 1
75 7.06508e+02 1.13087e-02 2.15973e-03 1.00000e-09 1.00000e-09 1.0000 1
76 7.06507e+02 7.59883e-03 1.45112e-03 1.00000e-09 1.00000e-09 1.0000 1
77 7.06506e+02 5.10267e-03 9.74412e-04 1.00000e-09 1.00000e-09 1.0000 1
78 7.06505e+02 3.42460e-03 6.53968e-04 1.00000e-09 1.00000e-09 1.0000 1
79 7.06505e+02 2.29732e-03 4.38710e-04 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
80 7.06505e+02 1.54053e-03 2.94196e-04 1.00000e-09 1.00000e-09 1.0000 1
81 7.06504e+02 1.03271e-03 1.97224e-04 1.00000e-09 1.00000e-09 1.0000 1
82 7.06504e+02 6.92113e-04 1.32181e-04 1.00000e-09 1.00000e-09 1.0000 1
83 7.06504e+02 4.63746e-04 8.85696e-05 1.00000e-09 1.00000e-09 1.0000 1
84 7.06504e+02 3.10676e-04 5.93365e-05 1.00000e-09 1.00000e-09 1.0000 1
85 7.06504e+02 2.08099e-04 3.97461e-05 1.00000e-09 1.00000e-09 1.0000 1
86 7.06504e+02 1.39374e-04 2.66203e-05 1.00000e-09 1.00000e-09 1.0000 1
87 7.06504e+02 9.33361e-05 1.78274e-05 1.00000e-09 1.00000e-09 1.0000 1
88 7.06504e+02 6.25004e-05 1.19379e-05 1.00000e-09 1.00000e-09 1.0000 1
89 7.06504e+02 4.18492e-05 7.99351e-06 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
90 7.06504e+02 2.80200e-05 5.35208e-06 1.00000e-09 1.00000e-09 1.0000 1
91 7.06504e+02 1.87599e-05 3.58333e-06 1.00000e-09 1.00000e-09 1.0000 1
92 7.06504e+02 1.25596e-05 2.39903e-06 1.00000e-09 1.00000e-09 1.0000 1
93 7.06504e+02 8.40829e-06 1.60609e-06 1.00000e-09 1.00000e-09 1.0000 1
94 7.06504e+02 5.62898e-06 1.07521e-06 1.00000e-09 1.00000e-09 1.0000 1
95 7.06504e+02 3.76828e-06 7.19797e-07 1.00000e-09 1.00000e-09 1.0000 1
96 7.06504e+02 2.52261e-06 4.81856e-07 1.00000e-09 1.00000e-09 1.0000 1
97 7.06504e+02 1.68869e-06 3.22566e-07 1.00000e-09 1.00000e-09 1.0000 1
98 7.06504e+02 1.13043e-06 2.15931e-07 1.00000e-09 1.00000e-09 1.0000 1
99 7.06504e+02 7.56723e-07 1.44547e-07 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
100 7.06504e+02 5.06554e-07 9.67603e-08 1.00000e-09 1.00000e-09 1.0000 1
101 7.06504e+02 3.39087e-07 6.47715e-08 1.00000e-09 1.00000e-09 1.0000 1
102 7.06504e+02 2.26984e-07 4.33579e-08 1.00000e-09 1.00000e-09 1.0000 1
103 7.06504e+02 1.51942e-07 2.90235e-08 1.00000e-09 1.00000e-09 1.0000 1
104 7.06504e+02 1.01709e-07 1.94281e-08 1.00000e-09 1.00000e-09 1.0000 1
105 7.06504e+02 6.80828e-08 1.30050e-08 1.00000e-09 1.00000e-09 1.0000 1
106 7.06504e+02 4.55739e-08 8.70541e-09 1.00000e-09 1.00000e-09 1.0000 1
107 7.06504e+02 3.05066e-08 5.82730e-09 1.00000e-09 1.00000e-09 1.0000 1
108 7.06504e+02 2.04207e-08 3.90072e-09 1.00000e-09 1.00000e-09 1.0000 1
109 7.06504e+02 1.36693e-08 2.61109e-09 1.00000e-09 1.00000e-09 1.0000 1
iter cost stop grad xreg ureg step feas
110 7.06504e+02 9.15005e-09 1.74782e-09 1.00000e-09 1.00000e-09 1.0000 1
111 7.06504e+02 6.12490e-09 1.16997e-09 1.00000e-09 1.00000e-09 1.0000 1
112 7.06504e+02 4.09991e-09 7.83156e-10 1.00000e-09 1.00000e-09 1.0000 1
113 7.06504e+02 2.74441e-09 5.24232e-10 1.00000e-09 1.00000e-09 1.0000 1
114 7.06504e+02 1.83707e-09 3.50913e-10 1.00000e-09 1.00000e-09 1.0000 1
115 7.06504e+02 1.22970e-09 2.34895e-10 1.00000e-09 1.00000e-09 1.0000 1
116 7.06504e+02 8.23141e-10 1.57235e-10 1.00000e-09 1.00000e-09 1.0000 1
([array([3.14, 0. , 0. , 0. ]),
array([ 3.18493482, -0.08713096, 4.49348194, -8.71309552]),
array([ 3.2298292 , -0.17422292, 4.48943827, -8.70919683]),
array([ 3.27463366, -0.26123502, 4.48044598, -8.70120942]),
array([ 3.31930113, -0.34813226, 4.46674667, -8.68972446]),
array([ 3.36378637, -0.43488521, 4.44852367, -8.67529474]),
array([ 3.4080461 , -0.52147097, 4.42597344, -8.65857575]),
array([ 3.45203903, -0.60787403, 4.39929332, -8.64030581]),
array([ 3.4957257 , -0.69408685, 4.36866653, -8.62128281]),
array([ 3.53906814, -0.78011023, 4.33424423, -8.60233717]),
array([ 3.58202938, -0.86595323, 4.29612405, -8.58430083]),
array([ 3.62457263, -0.95163295, 4.2543245 , -8.56797163]),
array([ 3.66666017, -1.03717368, 4.20875472, -8.55407264]),
array([ 3.70825196, -1.12260574, 4.15917857, -8.54320601]),
array([ 3.74930368, -1.20796374, 4.10517248, -8.53580074]),
array([ 3.78976444, -1.29328428, 4.04607602, -8.53205407]),
array([ 3.82957379, -1.37860295, 3.98093443, -8.53186644]),
array([ 3.86865812, -1.46395065, 3.90843271, -8.5347701 ]),
array([ 3.90692633, -1.54934918, 3.82682107, -8.53985257]),
array([ 3.94426465, -1.63480594, 3.73383282, -8.54567695]),
array([ 3.98053063, -1.72030798, 3.62659768, -8.55020316]),
array([ 4.01554619, -1.80581515, 3.50155634, -8.55071692]),
array([ 4.04909007, -1.89125292, 3.35438748, -8.54377767]),
array([ 4.08088973, -1.97650495, 3.17996605, -8.52520265]),
array([ 4.11061355, -2.06140607, 2.9723825 , -8.49011177]),
array([ 4.13786422, -2.14573673, 2.72506642, -8.43306615]),
array([ 4.16217494, -2.22922011, 2.43107181, -8.34833785]),
array([ 4.18301081, -2.31152354, 2.08358752, -8.23034349]),
array([ 4.19977803, -2.39226603, 1.67672214, -8.07424895]),
array([ 4.21184361, -2.47103299, 1.2065574 , -7.87669617]),
array([ 4.21856715, -2.54739816, 0.67235412, -7.63651698]),
array([ 4.21934356, -2.62095029, 0.07764073, -7.35521284]),
array([ 4.21365137, -2.69131985, -0.5692183 , -7.03695599]),
array([ 4.20109761, -2.75819961, -1.25537597, -6.68797565]),
array([ 4.18144808, -2.82135392, -1.96495324, -6.31543089]),
array([ 4.15463456, -2.88061511, -2.68135242, -5.92611935]),
array([ 4.12073641, -2.93586965, -3.38981479, -5.525454 ]),
array([ 4.07994156, -2.98703951, -4.07948487, -5.11698614]),
array([ 4.03249694, -3.03406423, -4.74446208, -4.70247228]),
array([ 3.97865966, -3.0768869 , -5.38372748, -4.28226633]),
array([ 3.91865772, -3.11544464, -6.00019469, -3.85577402]),
array([ 3.85266466, -3.14966263, -6.59930552, -3.42179966]),
array([ 3.78078902, -3.17945009, -7.18756462, -2.97874593]),
array([ 3.70307634, -3.20469726, -7.77126796, -2.52471678]),
array([ 3.61952115, -3.22527328, -8.3555189 , -2.05760147]),
array([ 3.5300861 , -3.24102531, -8.94350507, -1.57520325]),
array([ 3.43472662, -3.25177975, -9.53594786, -1.07544446]),
array([ 3.33342033, -3.25734622, -10.13062875, -0.55664642]),
array([ 3.22620107, -3.25752473, -10.72192632, -0.01785156]),
array([ 3.11319752, -3.25211597, -11.30035464, 0.54087625]),
array([ 2.99467581, -3.24093327, -11.85217104, 1.11826978]),
array([ 2.87108366, -3.22381409, -12.35921487, 1.71191798]),
array([ 2.74309134, -3.2006272 , -12.79923182, 2.31868886]),
array([ 2.61162144, -3.17127146, -13.14699083, 2.93557402]),
array([ 2.47785696, -3.13566294, -13.3764471 , 3.56085211]),
array([ 2.34321717, -3.09371085, -13.46397986, 4.19520901]),
array([ 2.20929372, -3.0452891 , -13.39234466, 4.84217551]),
array([ 2.07774808, -2.99021784, -13.1545638 , 5.50712605]),
array([ 1.95018035, -2.92827437, -12.75677323, 6.19434675]),
array([ 1.82798839, -2.85924962, -12.2191963 , 6.90247462]),
array([ 1.71224041, -2.78305121, -11.57479785, 7.61984101]),
array([ 1.60358529, -2.6998276 , -10.86551226, 8.32236121]),
array([ 1.50222254, -2.61006306, -10.13627404, 8.976454 ]),
array([ 1.40794413, -2.51459222, -9.42784116, 9.54708392]),
array([ 1.32023892, -2.41451805, -8.77052111, 10.0074172 ]),
array([ 1.23842745, -2.31106757, -8.18114766, 10.34504814]),
array([ 1.16178642, -2.20544538, -7.6641023 , 10.5622186 ]),
array([ 1.0896362 , -2.09873042, -7.21502244, 10.67149584]),
array([ 1.02138612, -1.99182797, -6.82500812, 10.69024557]),
array([ 0.95654761, -1.8854647 , -6.48385065, 10.63632652]),
array([ 0.8947285 , -1.78020782, -6.18191078, 10.52568849]),
array([ 0.83561923, -1.67649297, -5.91092732, 10.37148461]),
array([ 0.77897738, -1.5746524 , -5.66418506, 10.18405693]),
array([ 0.72461361, -1.4749394 , -5.43637709, 9.9713008 ]),
array([ 0.67238 , -1.37754814, -5.22336057, 9.73912544]),
array([ 0.62216096, -1.28262932, -5.02190441, 9.49188186]),
array([ 0.57386627, -1.19030217, -4.8294683 , 9.23271545]),
array([ 0.52742604, -1.10066377, -4.64402354, 8.96383942]),
array([ 0.48278691, -1.01379637, -4.46391333, 8.68674066]),
array([ 0.43990944, -0.92977304, -4.28774644, 8.40233236]),
array([ 0.39876627, -0.84866238, -4.11431701, 8.11106667]),
array([ 0.35934083, -0.7705322 , -3.94254454, 7.81301792]),
array([ 0.32162654, -0.69545275, -3.77142905, 7.50794454]),
array([ 0.28562636, -0.6234994 , -3.60001745, 7.1953355 ]),
array([ 0.25135258, -0.55475494, -3.42737839, 6.87444539]),
array([ 0.21882675, -0.48931173, -3.2525831 , 6.54432136]),
array([ 0.18807984, -0.42727349, -3.0746908 , 6.20382372]),
array([ 0.15915247, -0.36875707, -2.8927373 , 5.85164182]),
array([ 0.13209521, -0.31389401, -2.70572581, 5.48630617]),
array([ 0.10696901, -0.26283204, -2.51261927, 5.1061972 ]),
array([ 0.08384568, -0.21573653, -2.31233348, 4.70955131]),
array([ 0.06280837, -0.17279189, -2.10373072, 4.29446411]),
array([ 0.04395224, -0.13420298, -1.88561332, 3.85889105]),
array([ 0.02738507, -0.10019652, -1.65671694, 3.40064542]),
array([ 0.01322804, -0.07102258, -1.41570347, 2.91739391]),
array([ 1.61650040e-03, -4.69560835e-02, -1.16115350e+00, 2.40664990e+00]),
array([-0.00729909, -0.02829843, -0.89155866, 1.86576554]),
array([-0.01335223, -0.01537919, -0.60531455, 1.29192372]),
array([-0.01635938, -0.00855786, -0.30071529, 0.6821328 ]),
array([-0.01611896, -0.00822546, 0.02404208, 0.03323985]),
array([-0.01586976, -0.00809705, 0.02492077, 0.01284125])],
[array([-0.41707639]),
array([-0.02170736]),
array([-0.04339121]),
array([-0.06488339]),
array([-0.08608214]),
array([-0.10690605]),
array([-0.12728863]),
array([-0.14717918]),
array([-0.16654239]),
array([-0.18535658]),
array([-0.20361058]),
array([-0.22129932]),
array([-0.23841813]),
array([-0.25495595]),
array([-0.27088756]),
array([-0.28616505]),
array([-0.30070894]),
array([-0.31439939]),
array([-0.32706843]),
array([-0.33849405]),
array([-0.34839822]),
array([-0.3564508]),
array([-0.36228264]),
array([-0.36551154]),
array([-0.36578462]),
array([-0.36283921]),
array([-0.35657909]),
array([-0.34715357]),
array([-0.33501288]),
array([-0.32090036]),
array([-0.30574326]),
array([-0.29043471]),
array([-0.27556091]),
array([-0.26118713]),
array([-0.24681691]),
array([-0.23155717]),
array([-0.21440566]),
array([-0.19451738]),
array([-0.17134323]),
array([-0.14462508]),
array([-0.11430488]),
array([-0.08042383]),
array([-0.04306259]),
array([-0.00233759]),
array([0.04155727]),
array([0.0882841]),
array([0.13729043]),
array([0.18775348]),
array([0.23855829]),
array([0.28833105]),
array([0.3355495]),
array([0.37874419]),
array([0.41677769]),
array([0.44913947]),
array([0.47613113]),
array([0.49877609]),
array([0.51832359]),
array([0.53537352]),
array([0.54891866]),
array([0.55588481]),
array([0.55180844]),
array([0.53280124]),
array([0.49790594]),
array([0.4502027]),
array([0.39572102]),
array([0.34097891]),
array([0.2908931]),
array([0.2480415]),
array([0.21303487]),
array([0.18528336]),
array([0.16366376]),
array([0.14693799]),
array([0.13396036]),
array([0.12375473]),
array([0.115526]),
array([0.10864418]),
array([0.10262018]),
array([0.09708141]),
array([0.09175015]),
array([0.0864254]),
array([0.08096782]),
array([0.07528741]),
array([0.06933347]),
array([0.06308651]),
array([0.05655164]),
array([0.04975356]),
array([0.04273256]),
array([0.03554161]),
array([0.02824437]),
array([0.02091379]),
array([0.01363135]),
array([0.00648661]),
array([-0.00042301]),
array([-0.00699249]),
array([-0.01310974]),
array([-0.0186566]),
array([-0.02351091]),
array([-0.02754985]),
array([-0.03065489]),
array([-0.00059537])],
True)
%% Cell type:code id: tags:
``` python
displayTrajectory(robot, ddp.xs, runningModel.timeStep)
```
%% Cell type:markdown id: tags:
%% Cell type:code id: tags:
``` python
import time
dt = 0.01
t = np.arange(0,1,dt)
q0 = np.array([[3.14,0]]).T
q = q0
q_d = np.zeros([2,1])
q_dd = np.zeros([2,1])
```
%% Cell type:markdown id: tags:
%% Cell type:code id: tags:
``` python
nle = np.zeros([2,1])
for i in range(len(t)):
pin.computeAllTerms(robot.model, robot.data, q, q_d)
M = robot.data.M
Minv = np.linalg.inv(M)
r = np.zeros([2,1])
tau = np.zeros([2,1])
tau[1,0] = ddp.us[i]
nle[:,0] = m2a(robot.data.nle)
r[:] = tau - nle
q_dd = np.dot(Minv, r)
q = q + q_d*dt + q_dd*dt**2
q_d = q_d + q_dd*dt
#pin.forwardKinematics(robot.model, robot.data, q, q_d)
robot.display(q)
time.sleep(dt)
```
%% Cell type:code id: tags:
``` python
import numpy as np
import matplotlib.pyplot as plt
control = np.vstack(ddp.us)
t = np.arange(0,T*dt, dt)
fig, axs = plt.subplots(1,2, figsize=(15,10))
fig.suptitle('Motor torques')
# axs[0].plot(t,control[:,0], t,control[:,1])
axs[0].plot(t,control[:,0])
axs[0].set_title('Moments')
axs[0].legend(['M1','M2'])
t_state = np.append(t, t[-1]+dt)
state = np.vstack(ddp.xs)
fig, axs = plt.subplots(1,2, figsize=(15,10))
fig.suptitle('States')
axs[0].plot(t_state,state[:,0], t_state, state[:,1])
axs[0].set_title('Position')
axs[0].legend(['Link 1','Link2'])
axs[1].plot(t_state,state[:,2], t_state, state[:,3])
axs[1].set_title('Vels')
axs[1].legend(['Link 1','Link2'])
```
%% Output
<matplotlib.legend.Legend at 0x7fa1936d3490>
%% Cell type:code id: tags:
``` python
```
......
This diff is collapsed.
source diff could not be displayed: it is too large. Options to address this: view the blob.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment