ex_0_ur5_joint_space_control.py
Go to the documentation of this file.
1 import os
2 import subprocess
3 import time
4 
5 import gepetto.corbaserver
6 import matplotlib.pyplot as plt
7 import numpy as np
8 import pinocchio as pin
9 import plot_utils as plut
10 import ur5_conf as conf
11 from numpy import nan
12 from numpy.linalg import norm as norm
13 
14 import tsid
15 
16 print("".center(conf.LINE_WIDTH, "#"))
17 print(" Joint Space Inverse Dynamics - Manipulator ".center(conf.LINE_WIDTH, "#"))
18 print("".center(conf.LINE_WIDTH, "#"), "\n")
19 
20 PLOT_JOINT_POS = 1
21 PLOT_JOINT_VEL = 1
22 PLOT_JOINT_ACC = 1
23 PLOT_TORQUES = 0
24 USE_VIEWER = 1
25 
26 robot = tsid.RobotWrapper(conf.urdf, [conf.path], False)
27 model = robot.model()
28 
29 formulation = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
30 q0 = conf.q0
31 v0 = np.zeros(robot.nv)
32 formulation.computeProblemData(0.0, q0, v0)
33 
34 postureTask = tsid.TaskJointPosture("task-posture", robot)
35 postureTask.setKp(conf.kp_posture * np.ones(robot.nv))
36 postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) * np.ones(robot.nv))
37 formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)
38 
39 trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q0)
40 postureTask.setReference(trajPosture.computeNext())
41 
42 v_max = conf.v_max_scaling * model.velocityLimit
43 v_min = -v_max
44 # jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot, conf.dt)
45 # jointBoundsTask.setVelocityBounds(v_min, v_max)
46 # formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0, 0.0)
47 
48 solver = tsid.SolverHQuadProgFast("qp solver")
49 solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
50 
51 if USE_VIEWER:
52  robot_display = pin.RobotWrapper.BuildFromURDF(
53  conf.urdf,
54  [
55  conf.path,
56  ],
57  )
58  n = subprocess.getstatusoutput("ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
59  if int(n[1]) == 0:
60  os.system("gepetto-gui &")
61  time.sleep(1)
62  gepetto.corbaserver.Client()
63  robot_display.initViewer(loadModel=True)
64  robot_display.displayCollisions(False)
65  robot_display.displayVisuals(True)
66  robot_display.display(q0)
67 # robot_display.viewer.gui.setCameraTransform(0, conf.CAMERA_TRANSFORM)
68 
69 N = conf.N_SIMULATION
70 tau = np.empty((robot.na, N)) * nan
71 q = np.empty((robot.nq, N + 1)) * nan
72 v = np.empty((robot.nv, N + 1)) * nan
73 dv = np.empty((robot.nv, N + 1)) * nan
74 q_ref = np.empty((robot.nq, N)) * nan
75 v_ref = np.empty((robot.nv, N)) * nan
76 dv_ref = np.empty((robot.nv, N)) * nan
77 dv_des = np.empty((robot.nv, N)) * nan
78 samplePosture = trajPosture.computeNext()
79 
80 amp = np.array([0.2, 0.3, 0.4, 0.0, 0.0, 0.0]) # amplitude
81 phi = np.array([0.0, 0.5 * np.pi, 0.0, 0.0, 0.0, 0.0]) # phase
82 two_pi_f = 2 * np.pi * np.array([1.0, 0.5, 0.3, 0.0, 0.0, 0.0]) # frequency (time 2 PI)
83 two_pi_f_amp = np.multiply(two_pi_f, amp)
84 two_pi_f_squared_amp = np.multiply(two_pi_f, two_pi_f_amp)
85 
86 t = 0.0
87 dt = conf.dt
88 q[:, 0], v[:, 0] = q0, v0
89 
90 for i in range(0, N):
91  time_start = time.time()
92 
93  # set reference trajectory
94  q_ref[:, i] = q0 + amp * np.sin(two_pi_f * t + phi)
95  v_ref[:, i] = two_pi_f_amp * np.cos(two_pi_f * t + phi)
96  dv_ref[:, i] = -two_pi_f_squared_amp * np.sin(two_pi_f * t + phi)
97  samplePosture.pos(q_ref[:, i])
98  samplePosture.vel(v_ref[:, i])
99  samplePosture.acc(dv_ref[:, i])
100  postureTask.setReference(samplePosture)
101 
102  HQPData = formulation.computeProblemData(t, q[:, i], v[:, i])
103  sol = solver.solve(HQPData)
104  if sol.status != 0:
105  print(f"Time {t:.3f} QP problem could not be solved! Error code:", sol.status)
106  break
107 
108  tau[:, i] = formulation.getActuatorForces(sol)
109  dv[:, i] = formulation.getAccelerations(sol)
110  dv_des[:, i] = postureTask.getDesiredAcceleration
111 
112  if i % conf.PRINT_N == 0:
113  print(f"Time {t:.3f}")
114  print(
115  "\ttracking err {}: {:.3f}".format(
116  postureTask.name.ljust(20, "."), norm(postureTask.position_error, 2)
117  )
118  )
119 
120  # numerical integration
121  v_mean = v[:, i] + 0.5 * dt * dv[:, i]
122  v[:, i + 1] = v[:, i] + dt * dv[:, i]
123  q[:, i + 1] = pin.integrate(model, q[:, i], dt * v_mean)
124  t += conf.dt
125 
126  if i % conf.DISPLAY_N == 0:
127  robot_display.display(q[:, i])
128 
129  time_spent = time.time() - time_start
130  if time_spent < conf.dt:
131  time.sleep(conf.dt - time_spent)
132 
133 # PLOT STUFF
134 time = np.arange(0.0, N * conf.dt, conf.dt)
135 
136 if PLOT_JOINT_POS:
137  (f, ax) = plut.create_empty_figure(int(robot.nv / 2), 2)
138  ax = ax.reshape(robot.nv)
139  for i in range(robot.nv):
140  ax[i].plot(time, q[i, :-1], label="q " + str(i))
141  ax[i].plot(time, q_ref[i, :], "--", label="q ref " + str(i))
142  ax[i].set_xlabel("Time [s]")
143  ax[i].set_ylabel("Q [rad]")
144  leg = ax[i].legend()
145  leg.get_frame().set_alpha(0.5)
146 
147 if PLOT_JOINT_VEL:
148  (f, ax) = plut.create_empty_figure(int(robot.nv / 2), 2)
149  ax = ax.reshape(robot.nv)
150  for i in range(robot.nv):
151  ax[i].plot(time, v[i, :-1], label="dq " + str(i))
152  ax[i].plot(time, v_ref[i, :], "--", label="dq ref " + str(i))
153  ax[i].plot([time[0], time[-1]], 2 * [v_min[i]], ":")
154  ax[i].plot([time[0], time[-1]], 2 * [v_max[i]], ":")
155  ax[i].set_xlabel("Time [s]")
156  ax[i].set_ylabel("dq [rad/s]")
157  leg = ax[i].legend()
158  leg.get_frame().set_alpha(0.5)
159 
160 if PLOT_JOINT_ACC:
161  (f, ax) = plut.create_empty_figure(int(robot.nv / 2), 2)
162  ax = ax.reshape(robot.nv)
163  for i in range(robot.nv):
164  ax[i].plot(time, dv[i, :-1], label="ddq " + str(i))
165  ax[i].plot(time, dv_ref[i, :], "--", label="ddq ref " + str(i))
166  ax[i].plot(time, dv_des[i, :], ":", label="ddq des " + str(i))
167  ax[i].set_xlabel("Time [s]")
168  ax[i].set_ylabel("ddq [rad/s^2]")
169  leg = ax[i].legend()
170  leg.get_frame().set_alpha(0.5)
171 
172 if PLOT_TORQUES:
173  (f, ax) = plut.create_empty_figure(int(robot.nv / 2), 2)
174  ax = ax.reshape(robot.nv)
175  for i in range(robot.nv):
176  ax[i].plot(time, tau[i, :], label="Torque " + str(i))
177  ax[i].set_xlabel("Time [s]")
178  ax[i].set_ylabel("Torque [Nm]")
179  leg = ax[i].legend()
180  leg.get_frame().set_alpha(0.5)
181 
182 plt.show()
plot
center
Vec3f center
tsid::InverseDynamicsFormulationAccForce
Definition: inverse-dynamics-formulation-acc-force.hpp:40


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