robot_hand.py
Go to the documentation of this file.
1 from math import pi
2 
3 import numpy as np
4 import pinocchio as pin
5 from display import Display
6 from numpy.linalg import norm, pinv
7 from pinocchio.utils import cross, eye, rotate, zero
8 
9 
10 class Visual:
11  """
12  Class representing one 3D mesh of the robot, to be attached to a joint. The class
13  contains:
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).
18 
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.
24  """
25 
26  def __init__(self, name, jointParent, placement, radius=0.1, length=None):
27  """Length and radius are used in case of capsule objects"""
28  self.name = name # Name in gepetto viewer
29  self.jointParent = jointParent # ID (int) of the joint
30  self.placement = placement # placement of the body wrt joint, i.e. bodyMjoint
31  if length is not None:
32  self.length = length
33  self.radius = radius
34 
35  def place(self, display, oMjoint):
36  oMbody = oMjoint * self.placement
37  display.place(self.name, oMbody, False)
38 
39  def isCapsule(self):
40  return hasattr(self, "length") and hasattr(self, "radius")
41 
42  def collision(self, c2, data=None, oMj1=None, oMj2=None):
43  if data is not None:
44  oMj1 = data.oMi[self.jointParent]
45  oMj2 = data.oMi[c2.jointParent]
46  M1 = oMj1 * self.placement
47  M2 = oMj2 * c2.placement
48  assert self.isCapsule() and c2.isCapsule()
49  l1 = self.length
50  r1 = self.radius
51  l2 = c2.length
52  r2 = c2.radius
53 
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]))
58 
59  a1a2_b1b2 = np.array([a1 - a2, b1 - b2]).T
60  ab = pinv(a1a2_b1b2) * (b2 - a2)
61 
62  if (0 <= ab).all() and (ab <= 1).all():
63  asat = bsat = False
64  pa = a2 + ab[0, 0] * (a1 - a2)
65  pb = b2 + ab[1, 0] * (b1 - b2)
66  else:
67  asat = bsat = True
68  i = np.argmin(np.vstack([ab, 1 - ab]))
69 
70  pa = a2 if i == 0 else a1
71  pb = b2 if i == 1 else b1
72  if i == 0 or i == 2: # fix a to pa, search b
73  b = (pinv((b1 - b2).reshape(3, 1)) * (pa - b2))[0, 0]
74  if b < 0:
75  pb = b2
76  elif b > 1:
77  pb = b1
78  else:
79  pb = b2 + b * (b1 - b2)
80  bsat = False
81  else: # fix b
82  a = (pinv((a1 - a2).reshape(3, 1)) * (pb - a2))[0, 0]
83  if a < 0:
84  pa = a2
85  elif a > 1:
86  pa = a1
87  else:
88  pa = a2 + a * (a1 - a2)
89  asat = False
90 
91  print(asat, bsat)
92  dist = norm(pa - pb) - (r1 + r2)
93  if norm(pa - pb) > 1e-3:
94  # Compute witness points
95  ab = pa - pb
96  ab /= norm(ab)
97  wa = pa - ab * r1
98  wb = pb + ab * r2
99 
100  # Compute normal matrix
101  x = np.array([1.0, 0, 0])
102  r1 = cross(ab, x)
103  if norm(r1) < 1e-2:
104  x = np.array([0, 1.0, 0])
105  r1 = cross(ab, x)
106  r1 /= norm(r1)
107  r2 = cross(ab, r1)
108  R = np.hstack([r1, r2, ab.reshape(3, 1)])
109 
110  self.dist = dist
111  c2.dist = dist
112  self.w = wa
113  c2.w = wb
114  self.R = R
115  c2.R = R
116 
117  return dist
118 
119  def jacobian(self, c2, robot, q):
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)
122 
123  Xa = pin.SE3(self.R, self.w).action
124  Xb = pin.SE3(c2.R, c2.w).action
125 
126  J = (Xa * Ja)[2, :] - (Xb * Jb)[2, :]
127  return J
128 
129  def displayCollision(self, viewer, name="world/wa"):
130  viewer.viewer.gui.setVisibility(name, "ON")
131  viewer.place(name, pin.SE3(self.R, self.w))
132 
133 
134 class Robot:
135  """
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
140  place them.
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).
145 
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).
149  """
150 
151  def __init__(self):
152  self.viewer = Display()
153  self.visuals = []
154  self.model = pin.Model()
155  self.createHand()
156  self.data = self.model.createData()
157  self.q0 = zero(self.model.nq)
158  # self.q0[3] = 1.0
159  self.v0 = zero(self.model.nv)
160  self.collisionPairs = []
161 
162  def createHand(self, root_id=0, prefix="", joint_placement=None):
163  def trans(x, y, z):
164  return pin.SE3(eye(3), np.array([x, y, z]))
165 
166  def inertia(m, c):
167  return pin.Inertia(m, np.array(c, np.double), eye(3) * m**2)
168 
169  def joint_name(body):
170  return prefix + body + "_joint"
171 
172  def body_name(body):
173  return "world/" + prefix + body
174 
175  color = [red, green, blue, transparency] = [1, 1, 0.78, 1.0]
176  joint_id = root_id
177  cm = 1e-2
178 
179  joint_placement = (
180  joint_placement if joint_placement is not None else pin.SE3.Identity()
181  )
182  joint_id = self.model.addJoint(
183  joint_id, pin.JointModelRY(), joint_placement, joint_name("wrist")
184  )
185  self.model.appendBodyToJoint(
186  joint_id, inertia(3, [0, 0, 0]), pin.SE3.Identity()
187  )
188 
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)
192  self.visuals.append(Visual(body_name("wpalm"), joint_id, trans(L / 2, 0, 0)))
193 
194  self.viewer.viewer.gui.addCapsule(body_name("wpalmb"), H, W, color)
195  self.visuals.append(
196  Visual(
197  body_name("wpalmb"),
198  joint_id,
199  pin.SE3(rotate("x", pi / 2), zero(3)),
200  H,
201  W,
202  )
203  )
204 
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]))
207  self.visuals.append(Visual(body_name("wpalmt"), joint_id, pos, H, W))
208 
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]))
211  self.visuals.append(Visual(body_name("wpalml"), joint_id, pos, H, L))
212 
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]))
215  self.visuals.append(Visual(body_name("wpalmr"), joint_id, pos, H, L))
216 
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")
220  )
221  self.model.appendBodyToJoint(
222  joint_id, inertia(2, [0, 0, 0]), pin.SE3.Identity()
223  )
224  self.viewer.viewer.gui.addCapsule(body_name("palm2"), 1 * cm, W, color)
225  self.visuals.append(
226  Visual(
227  body_name("palm2"),
228  joint_id,
229  pin.SE3(rotate("x", pi / 2), zero(3)),
230  H,
231  W,
232  )
233  )
234 
235  FL = 4 * cm
236  palmIdx = joint_id
237 
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")
241  )
242  self.model.appendBodyToJoint(
243  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
244  )
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]))
247  self.visuals.append(Visual(body_name("finger11"), joint_id, pos, H, FL - 2 * H))
248 
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")
252  )
253  self.model.appendBodyToJoint(
254  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
255  )
256 
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]))
259  self.visuals.append(Visual(body_name("finger12"), joint_id, pos, H, FL - 2 * H))
260 
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")
264  )
265  self.model.appendBodyToJoint(
266  joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
267  )
268  self.viewer.viewer.gui.addSphere(body_name("finger13"), H, color)
269  self.visuals.append(
270  Visual(body_name("finger13"), joint_id, trans(2 * H, 0, 0), H, 0)
271  )
272 
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")
276  )
277  self.model.appendBodyToJoint(
278  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
279  )
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]))
282  self.visuals.append(Visual(body_name("finger21"), joint_id, pos, H, FL - 2 * H))
283 
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")
287  )
288  self.model.appendBodyToJoint(
289  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
290  )
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]))
293  self.visuals.append(Visual(body_name("finger22"), joint_id, pos, H, FL - 2 * H))
294 
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")
298  )
299  self.model.appendBodyToJoint(
300  joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
301  )
302  self.viewer.viewer.gui.addSphere(body_name("finger23"), H, color)
303  self.visuals.append(
304  Visual(body_name("finger23"), joint_id, trans(H, 0, 0), H, 0)
305  )
306 
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")
310  )
311  self.model.appendBodyToJoint(
312  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
313  )
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]))
316  self.visuals.append(Visual(body_name("finger31"), joint_id, pos, H, FL - 2 * H))
317 
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")
321  )
322  self.model.appendBodyToJoint(
323  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
324  )
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]))
327  self.visuals.append(Visual(body_name("finger32"), joint_id, pos, H, FL - 2 * H))
328 
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")
332  )
333  self.model.appendBodyToJoint(
334  joint_id, inertia(0.3, [0, 0, 0]), pin.SE3.Identity()
335  )
336  self.viewer.viewer.gui.addSphere(body_name("finger33"), H, color)
337  self.visuals.append(
338  Visual(body_name("finger33"), joint_id, trans(2 * H, 0, 0), H, 0)
339  )
340 
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")
344  )
345  self.model.appendBodyToJoint(
346  joint_id, inertia(0.5, [0, 0, 0]), pin.SE3.Identity()
347  )
348  self.viewer.viewer.gui.addCapsule(body_name("thumb1"), H, 2 * cm, color)
349  pos = pin.SE3(
350  rotate("z", pi / 3) * rotate("x", pi / 2), np.array([1 * cm, -1 * cm, 0])
351  )
352  self.visuals.append(Visual(body_name("thumb1"), joint_id, pos, 2 * cm))
353 
354  joint_placement = pin.SE3(
355  rotate("z", pi / 3) * rotate("x", pi), np.array([3 * cm, -1.8 * cm, 0])
356  )
357  joint_id = self.model.addJoint(
358  joint_id, pin.JointModelRZ(), joint_placement, joint_name("thumb2")
359  )
360  self.model.appendBodyToJoint(
361  joint_id, inertia(0.4, [0, 0, 0]), pin.SE3.Identity()
362  )
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]))
365  self.visuals.append(Visual(body_name("thumb2"), joint_id, pos, H, FL - 2 * H))
366 
367  # Prepare some patches to represent collision points. Yet unvisible.
368  for i in range(10):
369  self.viewer.viewer.gui.addCylinder(
370  "world/wa%i" % i, 0.01, 0.003, [1.0, 0, 0, 1]
371  )
372  self.viewer.viewer.gui.addCylinder(
373  "world/wb%i" % i, 0.01, 0.003, [1.0, 0, 0, 1]
374  )
375  self.viewer.viewer.gui.setVisibility("world/wa%i" % i, "OFF")
376  self.viewer.viewer.gui.setVisibility("world/wb%i" % i, "OFF")
377 
378  def checkCollision(self, pairIndex):
379  ia, ib = self.collisionPairs[pairIndex]
380  va = self.visuals[ia]
381  vb = self.visuals[ib]
382  dist = va.collision(vb, self.data)
383  return dist
384 
385  def collisionJacobian(self, pairIndex, q):
386  ia, ib = self.collisionPairs[pairIndex]
387  va = self.visuals[ia]
388  vb = self.visuals[ib]
389  return va.jacobian(vb, self, q)
390 
391  def displayCollision(self, pairIndex, meshIndex, onlyOne=False):
392  ia, ib = self.collisionPairs[pairIndex]
393  va = self.visuals[ia]
394  vb = self.visuals[ib]
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")
399 
400  def display(self, q):
401  pin.forwardKinematics(self.model, self.data, q)
402  for visual in self.visuals:
403  visual.place(self.viewer, self.data.oMi[visual.jointParent])
404  self.viewer.viewer.gui.refresh()
robot_hand.Visual.displayCollision
def displayCollision(self, viewer, name="world/wa")
Definition: robot_hand.py:129
robot_hand.Visual.radius
radius
Definition: robot_hand.py:33
robot_hand.Robot.collisionJacobian
def collisionJacobian(self, pairIndex, q)
Definition: robot_hand.py:385
robot_hand.Robot.checkCollision
def checkCollision(self, pairIndex)
Definition: robot_hand.py:378
robot_hand.Robot.viewer
viewer
Definition: robot_hand.py:152
display.Display
Definition: display.py:8
robot_hand.Visual
Definition: robot_hand.py:10
robot_hand.Visual.name
name
Definition: robot_hand.py:28
robot_hand.Visual.w
w
Definition: robot_hand.py:112
robot_hand.Robot.model
model
Definition: robot_hand.py:154
robot_hand.Robot.v0
v0
Definition: robot_hand.py:159
robot_hand.Visual.jacobian
def jacobian(self, c2, robot, q)
Definition: robot_hand.py:119
robot_hand.Visual.placement
placement
Definition: robot_hand.py:30
robot_hand.Robot.data
data
Definition: robot_hand.py:156
robot_hand.Robot
Definition: robot_hand.py:134
pinocchio.utils
Definition: bindings/python/pinocchio/utils.py:1
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:239
robot_hand.Visual.R
R
Definition: robot_hand.py:114
robot_hand.Visual.isCapsule
def isCapsule(self)
Definition: robot_hand.py:39
robot_hand.Robot.createHand
def createHand(self, root_id=0, prefix="", joint_placement=None)
Definition: robot_hand.py:162
pinocchio.utils.eye
def eye(n)
Definition: bindings/python/pinocchio/utils.py:32
robot_hand.Robot.displayCollision
def displayCollision(self, pairIndex, meshIndex, onlyOne=False)
Definition: robot_hand.py:391
robot_hand.Robot.__init__
def __init__(self)
Definition: robot_hand.py:151
robot_hand.Visual.length
length
Definition: robot_hand.py:32
append-urdf-model-with-another-model.joint_name
string joint_name
Definition: append-urdf-model-with-another-model.py:32
robot_hand.Visual.dist
dist
Definition: robot_hand.py:110
robot_hand.Visual.collision
def collision(self, c2, data=None, oMj1=None, oMj2=None)
Definition: robot_hand.py:42
robot_hand.Robot.display
def display(self, q)
Definition: robot_hand.py:400
pinocchio::cross
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
Definition: skew.hpp:228
boost::fusion::append
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:32
robot_hand.Visual.__init__
def __init__(self, name, jointParent, placement, radius=0.1, length=None)
Definition: robot_hand.py:26
robot_hand.Robot.q0
q0
Definition: robot_hand.py:157
robot_hand.Robot.visuals
visuals
Definition: robot_hand.py:153
pinocchio.utils.zero
def zero(n)
Definition: bindings/python/pinocchio/utils.py:37
robot_hand.Visual.jointParent
jointParent
Definition: robot_hand.py:29
robot_hand.Robot.collisionPairs
collisionPairs
Definition: robot_hand.py:160
robot_hand.Visual.place
def place(self, display, oMjoint)
Definition: robot_hand.py:35


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:48