-
Notifications
You must be signed in to change notification settings - Fork 0
/
Acrobot_Running.py
177 lines (129 loc) · 5.56 KB
/
Acrobot_Running.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
from pydrake.examples.acrobot import (AcrobotGeometry, AcrobotInput,
AcrobotPlant, AcrobotState, AcrobotParams)
from pydrake.all import Linearize, LinearQuadraticRegulator, SymbolicVectorSystem, Variable, Saturation, \
WrapToSystem, Simulator, Polynomial
from pydrake.systems.framework import DiagramBuilder
from pydrake.systems.primitives import LogVectorOutput
from IPython.display import SVG, display
import pydot
import numpy as np
import math
import control
import pydrake
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
import pydrake.forwarddiff as pf
import time
from IPython.display import display, Math, Markdown
from pydrake.examples.pendulum import PendulumPlant
from pydrake.examples.acrobot import AcrobotPlant
from pydrake.all import MultibodyPlant, Parser, SinCos, MakeVectorVariable, ToLatex, Substitute, Box
from underactuated import FindResource
from underactuated.scenarios import AddShape
from pydrake.all import (Jacobian, MathematicalProgram, Polynomial,
RegionOfAttraction, RegionOfAttractionOptions, Solve,
SymbolicVectorSystem, ToLatex, Variable, Variables,
plot_sublevelset_expression, SolverOptions, CommonSolverOption, SolverOptions)
from pydrake.solvers.mosek import MosekSolver
if __name__ == '__main__':
p = AcrobotParams()
m1 = p.m1()
m2 = p.m2()
l1 = p.l1()
lc1 = p.lc1()
lc2 = p.lc2()
Ic1 = p.Ic1()
Ic2 = p.Ic2()
b1 = p.b1()
b2 = p.b2()
gravity = p.gravity()
I1 = Ic1 + m1*lc1**2
I2 = Ic2 + m2*lc2**2
prog_create = MathematicalProgram()
x = prog_create.NewIndeterminates(4, 'X')
p1 = x[0]
p2 = x[1]
t1d = x[2]
t2d = x[3]
M = np.array([[1, 0, 0, 0],
[0, 1, 0, 0],
[0, 0, (1+p1**2)*(1+p2**2)*(I1+I2+m2*l1**2)+2*m2*l1*lc2*(1+p1**2)*(1-p2**2), \
(1+p1**2)*(1+p2**2)*I2+m2*l1*lc2*(1-p2**2)*(1+p1**2)],
[0, 0, I2*(1+p1**2)*(1+p2**2)+m2*l1*lc2*(1+p1**2)*(1-p2**2), I2*(1+p1**2)*(1+p2**2)]])
f3 = -2*m2*l1*lc2*2*p2*t1d*t2d*(1+p1**2) - m2*l1*lc2*2*p2*t2d**2*(1+p1**2) - m1*gravity*lc1*2*p1*(1+p2**2) \
+m2*gravity*(-l1*2*p1*(1+p2**2) + lc2*(-2*p1*(1-p2**2) - 2*p2*(1-p1**2))) + b1*t1d*(1+p1**2)*(1+p2**2)
f4 = m2*l1*lc2*2*p2*t1d**2*(1+p1**2) + m2*gravity*lc2*(-2*p1*(1-p2**2) - 2*p2*(1-p1**2)) \
+ b2*t2d*(1+p1**2)*(1+p2**2)
f = np.array([[0.5*(1+p1**2)*t1d],
[0.5*(1+p2**2)*t2d],
[-f3],
[-f4]])
p1d = 0.5*(1+p1**2)*t1d
p2d = 0.5*(1+p2**2)*t2d
Mdot = np.array([[0, 0, 0, 0],
[0, 0, 0, 0],
[0, 0, (2*p2*p2d+2*p1*p1d+2*p1*p2**2*p1d+2*p2*p1**2*p2d)*(I1+I2+m2*l1**2)\
+2*m2*l1*lc2*(-2*p2*p2d+2*p1*p1d-2*p1*p2**2*p1d-2*p2*p1**2*p2d), \
(2*p2*p2d+2*p1*p1d+2*p1*p2**2*p1d+2*p2*p1**2*p2d)*I2\
+m2*l1*lc1*(-2*p2*p2d+2*p1*p1d-2*p1*p2**2*p1d-2*p2*p1**2*p2d)], \
[0, 0, I2*(2*p2*p2d+2*p1*p1d+2*p1*p2**2*p1d+2*p2*p1**2*p2d)\
+m2*l1*lc2*(-2*p2*p2d+2*p1*p1d-2*p1*p2**2*p1d-2*p2*p1**2*p2d), \
I2*(2*p2*p2d+2*p1*p1d+2*p1*p2**2*p1d+2*p2*p1**2*p2d)]])
env = {p1:0, p2:0, t1d:0, t2d:0}
A_general = []
for exp in f:
exp_curr = exp[0].Jacobian(x)
A_general.append(exp_curr)
A_general = np.array(A_general)
A = np.zeros_like(A_general)
for i, row in enumerate(A_general):
for j, elem in enumerate(row):
A[i, j] = elem.Evaluate(env)
A = np.array(A, dtype=float)
E = np.zeros_like(M)
for i, row in enumerate(M):
for j, elem in enumerate(row):
if type(elem) == pydrake.symbolic.Expression:
E[i, j] = elem.Evaluate(env)
else:
E[i, j] = M[i, j]
E = np.array(E, dtype=float)
B = np.array([[0],
[0],
[0],
[1]])
Q = np.diag([5, 5, 1, 1])
R = [1]
X, L, K = control.care(A, B, Q, R, E=E)
A_cloop = A-B@K
Q_lyap = np.eye(4)
P = control.lyap(A_cloop.T, Q_lyap, E = E.T)
#add the controller
K2 = B.T@X@M
u = -K2@x
print(u)
f[3] = f[3] + u[0]*(1+p1**2)*(1+p2**2)
V = [email protected]@P@E@x
V = Polynomial(V)
Vdot = f.T@P@E@x + [email protected]@P@f
Vdot = Polynomial(Vdot[0])
# do the certification
prog = MathematicalProgram()
prog.AddIndeterminates(x)
rho = prog.NewContinuousVariables(1, 'rho')[0]
l_deg = Vdot.TotalDegree()
lambda_, lambda_Q = prog.NewSosPolynomial(Variables(x), l_deg)
print('Reached here 1')
#prog.AddSosConstraint(-Vdot + lambda_*(V - rho))
prog.AddSosConstraint(Polynomial(x.dot(x))*(V-rho) - lambda_*Vdot)
prog.AddLinearCost(-rho)
options = SolverOptions()
options.SetOption(CommonSolverOption.kPrintFileName, './check_solver_acrobot.txt')
solver = MosekSolver()
print('Reached here ')
result = solver.Solve(prog, solver_options=options)
print(str(result.get_solver_details().solution_status))
print(str(result.GetSolution(rho)))
print(np.linalg.eigvals(result.GetSolution(lambda_Q)))
print('Reached here succeffuly')