3 import matplotlib.pyplot
as plt
5 import plot_utils
as plut
8 import ur5_reaching_conf
as conf
10 from numpy.linalg
import norm
as norm
11 from tsid_manipulator
import TsidManipulator
13 print(
"".
center(conf.LINE_WIDTH,
"#"))
14 print(
" TSID - Manipulator End-Effector Sin Tracking ".
center(conf.LINE_WIDTH,
"#"))
15 print(
"".
center(conf.LINE_WIDTH,
"#"))
27 tau = np.empty((tsid.robot.na, N)) * nan
28 q = np.empty((tsid.robot.nq, N + 1)) * nan
29 v = np.empty((tsid.robot.nv, N + 1)) * nan
30 ee_pos = np.empty((3, N)) * nan
31 ee_vel = np.empty((3, N)) * nan
32 ee_acc = np.empty((3, N)) * nan
33 ee_pos_ref = np.empty((3, N)) * nan
34 ee_vel_ref = np.empty((3, N)) * nan
35 ee_acc_ref = np.empty((3, N)) * nan
36 ee_acc_des = np.empty((3, N)) * nan
38 sampleEE = tsid.trajEE.computeNext()
39 samplePosture = tsid.trajPosture.computeNext()
41 offset = sampleEE.pos()
42 offset[3:] = np.array([1.0, 0, 0, 0.0, 1, 0, 0.0, 0, 1])
43 offset[:3] += conf.offset
44 two_pi_f_amp = conf.two_pi_f * conf.amp
45 two_pi_f_squared_amp = conf.two_pi_f * two_pi_f_amp
51 tsid.gui.addSphere(
"world/ee", conf.SPHERE_RADIUS, conf.EE_SPHERE_COLOR)
52 tsid.gui.addSphere(
"world/ee_ref", conf.REF_SPHERE_RADIUS, conf.EE_REF_SPHERE_COLOR)
55 q[:, 0], v[:, 0] = tsid.q, tsid.v
58 time_start = time.time()
60 pEE[:3] = offset[:3] + conf.amp * np.sin(conf.two_pi_f * t + conf.phi)
61 vEE[:3] = two_pi_f_amp * np.cos(conf.two_pi_f * t + conf.phi)
62 aEE[:3] = -two_pi_f_squared_amp * np.sin(conf.two_pi_f * t + conf.phi)
66 tsid.eeTask.setReference(sampleEE)
68 HQPData = tsid.formulation.computeProblemData(t, q[:, i], v[:, i])
71 sol = tsid.solver.solve(HQPData)
73 print((f
"Time {t:.3f} QP problem could not be solved! Error code:", sol.status))
76 tau[:, i] = tsid.formulation.getActuatorForces(sol)
77 dv = tsid.formulation.getAccelerations(sol)
79 ee_pos[:, i] = tsid.robot.framePosition(
80 tsid.formulation.data(), tsid.EE
82 ee_vel[:, i] = tsid.robot.frameVelocityWorldOriented(
83 tsid.formulation.data(), tsid.EE
85 ee_acc[:, i] = tsid.eeTask.getAcceleration(dv)[:3]
86 ee_pos_ref[:, i] = sampleEE.pos()[:3]
87 ee_vel_ref[:, i] = sampleEE.vel()[:3]
88 ee_acc_ref[:, i] = sampleEE.acc()[:3]
89 ee_acc_des[:, i] = tsid.eeTask.getDesiredAcceleration[:3]
91 if i % conf.PRINT_N == 0:
92 print(f
"Time {t:.3f}")
94 "\ttracking err {}: {:.3f}".format(
95 tsid.eeTask.name.ljust(20,
"."), norm(tsid.eeTask.position_error, 2)
99 q[:, i + 1], v[:, i + 1] = tsid.integrate_dv(q[:, i], v[:, i], dv, conf.dt)
102 if i % conf.DISPLAY_N == 0:
103 tsid.robot_display.display(q[:, i])
104 tsid.gui.applyConfiguration(
"world/ee", [*ee_pos[:, i].tolist(), 0, 0, 0, 1.0])
105 tsid.gui.applyConfiguration(
106 "world/ee_ref", [*ee_pos_ref[:, i].tolist(), 0, 0, 0, 1.0]
109 time_spent = time.time() - time_start
110 if time_spent < conf.dt:
111 time.sleep(conf.dt - time_spent)
114 time = np.arange(0.0, N * conf.dt, conf.dt)
117 (f, ax) = plut.create_empty_figure(3, 1)
119 ax[i].
plot(time, ee_pos[i, :], label=
"EE " + str(i))
120 ax[i].
plot(time, ee_pos_ref[i, :],
"r:", label=
"EE Ref " + str(i))
121 ax[i].set_xlabel(
"Time [s]")
122 ax[i].set_ylabel(
"EE [m]")
124 leg.get_frame().set_alpha(0.5)
127 (f, ax) = plut.create_empty_figure(3, 1)
129 ax[i].
plot(time, ee_vel[i, :], label=
"EE Vel " + str(i))
130 ax[i].
plot(time, ee_vel_ref[i, :],
"r:", label=
"EE Vel Ref " + str(i))
131 ax[i].set_xlabel(
"Time [s]")
132 ax[i].set_ylabel(
"EE Vel [m/s]")
134 leg.get_frame().set_alpha(0.5)
137 (f, ax) = plut.create_empty_figure(3, 1)
139 ax[i].
plot(time, ee_acc[i, :], label=
"EE Acc " + str(i))
140 ax[i].
plot(time, ee_acc_ref[i, :],
"r:", label=
"EE Acc Ref " + str(i))
141 ax[i].
plot(time, ee_acc_des[i, :],
"g--", label=
"EE Acc Des " + str(i))
142 ax[i].set_xlabel(
"Time [s]")
143 ax[i].set_ylabel(
"EE Acc [m/s^2]")
145 leg.get_frame().set_alpha(0.5)
148 (f, ax) = plut.create_empty_figure(int(tsid.robot.nv / 2), 2)
149 ax = ax.reshape(tsid.robot.nv)
150 for i
in range(tsid.robot.nv):
151 ax[i].
plot(time, tau[i, :], label=
"Torque " + str(i))
152 ax[i].
plot([time[0], time[-1]], 2 * [tsid.tau_min[i]],
":")
153 ax[i].
plot([time[0], time[-1]], 2 * [tsid.tau_max[i]],
":")
154 ax[i].set_xlabel(
"Time [s]")
155 ax[i].set_ylabel(
"Torque [Nm]")
157 leg.get_frame().set_alpha(0.5)
160 (f, ax) = plut.create_empty_figure(int(tsid.robot.nv / 2), 2)
161 ax = ax.reshape(tsid.robot.nv)
162 for i
in range(tsid.robot.nv):
163 ax[i].
plot(time, v[i, :-1], label=
"Joint vel " + str(i))
164 ax[i].
plot([time[0], time[-1]], 2 * [tsid.v_min[i]],
":")
165 ax[i].
plot([time[0], time[-1]], 2 * [tsid.v_max[i]],
":")
166 ax[i].set_xlabel(
"Time [s]")
167 ax[i].set_ylabel(
"Joint velocity [rad/s]")
169 leg.get_frame().set_alpha(0.5)