ex_2.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(" TSID - Biped Sin Tracking ".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 offset = tsid.robot.com(tsid.formulation.data())
28 amp = np.array([0.0, 0.05, 0.0])
29 two_pi_f = 2 * np.pi * np.array([0.0, 0.5, 0.0])
30 two_pi_f_amp = two_pi_f * amp
31 two_pi_f_squared_amp = two_pi_f * two_pi_f_amp
32 
33 sampleCom = tsid.trajCom.computeNext()
34 samplePosture = tsid.trajPosture.computeNext()
35 
36 t = 0.0
37 q, v = tsid.q, tsid.v
38 
39 for i in range(0, N):
40  time_start = time.time()
41 
42  sampleCom.pos(offset + amp * np.sin(two_pi_f * t))
43  sampleCom.vel(two_pi_f_amp * np.cos(two_pi_f * t))
44  sampleCom.acc(-two_pi_f_squared_amp * np.sin(two_pi_f * t))
45 
46  tsid.comTask.setReference(sampleCom)
47  tsid.postureTask.setReference(samplePosture)
48 
49  HQPData = tsid.formulation.computeProblemData(t, q, v)
50  # if i == 0: HQPData.print_all()
51 
52  sol = tsid.solver.solve(HQPData)
53  if sol.status != 0:
54  print("QP problem could not be solved! Error code:", sol.status)
55  break
56 
57  tau = tsid.formulation.getActuatorForces(sol)
58  dv = tsid.formulation.getAccelerations(sol)
59 
60  com_pos[:, i] = tsid.robot.com(tsid.formulation.data())
61  com_vel[:, i] = tsid.robot.com_vel(tsid.formulation.data())
62  com_acc[:, i] = tsid.comTask.getAcceleration(dv)
63  com_pos_ref[:, i] = sampleCom.pos()
64  com_vel_ref[:, i] = sampleCom.vel()
65  com_acc_ref[:, i] = sampleCom.acc()
66  com_acc_des[:, i] = tsid.comTask.getDesiredAcceleration
67 
68  if i % conf.PRINT_N == 0:
69  print(f"Time {t:.3f}")
70  if tsid.formulation.checkContact(tsid.contactRF.name, sol):
71  f = tsid.formulation.getContactForce(tsid.contactRF.name, sol)
72  print(
73  "\tnormal force {}: {:.1f}".format(
74  tsid.contactRF.name.ljust(20, "."), tsid.contactRF.getNormalForce(f)
75  )
76  )
77 
78  if tsid.formulation.checkContact(tsid.contactLF.name, sol):
79  f = tsid.formulation.getContactForce(tsid.contactLF.name, sol)
80  print(
81  "\tnormal force {}: {:.1f}".format(
82  tsid.contactLF.name.ljust(20, "."), tsid.contactLF.getNormalForce(f)
83  )
84  )
85 
86  print(
87  "\ttracking err {}: {:.3f}".format(
88  tsid.comTask.name.ljust(20, "."), norm(tsid.comTask.position_error, 2)
89  )
90  )
91  print(f"\t||v||: {norm(v, 2):.3f}\t ||dv||: {norm(dv):.3f}")
92 
93  q, v = tsid.integrate_dv(q, v, dv, conf.dt)
94  t += conf.dt
95 
96  if i % conf.DISPLAY_N == 0:
97  tsid.display(q)
98 
99  time_spent = time.time() - time_start
100  if time_spent < conf.dt:
101  time.sleep(conf.dt - time_spent)
102 
103 # PLOT STUFF
104 time = np.arange(0.0, N * conf.dt, conf.dt)
105 
106 (f, ax) = plut.create_empty_figure(3, 1)
107 for i in range(3):
108  ax[i].plot(time, com_pos[i, :], label="CoM " + str(i))
109  ax[i].plot(time, com_pos_ref[i, :], "r:", label="CoM Ref " + str(i))
110  ax[i].set_xlabel("Time [s]")
111  ax[i].set_ylabel("CoM [m]")
112  leg = ax[i].legend()
113  leg.get_frame().set_alpha(0.5)
114 
115 (f, ax) = plut.create_empty_figure(3, 1)
116 for i in range(3):
117  ax[i].plot(time, com_vel[i, :], label="CoM Vel " + str(i))
118  ax[i].plot(time, com_vel_ref[i, :], "r:", label="CoM Vel Ref " + str(i))
119  ax[i].set_xlabel("Time [s]")
120  ax[i].set_ylabel("CoM Vel [m/s]")
121  leg = ax[i].legend()
122  leg.get_frame().set_alpha(0.5)
123 
124 (f, ax) = plut.create_empty_figure(3, 1)
125 for i in range(3):
126  ax[i].plot(time, com_acc[i, :], label="CoM Acc " + str(i))
127  ax[i].plot(time, com_acc_ref[i, :], "r:", label="CoM Acc Ref " + str(i))
128  ax[i].plot(time, com_acc_des[i, :], "g--", label="CoM Acc Des " + str(i))
129  ax[i].set_xlabel("Time [s]")
130  ax[i].set_ylabel("CoM Acc [m/s^2]")
131  leg = ax[i].legend()
132  leg.get_frame().set_alpha(0.5)
133 
134 plt.show()
plot
center
Vec3f center
tsid_biped.TsidBiped
Definition: tsid_biped.py:11


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:16