4 import pinocchio
as pin
5 from display
import Display
6 from numpy.linalg
import norm, pinv
12 Class representing one 3D mesh of the robot, to be attached to a joint. The class
14 * the name of the 3D objects inside Gepetto viewer.
15 * the ID of the joint in the kinematic tree to which the body is attached.
16 * the placement of the body with respect to the joint frame.
17 This class is only used in the list Robot.visuals (see below).
19 The visual are supposed mostly to be capsules. In that case, the object also
20 contains radius and length of the capsule.
21 The collision checking computes collision test, distance, and witness points.
22 Using the supporting robot, the collision Jacobian returns a 1xN matrix
23 corresponding to the normal direction.
26 def __init__(self, name, jointParent, placement, radius=0.1, length=None):
27 """Length and radius are used in case of capsule objects"""
31 if length
is not None:
35 def place(self, display, oMjoint):
37 display.place(self.
name, oMbody,
False)
40 return hasattr(self,
"length")
and hasattr(self,
"radius")
42 def collision(self, c2, data=None, oMj1=None, oMj2=None):
45 oMj2 = data.oMi[c2.jointParent]
47 M2 = oMj2 * c2.placement
48 assert self.
isCapsule()
and c2.isCapsule()
54 a1 = M1.act(np.array([0, 0, -l1 / 2]))
55 b1 = M2.act(np.array([0, 0, -l2 / 2]))
56 a2 = M1.act(np.array([0, 0, +l1 / 2]))
57 b2 = M2.act(np.array([0, 0, +l2 / 2]))
59 a1a2_b1b2 = np.array([a1 - a2, b1 - b2]).T
60 ab = pinv(a1a2_b1b2) * (b2 - a2)
62 if (0 <= ab).all()
and (ab <= 1).all():
64 pa = a2 + ab[0, 0] * (a1 - a2)
65 pb = b2 + ab[1, 0] * (b1 - b2)
68 i = np.argmin(np.vstack([ab, 1 - ab]))
70 pa = a2
if i == 0
else a1
71 pb = b2
if i == 1
else b1
73 b = (pinv((b1 - b2).reshape(3, 1)) * (pa - b2))[0, 0]
79 pb = b2 + b * (b1 - b2)
82 a = (pinv((a1 - a2).reshape(3, 1)) * (pb - a2))[0, 0]
88 pa = a2 + a * (a1 - a2)
92 dist = norm(pa - pb) - (r1 + r2)
93 if norm(pa - pb) > 1e-3:
101 x = np.array([1.0, 0, 0])
104 x = np.array([0, 1.0, 0])
108 R = np.hstack([r1, r2, ab.reshape(3, 1)])
120 Ja = pin.jacobian(robot.model, robot.data, q, self.
jointParent,
False,
True)
121 Jb = pin.jacobian(robot.model, robot.data, q, c2.jointParent,
False,
True)
123 Xa = pin.SE3(self.
R, self.
w).action
124 Xb = pin.SE3(c2.R, c2.w).action
126 J = (Xa * Ja)[2, :] - (Xb * Jb)[2, :]
130 viewer.viewer.gui.setVisibility(name,
"ON")
131 viewer.place(name, pin.SE3(self.
R, self.
w))
136 Define a class Robot with 7DOF (shoulder=3 + elbow=1 + wrist=3).
137 The configuration is nq=7. The velocity is the same.
138 The members of the class are:
139 * viewer: a display encapsulating a gepetto viewer client to create 3D objects and
141 * model: the kinematic tree of the robot.
142 * data: the temporary variables to be used by the kinematic algorithms.
143 * visuals: the list of all the 'visual' 3D objects to render the robot, each element
144 of the list being an object Visual (see above).
146 CollisionPairs is a list of visual indexes.
147 Reference to the collision pair is used in the collision test and jacobian of the
148 collision (which are simply proxy method to methods of the visual class).
162 def createHand(self, root_id=0, prefix="", joint_placement=None):
164 return pin.SE3(
eye(3), np.array([x, y, z]))
167 return pin.Inertia(m, np.array(c, np.double),
eye(3) * m**2)
170 return prefix + body +
"_joint"
173 return "world/" + prefix + body
175 color = [red, green, blue, transparency] = [1, 1, 0.78, 1.0]
180 joint_placement
if joint_placement
is not None else pin.SE3.Identity()
182 joint_id = self.
model.addJoint(
183 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"wrist")
185 self.
model.appendBodyToJoint(
186 joint_id, inertia(3, [0, 0, 0]), pin.SE3.Identity()
189 L, W, H = 3 * cm, 5 * cm, 1 * cm
190 self.
viewer.viewer.gui.addSphere(body_name(
"wrist"), 0.02, color)
191 self.
viewer.viewer.gui.addBox(body_name(
"wpalm"), L / 2, W / 2, H, color)
194 self.
viewer.viewer.gui.addCapsule(body_name(
"wpalmb"), H, W, color)
199 pin.SE3(rotate(
"x", pi / 2),
zero(3)),
205 self.
viewer.viewer.gui.addCapsule(body_name(
"wpalmt"), H, W, color)
206 pos = pin.SE3(rotate(
"x", pi / 2), np.array([L, 0, 0]))
209 self.
viewer.viewer.gui.addCapsule(body_name(
"wpalml"), H, L, color)
210 pos = pin.SE3(rotate(
"y", pi / 2), np.array([L / 2, -W / 2, 0]))
213 self.
viewer.viewer.gui.addCapsule(body_name(
"wpalmr"), H, L, color)
214 pos = pin.SE3(rotate(
"y", pi / 2), np.array([L / 2, +W / 2, 0]))
217 joint_placement = pin.SE3(
eye(3), np.array([5 * cm, 0, 0]))
218 joint_id = self.
model.addJoint(
219 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"palm")
221 self.
model.appendBodyToJoint(
222 joint_id, inertia(2, [0, 0, 0]), pin.SE3.Identity()
224 self.
viewer.viewer.gui.addCapsule(body_name(
"palm2"), 1 * cm, W, color)
229 pin.SE3(rotate(
"x", pi / 2),
zero(3)),
238 joint_placement = pin.SE3(
eye(3), np.array([2 * cm, W / 2, 0]))
239 joint_id = self.
model.addJoint(
240 palmIdx, pin.JointModelRY(), joint_placement,
joint_name(
"finger11")
242 self.
model.appendBodyToJoint(
243 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
245 self.
viewer.viewer.gui.addCapsule(body_name(
"finger11"), H, FL - 2 * H, color)
246 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
249 joint_placement = pin.SE3(
eye(3), np.array([FL, 0, 0]))
250 joint_id = self.
model.addJoint(
251 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger12")
253 self.
model.appendBodyToJoint(
254 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
257 self.
viewer.viewer.gui.addCapsule(body_name(
"finger12"), H, FL - 2 * H, color)
258 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
261 joint_placement = pin.SE3(
eye(3), np.array([FL - 2 * H, 0, 0]))
262 joint_id = self.
model.addJoint(
263 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger13")
265 self.
model.appendBodyToJoint(
266 joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
268 self.
viewer.viewer.gui.addSphere(body_name(
"finger13"), H, color)
270 Visual(body_name(
"finger13"), joint_id, trans(2 * H, 0, 0), H, 0)
273 joint_placement = pin.SE3(
eye(3), np.array([2 * cm, 0, 0]))
274 joint_id = self.
model.addJoint(
275 palmIdx, pin.JointModelRY(), joint_placement,
joint_name(
"finger21")
277 self.
model.appendBodyToJoint(
278 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
280 self.
viewer.viewer.gui.addCapsule(body_name(
"finger21"), H, FL - 2 * H, color)
281 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
284 joint_placement = pin.SE3(
eye(3), np.array([FL, 0, 0]))
285 joint_id = self.
model.addJoint(
286 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger22")
288 self.
model.appendBodyToJoint(
289 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
291 self.
viewer.viewer.gui.addCapsule(body_name(
"finger22"), H, FL - 2 * H, color)
292 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
295 joint_placement = pin.SE3(
eye(3), np.array([FL - H, 0, 0]))
296 joint_id = self.
model.addJoint(
297 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger23")
299 self.
model.appendBodyToJoint(
300 joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
302 self.
viewer.viewer.gui.addSphere(body_name(
"finger23"), H, color)
304 Visual(body_name(
"finger23"), joint_id, trans(H, 0, 0), H, 0)
307 joint_placement = pin.SE3(
eye(3), np.array([2 * cm, -W / 2, 0]))
308 joint_id = self.
model.addJoint(
309 palmIdx, pin.JointModelRY(), joint_placement,
joint_name(
"finger31")
311 self.
model.appendBodyToJoint(
312 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
314 self.
viewer.viewer.gui.addCapsule(body_name(
"finger31"), H, FL - 2 * H, color)
315 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
318 joint_placement = pin.SE3(
eye(3), np.array([FL, 0, 0]))
319 joint_id = self.
model.addJoint(
320 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger32")
322 self.
model.appendBodyToJoint(
323 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
325 self.
viewer.viewer.gui.addCapsule(body_name(
"finger32"), H, FL - 2 * H, color)
326 pos = pin.SE3(rotate(
"y", pi / 2), np.array([FL / 2 - H, 0, 0]))
329 joint_placement = pin.SE3(
eye(3), np.array([FL - 2 * H, 0, 0]))
330 joint_id = self.
model.addJoint(
331 joint_id, pin.JointModelRY(), joint_placement,
joint_name(
"finger33")
333 self.
model.appendBodyToJoint(
334 joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
336 self.
viewer.viewer.gui.addSphere(body_name(
"finger33"), H, color)
338 Visual(body_name(
"finger33"), joint_id, trans(2 * H, 0, 0), H, 0)
341 joint_placement = pin.SE3(
eye(3), np.array([1 * cm, -W / 2 - H * 1.5, 0]))
342 joint_id = self.
model.addJoint(
343 1, pin.JointModelRY(), joint_placement,
joint_name(
"thumb1")
345 self.
model.appendBodyToJoint(
346 joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
348 self.
viewer.viewer.gui.addCapsule(body_name(
"thumb1"), H, 2 * cm, color)
350 rotate(
"z", pi / 3) * rotate(
"x", pi / 2), np.array([1 * cm, -1 * cm, 0])
354 joint_placement = pin.SE3(
355 rotate(
"z", pi / 3) * rotate(
"x", pi), np.array([3 * cm, -1.8 * cm, 0])
357 joint_id = self.
model.addJoint(
358 joint_id, pin.JointModelRZ(), joint_placement,
joint_name(
"thumb2")
360 self.
model.appendBodyToJoint(
361 joint_id, inertia(0.4, [0, 0, 0]), pin.SE3.Identity()
363 self.
viewer.viewer.gui.addCapsule(body_name(
"thumb2"), H, FL - 2 * H, color)
364 pos = pin.SE3(rotate(
"x", pi / 3), np.array([-0.7 * cm, 0.8 * cm, -0.5 * cm]))
369 self.
viewer.viewer.gui.addCylinder(
370 "world/wa%i" % i, 0.01, 0.003, [1.0, 0, 0, 1]
372 self.
viewer.viewer.gui.addCylinder(
373 "world/wb%i" % i, 0.01, 0.003, [1.0, 0, 0, 1]
375 self.
viewer.viewer.gui.setVisibility(
"world/wa%i" % i,
"OFF")
376 self.
viewer.viewer.gui.setVisibility(
"world/wb%i" % i,
"OFF")
382 dist = va.collision(vb, self.
data)
389 return va.jacobian(vb, self, q)
395 va.displayCollision(self.
viewer,
"world/wa%i" % meshIndex)
396 vb.displayCollision(self.
viewer,
"world/wb%i" % meshIndex)
397 self.
viewer.viewer.gui.setVisibility(
"world/wa%i" % meshIndex,
"ON")
398 self.
viewer.viewer.gui.setVisibility(
"world/wb%i" % meshIndex,
"ON")
401 pin.forwardKinematics(self.
model, self.
data, q)
403 visual.place(self.
viewer, self.
data.oMi[visual.jointParent])
404 self.
viewer.viewer.gui.refresh()