3 import matplotlib.pyplot
as plt
5 import plot_utils
as plut
6 import romeo_conf
as conf
8 from numpy.linalg
import norm
as norm
9 from tsid_biped
import TsidBiped
11 print(
"".
center(conf.LINE_WIDTH,
"#"))
12 print(
" Test Task Space Inverse Dynamics - Biped ".
center(conf.LINE_WIDTH,
"#"))
13 print(
"".
center(conf.LINE_WIDTH,
"#"),
"\n")
18 com_pos = np.empty((3, N)) * nan
19 com_vel = np.empty((3, N)) * nan
20 com_acc = np.empty((3, N)) * nan
22 com_pos_ref = np.empty((3, N)) * nan
23 com_vel_ref = np.empty((3, N)) * nan
24 com_acc_ref = np.empty((3, N)) * nan
25 com_acc_des = np.empty((3, N)) * nan
31 time_start = time.time()
33 sampleCom = tsid.trajCom.computeNext()
34 tsid.comTask.setReference(sampleCom)
35 samplePosture = tsid.trajPosture.computeNext()
36 tsid.postureTask.setReference(samplePosture)
38 HQPData = tsid.formulation.computeProblemData(t, q, v)
41 sol = tsid.solver.solve(HQPData)
43 print(
"QP problem could not be solved! Error code:", sol.status)
46 tau = tsid.formulation.getActuatorForces(sol)
47 dv = tsid.formulation.getAccelerations(sol)
49 com_pos[:, i] = tsid.robot.com(tsid.formulation.data())
50 com_vel[:, i] = tsid.robot.com_vel(tsid.formulation.data())
51 com_acc[:, i] = tsid.comTask.getAcceleration(dv)
52 com_pos_ref[:, i] = sampleCom.pos()
53 com_vel_ref[:, i] = sampleCom.vel()
54 com_acc_ref[:, i] = sampleCom.acc()
55 com_acc_des[:, i] = tsid.comTask.getDesiredAcceleration
57 if i % conf.PRINT_N == 0:
58 print(
"Time %.3f" % (t))
59 if tsid.formulation.checkContact(tsid.contactRF.name, sol):
60 f = tsid.formulation.getContactForce(tsid.contactRF.name, sol)
62 "\tnormal force %s: %.1f" 63 % (tsid.contactRF.name.ljust(20,
"."), tsid.contactRF.getNormalForce(f))
66 if tsid.formulation.checkContact(tsid.contactLF.name, sol):
67 f = tsid.formulation.getContactForce(tsid.contactLF.name, sol)
69 "\tnormal force %s: %.1f" 70 % (tsid.contactLF.name.ljust(20,
"."), tsid.contactLF.getNormalForce(f))
74 "\ttracking err %s: %.3f" 75 % (tsid.comTask.name.ljust(20,
"."), norm(tsid.comTask.position_error, 2))
77 print(
"\t||v||: %.3f\t ||dv||: %.3f" % (norm(v, 2), norm(dv)))
79 q, v = tsid.integrate_dv(q, v, dv, conf.dt)
82 if i % conf.DISPLAY_N == 0:
85 time_spent = time.time() - time_start
86 if time_spent < conf.dt:
87 time.sleep(conf.dt - time_spent)
90 time = np.arange(0.0, N * conf.dt, conf.dt)
92 (f, ax) = plut.create_empty_figure(3, 1)
94 ax[i].plot(time, com_pos[i, :], label=
"CoM " + str(i))
95 ax[i].plot(time, com_pos_ref[i, :],
"r:", label=
"CoM Ref " + str(i))
96 ax[i].set_xlabel(
"Time [s]")
97 ax[i].set_ylabel(
"CoM [m]")
99 leg.get_frame().set_alpha(0.5)
101 (f, ax) = plut.create_empty_figure(3, 1)
103 ax[i].plot(time, com_vel[i, :], label=
"CoM Vel " + str(i))
104 ax[i].plot(time, com_vel_ref[i, :],
"r:", label=
"CoM Vel Ref " + str(i))
105 ax[i].set_xlabel(
"Time [s]")
106 ax[i].set_ylabel(
"CoM Vel [m/s]")
108 leg.get_frame().set_alpha(0.5)
110 (f, ax) = plut.create_empty_figure(3, 1)
112 ax[i].plot(time, com_acc[i, :], label=
"CoM Acc " + str(i))
113 ax[i].plot(time, com_acc_ref[i, :],
"r:", label=
"CoM Acc Ref " + str(i))
114 ax[i].plot(time, com_acc_des[i, :],
"g--", label=
"CoM Acc Des " + str(i))
115 ax[i].set_xlabel(
"Time [s]")
116 ax[i].set_ylabel(
"CoM Acc [m/s^2]")
118 leg.get_frame().set_alpha(0.5)