Skip to content

Commit 8cdb7ea

Browse files
committed
fix matrix products
1 parent 1c671d5 commit 8cdb7ea

File tree

3 files changed

+14
-15
lines changed

3 files changed

+14
-15
lines changed

exercizes/ex_4_walking.py

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import matplotlib.pyplot as plt
55
import numpy as np
66
import plot_utils as plut
7-
import scipy.sparse as spa
87
from numpy import nan
98
from numpy.linalg import norm as norm
109
from tsid_biped import TsidBiped
@@ -175,16 +174,16 @@
175174

176175
if tsid_biped.formulation.checkContact(tsid_biped.contactRF.name, sol):
177176
T_RF = tsid_biped.contactRF.getForceGeneratorMatrix
178-
f_RF[:, i] = T_RF @ tsid_biped.formulation.getContactForce(
179-
tsid_biped.contactRF.name, sol
177+
f_RF[:, i] = T_RF.dot(
178+
tsid_biped.formulation.getContactForce(tsid_biped.contactRF.name, sol)
180179
)
181180
if f_RF[2, i] > 1e-3:
182181
cop_RF[0, i] = f_RF[4, i] / f_RF[2, i]
183182
cop_RF[1, i] = -f_RF[3, i] / f_RF[2, i]
184183
if tsid_biped.formulation.checkContact(tsid_biped.contactLF.name, sol):
185184
T_LF = tsid_biped.contactRF.getForceGeneratorMatrix
186-
f_LF[:, i] = T_LF @ tsid_biped.formulation.getContactForce(
187-
tsid_biped.contactLF.name, sol
185+
f_LF[:, i] = T_LF.dot(
186+
tsid_biped.formulation.getContactForce(tsid_biped.contactLF.name, sol)
188187
)
189188
if f_LF[2, i] > 1e-3:
190189
cop_LF[0, i] = f_LF[4, i] / f_LF[2, i]

exercizes/test_cop_task.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -152,16 +152,16 @@
152152

153153
if tsid.formulation.checkContact(tsid.contactRF.name, sol):
154154
T_RF = tsid.contactRF.getForceGeneratorMatrix
155-
f_RF[:, i] = T_RF @ tsid.formulation.getContactForce(
156-
tsid.contactRF.name, sol
155+
f_RF[:, i] = T_RF.dot(
156+
tsid.formulation.getContactForce(tsid.contactRF.name, sol)
157157
)
158158
if f_RF[2, i] > 1e-3:
159159
cop_RF[0, i] = f_RF[4, i] / f_RF[2, i]
160160
cop_RF[1, i] = -f_RF[3, i] / f_RF[2, i]
161161
if tsid.formulation.checkContact(tsid.contactLF.name, sol):
162162
T_LF = tsid.contactRF.getForceGeneratorMatrix
163-
f_LF[:, i] = T_LF @ tsid.formulation.getContactForce(
164-
tsid.contactLF.name, sol
163+
f_LF[:, i] = T_LF.dot(
164+
tsid.formulation.getContactForce(tsid.contactLF.name, sol)
165165
)
166166
if f_LF[2, i] > 1e-3:
167167
cop_LF[0, i] = f_LF[4, i] / f_LF[2, i]

tests/python/test_Solvers.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -60,11 +60,11 @@
6060
b1 = np.random.rand(n)
6161
cost = tsid.ConstraintEquality("c1", A1, b1)
6262

63-
x = np.linalg.inv(A1) @ b1
63+
x = np.linalg.inv(A1).dot(b1)
6464
A_in = np.random.rand(nin, n)
6565
A_lb = np.random.rand(nin) * NORMAL_DISTR_VAR
6666
A_ub = np.random.rand(nin) * NORMAL_DISTR_VAR
67-
constrVal = A_in @ x
67+
constrVal = A_in.dot(x)
6868

6969
for i in range(0, nin):
7070
if A_ub[i] <= A_lb[i]:
@@ -78,7 +78,7 @@
7878

7979
in_const = tsid.ConstraintInequality("ini1", A_in, A_lb, A_ub)
8080
A_eq = np.random.rand(neq, n)
81-
b_eq = A_eq @ x
81+
b_eq = A_eq.dot(x)
8282
eq_const = tsid.ConstraintEquality("eq1", A_eq, b_eq)
8383

8484
const1 = tsid.ConstraintLevel()
@@ -111,7 +111,7 @@
111111

112112
HQPoutput = solver.solve(HQPData)
113113

114-
assert np.linalg.norm(A_eq @ HQPoutput.x - b_eq, 2) < EPS
115-
assert (A_in @ HQPoutput.x <= A_ub + EPS).all()
116-
assert (A_in @ HQPoutput.x > A_lb - EPS).all()
114+
assert np.linalg.norm(A_eq.dot(HQPoutput.x) - b_eq, 2) < EPS
115+
assert (A_in.dot(HQPoutput.x) <= A_ub + EPS).all()
116+
assert (A_in.dot(HQPoutput.x) > A_lb - EPS).all()
117117
print("-> succesful")

0 commit comments

Comments
 (0)