5 import gepetto.corbaserver
6 import matplotlib.pyplot
as plt
8 import pinocchio
as pin
9 import plot_utils
as plut
10 import ur5_conf
as conf
12 from numpy.linalg
import norm
as norm
16 print(
"".
center(conf.LINE_WIDTH,
"#"))
17 print(
" Joint Space Inverse Dynamics - Manipulator ".
center(conf.LINE_WIDTH,
"#"))
18 print(
"".
center(conf.LINE_WIDTH,
"#"),
"\n")
26 robot = tsid.RobotWrapper(conf.urdf, [conf.path],
False)
31 v0 = np.zeros(robot.nv)
32 formulation.computeProblemData(0.0, q0, v0)
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)
39 trajPosture = tsid.TrajectoryEuclidianConstant(
"traj_joint", q0)
40 postureTask.setReference(trajPosture.computeNext())
42 v_max = conf.v_max_scaling * model.velocityLimit
48 solver = tsid.SolverHQuadProgFast(
"qp solver")
49 solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)
52 robot_display = pin.RobotWrapper.BuildFromURDF(
58 n = subprocess.getstatusoutput(
"ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
60 os.system(
"gepetto-gui &")
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)
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()
80 amp = np.array([0.2, 0.3, 0.4, 0.0, 0.0, 0.0])
81 phi = np.array([0.0, 0.5 * np.pi, 0.0, 0.0, 0.0, 0.0])
82 two_pi_f = 2 * np.pi * np.array([1.0, 0.5, 0.3, 0.0, 0.0, 0.0])
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)
88 q[:, 0], v[:, 0] = q0, v0
91 time_start = time.time()
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)
102 HQPData = formulation.computeProblemData(t, q[:, i], v[:, i])
103 sol = solver.solve(HQPData)
105 print(f
"Time {t:.3f} QP problem could not be solved! Error code:", sol.status)
108 tau[:, i] = formulation.getActuatorForces(sol)
109 dv[:, i] = formulation.getAccelerations(sol)
110 dv_des[:, i] = postureTask.getDesiredAcceleration
112 if i % conf.PRINT_N == 0:
113 print(f
"Time {t:.3f}")
115 "\ttracking err {}: {:.3f}".format(
116 postureTask.name.ljust(20,
"."), norm(postureTask.position_error, 2)
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)
126 if i % conf.DISPLAY_N == 0:
127 robot_display.display(q[:, i])
129 time_spent = time.time() - time_start
130 if time_spent < conf.dt:
131 time.sleep(conf.dt - time_spent)
134 time = np.arange(0.0, N * conf.dt, conf.dt)
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]")
145 leg.get_frame().set_alpha(0.5)
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]")
158 leg.get_frame().set_alpha(0.5)
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]")
170 leg.get_frame().set_alpha(0.5)
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]")
180 leg.get_frame().set_alpha(0.5)