ex_1.py
Go to the documentation of this file.
1 import time
2 
3 import matplotlib.pyplot as plt
4 import numpy as np
5 import plot_utils as plut
6 import romeo_conf as conf
7 from numpy import nan
8 from numpy.linalg import norm as norm
9 from tsid_biped import TsidBiped
10 
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")
14 
15 tsid = TsidBiped(conf, conf.viewer)
16 
17 N = conf.N_SIMULATION
18 com_pos = np.empty((3, N)) * nan
19 com_vel = np.empty((3, N)) * nan
20 com_acc = np.empty((3, N)) * nan
21 
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 # acc_des = acc_ref - Kp*pos_err - Kd*vel_err
26 
27 t = 0.0
28 q, v = tsid.q, tsid.v
29 
30 for i in range(0, N):
31  time_start = time.time()
32 
33  sampleCom = tsid.trajCom.computeNext()
34  tsid.comTask.setReference(sampleCom)
35  samplePosture = tsid.trajPosture.computeNext()
36  tsid.postureTask.setReference(samplePosture)
37 
38  HQPData = tsid.formulation.computeProblemData(t, q, v)
39  # if i == 0: HQPData.print_all()
40 
41  sol = tsid.solver.solve(HQPData)
42  if sol.status != 0:
43  print("QP problem could not be solved! Error code:", sol.status)
44  break
45 
46  tau = tsid.formulation.getActuatorForces(sol)
47  dv = tsid.formulation.getAccelerations(sol)
48 
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
56 
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)
61  print(
62  "\tnormal force %s: %.1f"
63  % (tsid.contactRF.name.ljust(20, "."), tsid.contactRF.getNormalForce(f))
64  )
65 
66  if tsid.formulation.checkContact(tsid.contactLF.name, sol):
67  f = tsid.formulation.getContactForce(tsid.contactLF.name, sol)
68  print(
69  "\tnormal force %s: %.1f"
70  % (tsid.contactLF.name.ljust(20, "."), tsid.contactLF.getNormalForce(f))
71  )
72 
73  print(
74  "\ttracking err %s: %.3f"
75  % (tsid.comTask.name.ljust(20, "."), norm(tsid.comTask.position_error, 2))
76  )
77  print("\t||v||: %.3f\t ||dv||: %.3f" % (norm(v, 2), norm(dv)))
78 
79  q, v = tsid.integrate_dv(q, v, dv, conf.dt)
80  t += conf.dt
81 
82  if i % conf.DISPLAY_N == 0:
83  tsid.display(q)
84 
85  time_spent = time.time() - time_start
86  if time_spent < conf.dt:
87  time.sleep(conf.dt - time_spent)
88 
89 # PLOT STUFF
90 time = np.arange(0.0, N * conf.dt, conf.dt)
91 
92 (f, ax) = plut.create_empty_figure(3, 1)
93 for i in range(3):
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]")
98  leg = ax[i].legend()
99  leg.get_frame().set_alpha(0.5)
100 
101 (f, ax) = plut.create_empty_figure(3, 1)
102 for i in range(3):
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]")
107  leg = ax[i].legend()
108  leg.get_frame().set_alpha(0.5)
109 
110 (f, ax) = plut.create_empty_figure(3, 1)
111 for i in range(3):
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]")
117  leg = ax[i].legend()
118  leg.get_frame().set_alpha(0.5)
119 
120 plt.show()
Vec3f center


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51